Browse Source

End action only supports RTL

QGC4.4
DonLakeFlyer 8 years ago
parent
commit
6e2efab73a
  1. 8
      src/MissionManager/MissionSettings.FactMetaData.json
  2. 53
      src/MissionManager/MissionSettingsItem.cc
  3. 16
      src/MissionManager/MissionSettingsItem.h
  4. 9
      src/PlanView/MissionSettingsEditor.qml

8
src/MissionManager/MissionSettings.FactMetaData.json

@ -6,13 +6,5 @@ @@ -6,13 +6,5 @@
"units": "m",
"decimalPlaces": 1,
"defaultValue": 0
},
{
"name": "MissionEndAction",
"shortDescription": "The action to take when the mission completed.",
"type": "uint32",
"enumStrings": "No action on mission end,Loiter after mission end,RTL after mission end",
"enumValues": "0,1,2",
"defaultValue": 0
}
]

53
src/MissionManager/MissionSettingsItem.cc

@ -24,14 +24,13 @@ QGC_LOGGING_CATEGORY(MissionSettingsComplexItemLog, "MissionSettingsComplexItemL @@ -24,14 +24,13 @@ QGC_LOGGING_CATEGORY(MissionSettingsComplexItemLog, "MissionSettingsComplexItemL
const char* MissionSettingsItem::jsonComplexItemTypeValue = "MissionSettings";
const char* MissionSettingsItem::_plannedHomePositionAltitudeName = "PlannedHomePositionAltitude";
const char* MissionSettingsItem::_missionEndActionName = "MissionEndAction";
QMap<QString, FactMetaData*> MissionSettingsItem::_metaDataMap;
MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent)
: ComplexMissionItem (vehicle, parent)
, _plannedHomePositionAltitudeFact (0, _plannedHomePositionAltitudeName, FactMetaData::valueTypeDouble)
, _missionEndActionFact (0, _missionEndActionName, FactMetaData::valueTypeUint32)
, _missionEndRTL (false)
, _cameraSection (vehicle)
, _speedSection (vehicle)
, _sequenceNumber (0)
@ -44,21 +43,19 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent) @@ -44,21 +43,19 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent)
}
_plannedHomePositionAltitudeFact.setMetaData (_metaDataMap[_plannedHomePositionAltitudeName]);
_missionEndActionFact.setMetaData (_metaDataMap[_missionEndActionName]);
_plannedHomePositionAltitudeFact.setRawValue (_plannedHomePositionAltitudeFact.rawDefaultValue());
_missionEndActionFact.setRawValue (_missionEndActionFact.rawDefaultValue());
setHomePositionSpecialCase(true);
connect(this, &MissionSettingsItem::specifyMissionFlightSpeedChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
connect(this, &MissionSettingsItem::missionEndRTLChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
connect(&_cameraSection, &CameraSection::itemCountChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
connect(&_speedSection, &CameraSection::itemCountChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
connect(&_plannedHomePositionAltitudeFact, &Fact::valueChanged, this, &MissionSettingsItem::_setDirty);
connect(&_plannedHomePositionAltitudeFact, &Fact::valueChanged, this, &MissionSettingsItem::_updateAltitudeInCoordinate);
connect(&_missionEndActionFact, &Fact::valueChanged, this, &MissionSettingsItem::_setDirty);
connect(&_plannedHomePositionAltitudeFact, &Fact::valueChanged, this, &MissionSettingsItem::_updateAltitudeInCoordinate);
connect(&_cameraSection, &CameraSection::dirtyChanged, this, &MissionSettingsItem::_sectionDirtyChanged);
connect(&_speedSection, &SpeedSection::dirtyChanged, this, &MissionSettingsItem::_sectionDirtyChanged);
@ -184,23 +181,7 @@ bool MissionSettingsItem::addMissionEndAction(QList<MissionItem*>& items, int se @@ -184,23 +181,7 @@ bool MissionSettingsItem::addMissionEndAction(QList<MissionItem*>& items, int se
return false;
}
switch(_missionEndActionFact.rawValue().toInt()) {
case MissionEndLoiter:
qCDebug(MissionSettingsComplexItemLog) << "Appending end action Loiter seqNum" << seqNum;
item = new MissionItem(seqNum,
MAV_CMD_NAV_LOITER_UNLIM,
lastWaypointFrame,
0, 0, // param 1-2 unused
0, // use default loiter radius
0, // param 4 not used
lastWaypointCoord.latitude(),
lastWaypointCoord.longitude(),
lastWaypointCoord.altitude(),
true, // autoContinue
false, // isCurrentItem
missionItemParent);
break;
case MissionEndRTL:
if (_missionEndRTL) {
qCDebug(MissionSettingsComplexItemLog) << "Appending end action RTL seqNum" << seqNum;
item = new MissionItem(seqNum,
MAV_CMD_NAV_RETURN_TO_LAUNCH,
@ -209,12 +190,6 @@ bool MissionSettingsItem::addMissionEndAction(QList<MissionItem*>& items, int se @@ -209,12 +190,6 @@ bool MissionSettingsItem::addMissionEndAction(QList<MissionItem*>& items, int se
true, // autoContinue
false, // isCurrentItem
missionItemParent);
break;
default:
break;
}
if (item) {
items.append(item);
return true;
} else {
@ -248,26 +223,12 @@ bool MissionSettingsItem::scanForMissionSettings(QmlObjectListModel* visualItems @@ -248,26 +223,12 @@ bool MissionSettingsItem::scanForMissionSettings(QmlObjectListModel* visualItems
if (item) {
MissionItem& missionItem = item->missionItem();
switch ((MAV_CMD)item->command()) {
case MAV_CMD_NAV_LOITER_UNLIM:
if (missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0) {
qCDebug(MissionSettingsComplexItemLog) << "Scan: Found end action Loiter";
settingsItem->missionEndAction()->setRawValue(MissionEndLoiter);
visualItems->removeAt(lastIndex)->deleteLater();
}
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
if (missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
if (item->command() == MAV_CMD_NAV_RETURN_TO_LAUNCH &&
missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
qCDebug(MissionSettingsComplexItemLog) << "Scan: Found end action RTL";
settingsItem->missionEndAction()->setRawValue(MissionEndRTL);
settingsItem->_missionEndRTL = true;
visualItems->removeAt(lastIndex)->deleteLater();
}
break;
default:
break;
}
}
return foundSpeedSection || foundCameraSection;

16
src/MissionManager/MissionSettingsItem.h

@ -26,20 +26,12 @@ class MissionSettingsItem : public ComplexMissionItem @@ -26,20 +26,12 @@ class MissionSettingsItem : public ComplexMissionItem
public:
MissionSettingsItem(Vehicle* vehicle, QObject* parent = NULL);
enum MissionEndAction {
MissionEndNoAction,
MissionEndLoiter,
MissionEndRTL
};
Q_ENUMS(MissionEndAction)
Q_PROPERTY(Fact* missionEndAction READ missionEndAction CONSTANT)
Q_PROPERTY(Fact* plannedHomePositionAltitude READ plannedHomePositionAltitude CONSTANT)
Q_PROPERTY(bool missionEndRTL MEMBER _missionEndRTL NOTIFY missionEndRTLChanged)
Q_PROPERTY(QObject* cameraSection READ cameraSection CONSTANT)
Q_PROPERTY(QObject* speedSection READ speedSection CONSTANT)
Fact* plannedHomePositionAltitude (void) { return &_plannedHomePositionAltitudeFact; }
Fact* missionEndAction (void) { return &_missionEndActionFact; }
QObject* cameraSection(void) { return &_cameraSection; }
QObject* speedSection(void) { return &_speedSection; }
@ -93,6 +85,7 @@ public: @@ -93,6 +85,7 @@ public:
signals:
void specifyMissionFlightSpeedChanged (bool specifyMissionFlightSpeed);
void missionEndRTLChanged (bool missionEndRTL);
private slots:
void _setDirtyAndUpdateLastSequenceNumber (void);
@ -101,9 +94,9 @@ private slots: @@ -101,9 +94,9 @@ private slots:
void _updateAltitudeInCoordinate (QVariant value);
private:
QGeoCoordinate _plannedHomePositionCoordinate; // Does not include altitde
QGeoCoordinate _plannedHomePositionCoordinate; // Does not include altitude
Fact _plannedHomePositionAltitudeFact;
Fact _missionEndActionFact;
bool _missionEndRTL;
CameraSection _cameraSection;
SpeedSection _speedSection;
@ -113,7 +106,6 @@ private: @@ -113,7 +106,6 @@ private:
static QMap<QString, FactMetaData*> _metaDataMap;
static const char* _plannedHomePositionAltitudeName;
static const char* _missionEndActionName;
};
#endif

9
src/PlanView/MissionSettingsEditor.qml

@ -124,11 +124,10 @@ Rectangle { @@ -124,11 +124,10 @@ Rectangle {
}
} // GridLayout
FactComboBox {
anchors.left: parent.left
anchors.right: parent.right
fact: missionItem.missionEndAction
indexModel: false
QGCCheckBox {
text: qsTr("RTL after mission end")
checked: missionItem.missionEndRTL
onClicked: missionItem.missionEndRTL = checked
}
}

Loading…
Cancel
Save