7const char* SpeedSection::_flightSpeedName =
"FlightSpeed";
9QMap<QString, FactMetaData*> SpeedSection::_metaDataMap;
12 :
Section (masterController, parent)
15 , _specifyFlightSpeed (false)
16 , _flightSpeedFact (0, _flightSpeedName,
FactMetaData::valueTypeDouble)
18 if (_metaDataMap.isEmpty()) {
29 _metaDataMap[_flightSpeedName]->setRawDefaultValue(
flightSpeed);
30 _flightSpeedFact.setMetaData(_metaDataMap[_flightSpeedName]);
34 connect(&_flightSpeedFact, &
Fact::valueChanged,
this, &SpeedSection::_flightSpeedChanged);
37 connect(&_flightSpeedFact, &
Fact::valueChanged,
this, &SpeedSection::_updateSpecifiedFlightSpeed);
42 return _specifyFlightSpeed;
57 if (_dirty !=
dirty) {
65 if (specifyFlightSpeed != _specifyFlightSpeed) {
66 _specifyFlightSpeed = specifyFlightSpeed;
75 return _specifyFlightSpeed ? 1: 0;
82 if (_specifyFlightSpeed) {
84 MAV_CMD_DO_CHANGE_SPEED,
87 _flightSpeedFact.rawValue().toDouble(),
100 if (!_available || scanIndex >= visualItems->
count()) {
113 if (missionItem.
command() == MAV_CMD_DO_CHANGE_SPEED && missionItem.
param3() == -1 && missionItem.
param4() == 0 && missionItem.
param5() == 0 && missionItem.
param6() == 0 && missionItem.
param7() == 0) {
119 visualItems->
removeAt(scanIndex)->deleteLater();
120 _flightSpeedFact.setRawValue(missionItem.
param2());
131 return _specifyFlightSpeed ? _flightSpeedFact.rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
134void SpeedSection::_updateSpecifiedFlightSpeed(
void)
136 if (_specifyFlightSpeed) {
141void SpeedSection::_flightSpeedChanged(
void)
145 if (_specifyFlightSpeed) {
void valueChanged(const QVariant &value)
This signal is only meant for use by the QT property system. It should not be connected to by client ...
MAV_CMD command(void) const
double param5(void) const
double param7(void) const
double param3(void) const
double param6(void) const
double param1(void) const
double param4(void) const
double param2(void) const
Master controller for mission, fence, rally.
Vehicle * controllerVehicle(void)
QObject * removeAt(int index)
int count() const override final
void dirtyChanged(bool dirty)
PlanMasterController * _masterController
void itemCountChanged(int itemCount)
bool available READ available WRITE setAvailable NOTIFY availableChanged(bool settingsSpecified READ settingsSpecified NOTIFY settingsSpecifiedChanged) 1(bool dirty READ dirty WRITE setDirty NOTIFY availableChanged) virtual bool available(void) const =0
void settingsSpecifiedChanged(bool settingsSpecified)
A SimpleMissionItem is used to represent a single MissionItem to the ui.
MissionItem & missionItem(void)
bool dirty(void) const override
void setAvailable(bool available) override
double specifiedFlightSpeed(void) const
int itemCount(void) const override
SpeedSection(PlanMasterController *masterController, QObject *parent=nullptr)
void specifiedFlightSpeedChanged(double flightSpeed)
void setSpecifyFlightSpeed(bool specifyFlightSpeed)
void appendSectionItems(QList< MissionItem * > &items, QObject *missionItemParent, int &seqNum) override
void setDirty(bool dirty) override
bool settingsSpecified(void) const override
bool specifyFlightSpeed READ specifyFlightSpeed WRITE setSpecifyFlightSpeed NOTIFY specifyFlightSpeedChanged(Fact *flightSpeed READ flightSpeed CONSTANT) bool specifyFlightSpeed(void) const
bool available(void) const override
bool scanForSection(QmlObjectListModel *visualItems, int scanIndex) override
double defaultHoverSpeed() const
double defaultCruiseSpeed() const