Unverified Commit 67f93cee authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #8586 from DonLakeFlyer/VTOLFixes

VTOL Fixes
parents 5b628000 259a1bcb
...@@ -25,7 +25,8 @@ ...@@ -25,7 +25,8 @@
{ {
"id": 22, "id": 22,
"comment": "MAV_CMD_NAV_TAKEOFF", "comment": "MAV_CMD_NAV_TAKEOFF",
"paramRemove": "1" "paramRemove": "1",
"description": "Hover straight up to specified altitude. Then travel to specified position."
} }
] ]
} }
...@@ -51,7 +51,7 @@ ...@@ -51,7 +51,7 @@
"decimalPlaces": 2 "decimalPlaces": 2
}, },
"param4": { "param4": {
"label": "Heading", "label": "Yaw",
"units": "deg", "units": "deg",
"nanUnchanged": true, "nanUnchanged": true,
"default": null, "default": null,
...@@ -73,7 +73,7 @@ ...@@ -73,7 +73,7 @@
"decimalPlaces": 2 "decimalPlaces": 2
}, },
"param4": { "param4": {
"label": "Heading", "label": "Yaw",
"units": "deg", "units": "deg",
"nanUnchanged": true, "nanUnchanged": true,
"default": null, "default": null,
...@@ -100,7 +100,7 @@ ...@@ -100,7 +100,7 @@
"decimalPlaces": 2 "decimalPlaces": 2
}, },
"param4": { "param4": {
"label": "Heading", "label": "Yaw",
"units": "deg", "units": "deg",
"nanUnchanged": true, "nanUnchanged": true,
"default": null, "default": null,
...@@ -128,7 +128,7 @@ ...@@ -128,7 +128,7 @@
"decimalPlaces": 2 "decimalPlaces": 2
}, },
"param4": { "param4": {
"label": "Heading", "label": "Yaw",
"units": "deg", "units": "deg",
"nanUnchanged": true, "nanUnchanged": true,
"default": null, "default": null,
...@@ -149,6 +149,7 @@ ...@@ -149,6 +149,7 @@
"friendlyName": "Land", "friendlyName": "Land",
"description": "Land vehicle at the specified location.", "description": "Land vehicle at the specified location.",
"specifiesCoordinate": true, "specifiesCoordinate": true,
"isLandCommand": true,
"friendlyEdit": true, "friendlyEdit": true,
"category": "Basic", "category": "Basic",
"param1": { "param1": {
...@@ -158,7 +159,7 @@ ...@@ -158,7 +159,7 @@
"decimalPlaces": 2 "decimalPlaces": 2
}, },
"param4": { "param4": {
"label": "Heading", "label": "Yaw",
"units": "deg", "units": "deg",
"nanUnchanged": true, "nanUnchanged": true,
"default": null, "default": null,
...@@ -169,7 +170,7 @@ ...@@ -169,7 +170,7 @@
"id": 22, "id": 22,
"rawName": "MAV_CMD_NAV_TAKEOFF", "rawName": "MAV_CMD_NAV_TAKEOFF",
"friendlyName": "Takeoff", "friendlyName": "Takeoff",
"description": "Take off from the ground and travel towards the specified position.", "description": "Launch from the ground and travel towards the specified takeoff position.",
"specifiesCoordinate": true, "specifiesCoordinate": true,
"friendlyEdit": true, "friendlyEdit": true,
"category": "Basic", "category": "Basic",
...@@ -180,7 +181,7 @@ ...@@ -180,7 +181,7 @@
"decimalPlaces": 2 "decimalPlaces": 2
}, },
"param4": { "param4": {
"label": "Heading", "label": "Yaw",
"units": "deg", "units": "deg",
"nanUnchanged": true, "nanUnchanged": true,
"default": null, "default": null,
...@@ -287,12 +288,12 @@ ...@@ -287,12 +288,12 @@
"id": 84, "id": 84,
"rawName": "MAV_CMD_NAV_VTOL_TAKEOFF", "rawName": "MAV_CMD_NAV_VTOL_TAKEOFF",
"friendlyName": "VTOL takeoff", "friendlyName": "VTOL takeoff",
"description": "Takeoff in VTOL mode, transition to forward flight and fly to the specified location.", "description": "Hover straight up to specified altitude, transition to fixed-wing and fly to the specified takeoff location.",
"specifiesCoordinate": true, "specifiesCoordinate": true,
"friendlyEdit": true, "friendlyEdit": true,
"category": "VTOL", "category": "Basic",
"param4": { "param4": {
"label": "Heading", "label": "Yaw",
"units": "deg", "units": "deg",
"nanUnchanged": true, "nanUnchanged": true,
"default": null, "default": null,
...@@ -302,13 +303,14 @@ ...@@ -302,13 +303,14 @@
{ {
"id": 85, "id": 85,
"rawName": "MAV_CMD_NAV_VTOL_LAND", "rawName": "MAV_CMD_NAV_VTOL_LAND",
"friendlyName": "VTOL transition and land", "friendlyName": "VTOL land",
"description": "Transition to VTOL mode and land.", "description": "Fly to specified location at current altitude, transition to multi-rotor and land.",
"specifiesCoordinate": true, "specifiesCoordinate": true,
"isLandCommand": true,
"friendlyEdit": true, "friendlyEdit": true,
"category": "VTOL", "category": "Basic",
"param4": { "param4": {
"label": "Heading", "label": "Yaw",
"units": "deg", "units": "deg",
"nanUnchanged": true, "nanUnchanged": true,
"default": null, "default": null,
...@@ -400,11 +402,11 @@ ...@@ -400,11 +402,11 @@
{ {
"id": 115, "id": 115,
"rawName": "MAV_CMD_CONDITION_YAW", "rawName": "MAV_CMD_CONDITION_YAW",
"friendlyName": "Wait for Heading", "friendlyName": "Wait for Yaw",
"description": "Delay the mission until the specified heading is reached.", "description": "Delay the mission until the specified yaw is reached.",
"category": "Conditionals", "category": "Conditionals",
"param1": { "param1": {
"label": "Heading", "label": "Yaw",
"units": "deg", "units": "deg",
"default": 0, "default": 0,
"decimalPlaces": 1 "decimalPlaces": 1
......
...@@ -37,6 +37,7 @@ const char* MissionCommandUIInfo::_rawNameJsonKey = "rawName"; ...@@ -37,6 +37,7 @@ const char* MissionCommandUIInfo::_rawNameJsonKey = "rawName";
const char* MissionCommandUIInfo::_standaloneCoordinateJsonKey = "standaloneCoordinate"; const char* MissionCommandUIInfo::_standaloneCoordinateJsonKey = "standaloneCoordinate";
const char* MissionCommandUIInfo::_specifiesCoordinateJsonKey = "specifiesCoordinate"; const char* MissionCommandUIInfo::_specifiesCoordinateJsonKey = "specifiesCoordinate";
const char* MissionCommandUIInfo::_specifiesAltitudeOnlyJsonKey = "specifiesAltitudeOnly"; const char* MissionCommandUIInfo::_specifiesAltitudeOnlyJsonKey = "specifiesAltitudeOnly";
const char* MissionCommandUIInfo::_isLandCommandJsonKey = "isLandCommand";
const char* MissionCommandUIInfo::_unitsJsonKey = "units"; const char* MissionCommandUIInfo::_unitsJsonKey = "units";
const char* MissionCommandUIInfo::_commentJsonKey = "comment"; const char* MissionCommandUIInfo::_commentJsonKey = "comment";
const char* MissionCommandUIInfo::_advancedCategory = "Advanced"; const char* MissionCommandUIInfo::_advancedCategory = "Advanced";
...@@ -164,6 +165,15 @@ bool MissionCommandUIInfo::specifiesAltitudeOnly(void) const ...@@ -164,6 +165,15 @@ bool MissionCommandUIInfo::specifiesAltitudeOnly(void) const
} }
} }
bool MissionCommandUIInfo::isLandCommand(void) const
{
if (_infoMap.contains(_isLandCommandJsonKey)) {
return _infoMap[_isLandCommandJsonKey].toBool();
} else {
return false;
}
}
void MissionCommandUIInfo::_overrideInfo(MissionCommandUIInfo* uiInfo) void MissionCommandUIInfo::_overrideInfo(MissionCommandUIInfo* uiInfo)
{ {
// Override info values // Override info values
...@@ -199,7 +209,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ ...@@ -199,7 +209,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
QStringList allKeys; QStringList allKeys;
allKeys << _idJsonKey << _rawNameJsonKey << _friendlyNameJsonKey << _descriptionJsonKey << _standaloneCoordinateJsonKey << _specifiesCoordinateJsonKey allKeys << _idJsonKey << _rawNameJsonKey << _friendlyNameJsonKey << _descriptionJsonKey << _standaloneCoordinateJsonKey << _specifiesCoordinateJsonKey
<<_friendlyEditJsonKey << _param1JsonKey << _param2JsonKey << _param3JsonKey << _param4JsonKey << _param5JsonKey << _param6JsonKey << _param7JsonKey <<_friendlyEditJsonKey << _param1JsonKey << _param2JsonKey << _param3JsonKey << _param4JsonKey << _param5JsonKey << _param6JsonKey << _param7JsonKey
<< _paramRemoveJsonKey << _categoryJsonKey << _specifiesAltitudeOnlyJsonKey; << _paramRemoveJsonKey << _categoryJsonKey << _specifiesAltitudeOnlyJsonKey << _isLandCommandJsonKey;
// Look for unknown keys in top level object // Look for unknown keys in top level object
for (const QString& key: jsonObject.keys()) { for (const QString& key: jsonObject.keys()) {
...@@ -231,7 +241,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ ...@@ -231,7 +241,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
QList<QJsonValue::Type> types; QList<QJsonValue::Type> types;
types << QJsonValue::Double << QJsonValue::String << QJsonValue::String<< QJsonValue::String << QJsonValue::Bool << QJsonValue::Bool << QJsonValue::Bool types << QJsonValue::Double << QJsonValue::String << QJsonValue::String<< QJsonValue::String << QJsonValue::Bool << QJsonValue::Bool << QJsonValue::Bool
<< QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object
<< QJsonValue::String << QJsonValue::String << QJsonValue::Bool; << QJsonValue::String << QJsonValue::String << QJsonValue::Bool << QJsonValue::Bool;
if (!JsonHelper::validateKeyTypes(jsonObject, allKeys, types, internalError)) { if (!JsonHelper::validateKeyTypes(jsonObject, allKeys, types, internalError)) {
errorString = _loadErrorString(internalError); errorString = _loadErrorString(internalError);
return false; return false;
...@@ -262,6 +272,9 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ ...@@ -262,6 +272,9 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
if (jsonObject.contains(_specifiesAltitudeOnlyJsonKey)) { if (jsonObject.contains(_specifiesAltitudeOnlyJsonKey)) {
_infoMap[_specifiesAltitudeOnlyJsonKey] = jsonObject.value(_specifiesAltitudeOnlyJsonKey).toBool(); _infoMap[_specifiesAltitudeOnlyJsonKey] = jsonObject.value(_specifiesAltitudeOnlyJsonKey).toBool();
} }
if (jsonObject.contains(_isLandCommandJsonKey)) {
_infoMap[_isLandCommandJsonKey] = jsonObject.value(_isLandCommandJsonKey).toBool();
}
if (jsonObject.contains(_friendlyEditJsonKey)) { if (jsonObject.contains(_friendlyEditJsonKey)) {
_infoMap[_friendlyEditJsonKey] = jsonObject.value(_friendlyEditJsonKey).toVariant(); _infoMap[_friendlyEditJsonKey] = jsonObject.value(_friendlyEditJsonKey).toVariant();
} }
...@@ -289,6 +302,9 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ ...@@ -289,6 +302,9 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
if (!_infoAvailable(_specifiesCoordinateJsonKey)) { if (!_infoAvailable(_specifiesCoordinateJsonKey)) {
_setInfoValue(_specifiesCoordinateJsonKey, false); _setInfoValue(_specifiesCoordinateJsonKey, false);
} }
if (!_infoAvailable(_isLandCommandJsonKey)) {
_setInfoValue(_isLandCommandJsonKey, false);
}
if (!_infoAvailable(_friendlyEditJsonKey)) { if (!_infoAvailable(_friendlyEditJsonKey)) {
_setInfoValue(_friendlyEditJsonKey, false); _setInfoValue(_friendlyEditJsonKey, false);
} }
......
...@@ -96,6 +96,7 @@ private: ...@@ -96,6 +96,7 @@ private:
/// specifiesCoordinate bool false true: Command specifies a lat/lon/alt coordinate /// specifiesCoordinate bool false true: Command specifies a lat/lon/alt coordinate
/// specifiesAltitudeOnly bool false true: Command specifies an altitude only (no coordinate) /// specifiesAltitudeOnly bool false true: Command specifies an altitude only (no coordinate)
/// standaloneCoordinate bool false true: Vehicle does not fly through coordinate associated with command (exampl: ROI) /// standaloneCoordinate bool false true: Vehicle does not fly through coordinate associated with command (exampl: ROI)
/// isLandCommand bool false true: Command specifies a land command (LAND, VTOL_LAND, ...)
/// friendlyEdit bool false true: Command supports friendly editing dialog, false: Command supports 'Show all values" style editing only /// friendlyEdit bool false true: Command supports friendly editing dialog, false: Command supports 'Show all values" style editing only
/// category string Advanced Category which this command belongs to /// category string Advanced Category which this command belongs to
/// paramRemove string Used by an override to remove params, example: "1,3" will remove params 1 and 3 on the override /// paramRemove string Used by an override to remove params, example: "1,3" will remove params 1 and 3 on the override
...@@ -118,6 +119,7 @@ public: ...@@ -118,6 +119,7 @@ public:
Q_PROPERTY(bool isStandaloneCoordinate READ isStandaloneCoordinate CONSTANT) Q_PROPERTY(bool isStandaloneCoordinate READ isStandaloneCoordinate CONSTANT)
Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate CONSTANT) Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate CONSTANT)
Q_PROPERTY(bool specifiesAltitudeOnly READ specifiesAltitudeOnly CONSTANT) Q_PROPERTY(bool specifiesAltitudeOnly READ specifiesAltitudeOnly CONSTANT)
Q_PROPERTY(bool isLandCommand READ isLandCommand CONSTANT)
Q_PROPERTY(int command READ intCommand CONSTANT) Q_PROPERTY(int command READ intCommand CONSTANT)
MAV_CMD command(void) const { return _command; } MAV_CMD command(void) const { return _command; }
...@@ -131,6 +133,7 @@ public: ...@@ -131,6 +133,7 @@ public:
bool isStandaloneCoordinate (void) const; bool isStandaloneCoordinate (void) const;
bool specifiesCoordinate (void) const; bool specifiesCoordinate (void) const;
bool specifiesAltitudeOnly (void) const; bool specifiesAltitudeOnly (void) const;
bool isLandCommand (void) const;
/// Load the data in the object from the specified json /// Load the data in the object from the specified json
/// @param jsonObject Json object to load from /// @param jsonObject Json object to load from
...@@ -190,6 +193,7 @@ private: ...@@ -190,6 +193,7 @@ private:
static const char* _standaloneCoordinateJsonKey; static const char* _standaloneCoordinateJsonKey;
static const char* _specifiesCoordinateJsonKey; static const char* _specifiesCoordinateJsonKey;
static const char* _specifiesAltitudeOnlyJsonKey; static const char* _specifiesAltitudeOnlyJsonKey;
static const char* _isLandCommandJsonKey;
static const char* _unitsJsonKey; static const char* _unitsJsonKey;
static const char* _commentJsonKey; static const char* _commentJsonKey;
static const char* _advancedCategory; static const char* _advancedCategory;
......
...@@ -348,12 +348,15 @@ VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordin ...@@ -348,12 +348,15 @@ VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordin
_initVisualItem(newItem); _initVisualItem(newItem);
if (newItem->specifiesAltitude()) { if (newItem->specifiesAltitude()) {
double prevAltitude; const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, command);
int prevAltitudeMode; if (!uiInfo->isLandCommand()) {
double prevAltitude;
if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltitudeMode)) { int prevAltitudeMode;
newItem->altitude()->setRawValue(prevAltitude);
newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode)); if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltitudeMode)) {
newItem->altitude()->setRawValue(prevAltitude);
newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
}
} }
} }
newItem->setMissionFlightStatus(_missionFlightStatus); newItem->setMissionFlightStatus(_missionFlightStatus);
...@@ -418,7 +421,7 @@ VisualMissionItem* MissionController::insertLandItem(QGeoCoordinate coordinate, ...@@ -418,7 +421,7 @@ VisualMissionItem* MissionController::insertLandItem(QGeoCoordinate coordinate,
fwLanding->setLoiterDragAngleOnly(true); fwLanding->setLoiterDragAngleOnly(true);
return fwLanding; return fwLanding;
} else { } else {
return _insertSimpleMissionItemWorker(coordinate, MAV_CMD_NAV_RETURN_TO_LAUNCH, visualItemIndex, makeCurrentItem); return _insertSimpleMissionItemWorker(coordinate, _managerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_RETURN_TO_LAUNCH, visualItemIndex, makeCurrentItem);
} }
} }
......
...@@ -182,6 +182,7 @@ void SimpleMissionItem::_connectSignals(void) ...@@ -182,6 +182,7 @@ void SimpleMissionItem::_connectSignals(void)
connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::specifiesCoordinateChanged); connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::specifiesCoordinateChanged);
connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::specifiesAltitudeOnlyChanged); connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::specifiesAltitudeOnlyChanged);
connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::isStandaloneCoordinateChanged); connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::isStandaloneCoordinateChanged);
connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::isLandCommandChanged);
// Whenever these properties change the ui model changes as well // Whenever these properties change the ui model changes as well
connect(this, &SimpleMissionItem::commandChanged, this, &SimpleMissionItem::_rebuildFacts); connect(this, &SimpleMissionItem::commandChanged, this, &SimpleMissionItem::_rebuildFacts);
...@@ -743,21 +744,13 @@ void SimpleMissionItem::_setDefaultsForCommand(void) ...@@ -743,21 +744,13 @@ void SimpleMissionItem::_setDefaultsForCommand(void)
} }
} }
switch (command) { if (command == MAV_CMD_NAV_WAYPOINT) {
case MAV_CMD_NAV_WAYPOINT:
// We default all acceptance radius to 0. This allows flight controller to be in control of // We default all acceptance radius to 0. This allows flight controller to be in control of
// accept radius. // accept radius.
_missionItem.setParam2(0); _missionItem.setParam2(0);
break; } else if ((uiInfo && uiInfo->isLandCommand()) || command == MAV_CMD_DO_SET_ROI_LOCATION) {
case MAV_CMD_NAV_LAND:
case MAV_CMD_NAV_VTOL_LAND:
case MAV_CMD_DO_SET_ROI_LOCATION:
_altitudeFact.setRawValue(0); _altitudeFact.setRawValue(0);
_missionItem.setParam7(0); _missionItem.setParam7(0);
break;
default:
break;
} }
_missionItem.setAutoContinue(true); _missionItem.setAutoContinue(true);
...@@ -984,3 +977,10 @@ void SimpleMissionItem::_possibleAdditionalTimeDelayChanged(void) ...@@ -984,3 +977,10 @@ void SimpleMissionItem::_possibleAdditionalTimeDelayChanged(void)
return; return;
} }
bool SimpleMissionItem::isLandCommand(void) const
{
MAV_CMD command = static_cast<MAV_CMD>(this->command());
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command);
return uiInfo->isLandCommand();
}
...@@ -100,6 +100,7 @@ public: ...@@ -100,6 +100,7 @@ public:
bool dirty (void) const override { return _dirty; } bool dirty (void) const override { return _dirty; }
bool isSimpleItem (void) const final { return true; } bool isSimpleItem (void) const final { return true; }
bool isStandaloneCoordinate (void) const final; bool isStandaloneCoordinate (void) const final;
bool isLandCommand (void) const final;
bool specifiesCoordinate (void) const final; bool specifiesCoordinate (void) const final;
bool specifiesAltitudeOnly (void) const final; bool specifiesAltitudeOnly (void) const final;
QString commandDescription (void) const final; QString commandDescription (void) const final;
......
...@@ -125,7 +125,7 @@ void TakeoffMissionItem::_initLaunchTakeoffAtSameLocation(void) ...@@ -125,7 +125,7 @@ void TakeoffMissionItem::_initLaunchTakeoffAtSameLocation(void)
if (_controllerVehicle->fixedWing() || _controllerVehicle->vtol()) { if (_controllerVehicle->fixedWing() || _controllerVehicle->vtol()) {
setLaunchTakeoffAtSameLocation(false); setLaunchTakeoffAtSameLocation(false);
} else { } else {
// PX4 specifies a coordinate for takeoff even for non fixed wing. But it makes more sense to not have a coordinate // PX4 specifies a coordinate for takeoff even for multi-rotor. But it makes more sense to not have a coordinate
// from and end user standpoint. So even for PX4 we try to keep launch and takeoff at the same position. Unless the // from and end user standpoint. So even for PX4 we try to keep launch and takeoff at the same position. Unless the
// user has moved/loaded launch at a different location than takeoff. // user has moved/loaded launch at a different location than takeoff.
if (coordinate().isValid() && _settingsItem->coordinate().isValid()) { if (coordinate().isValid() && _settingsItem->coordinate().isValid()) {
......
...@@ -68,6 +68,7 @@ public: ...@@ -68,6 +68,7 @@ public:
Q_PROPERTY(bool specifiesAltitudeOnly READ specifiesAltitudeOnly NOTIFY specifiesAltitudeOnlyChanged) ///< true: Item has altitude only, no full coordinate Q_PROPERTY(bool specifiesAltitudeOnly READ specifiesAltitudeOnly NOTIFY specifiesAltitudeOnlyChanged) ///< true: Item has altitude only, no full coordinate
Q_PROPERTY(bool isSimpleItem READ isSimpleItem NOTIFY isSimpleItemChanged) ///< Simple or Complex MissionItem Q_PROPERTY(bool isSimpleItem READ isSimpleItem NOTIFY isSimpleItemChanged) ///< Simple or Complex MissionItem
Q_PROPERTY(bool isTakeoffItem READ isTakeoffItem NOTIFY isTakeoffItemChanged) ///< true: Takeoff item special case Q_PROPERTY(bool isTakeoffItem READ isTakeoffItem NOTIFY isTakeoffItemChanged) ///< true: Takeoff item special case
Q_PROPERTY(bool isLandCommand READ isLandCommand NOTIFY isLandCommandChanged) ///< true: Takeoff item special case
Q_PROPERTY(QString editorQml MEMBER _editorQml CONSTANT) ///< Qml code for editing this item Q_PROPERTY(QString editorQml MEMBER _editorQml CONSTANT) ///< Qml code for editing this item
Q_PROPERTY(QString mapVisualQML READ mapVisualQML CONSTANT) ///< QMl code for map visuals Q_PROPERTY(QString mapVisualQML READ mapVisualQML CONSTANT) ///< QMl code for map visuals
Q_PROPERTY(double specifiedFlightSpeed READ specifiedFlightSpeed NOTIFY specifiedFlightSpeedChanged) ///< NaN for not specified Q_PROPERTY(double specifiedFlightSpeed READ specifiedFlightSpeed NOTIFY specifiedFlightSpeedChanged) ///< NaN for not specified
...@@ -131,6 +132,7 @@ public: ...@@ -131,6 +132,7 @@ public:
virtual bool dirty (void) const = 0; virtual bool dirty (void) const = 0;
virtual bool isSimpleItem (void) const = 0; virtual bool isSimpleItem (void) const = 0;
virtual bool isTakeoffItem (void) const { return false; } virtual bool isTakeoffItem (void) const { return false; }
virtual bool isLandCommand (void) const { return false; }
virtual bool isStandaloneCoordinate (void) const = 0; virtual bool isStandaloneCoordinate (void) const = 0;
virtual bool specifiesCoordinate (void) const = 0; virtual bool specifiesCoordinate (void) const = 0;
virtual bool specifiesAltitudeOnly (void) const = 0; virtual bool specifiesAltitudeOnly (void) const = 0;
...@@ -208,6 +210,7 @@ signals: ...@@ -208,6 +210,7 @@ signals:
void sequenceNumberChanged (int sequenceNumber); void sequenceNumberChanged (int sequenceNumber);
void isSimpleItemChanged (bool isSimpleItem); void isSimpleItemChanged (bool isSimpleItem);
void isTakeoffItemChanged (bool isTakeoffItem); void isTakeoffItemChanged (bool isTakeoffItem);
void isLandCommandChanged (void);
void specifiesCoordinateChanged (void); void specifiesCoordinateChanged (void);
void isStandaloneCoordinateChanged (void); void isStandaloneCoordinateChanged (void);
void specifiesAltitudeOnlyChanged (void); void specifiesAltitudeOnlyChanged (void);
......
...@@ -629,7 +629,7 @@ Item { ...@@ -629,7 +629,7 @@ Item {
dropPanelComponent: _singleComplexItem ? undefined : patternDropPanel dropPanelComponent: _singleComplexItem ? undefined : patternDropPanel
}, },
{ {
name: _planMasterController.controllerVehicle.fixedWing ? qsTr("Land") : qsTr("Return"), name: _planMasterController.controllerVehicle.multiRotor ? qsTr("Return") : qsTr("Land"),
iconSource: "/res/rtl.svg", iconSource: "/res/rtl.svg",
buttonEnabled: _missionController.isInsertLandValid, buttonEnabled: _missionController.isInsertLandValid,
buttonVisible: _isMissionLayer buttonVisible: _isMissionLayer
......
...@@ -59,6 +59,16 @@ Rectangle { ...@@ -59,6 +59,16 @@ Rectangle {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
anchors.top: parent.top anchors.top: parent.top
spacing: _margin
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize
text: missionItem.rawEdit ?
qsTr("Provides advanced access to all commands/parameters. Be very careful!") :
missionItem.commandDescription
}
ColumnLayout { ColumnLayout {
anchors.left: parent.left anchors.left: parent.left
...@@ -67,7 +77,7 @@ Rectangle { ...@@ -67,7 +77,7 @@ Rectangle {
visible: missionItem.isTakeoffItem && missionItem.wizardMode // Hack special case for takeoff item visible: missionItem.isTakeoffItem && missionItem.wizardMode // Hack special case for takeoff item
QGCLabel { QGCLabel {
text: qsTr("Move 'T' Takeoff to the %1 location.").arg(_controllerVehicle.vtol ? qsTr("desired") : qsTr("climbout")) text: qsTr("Move '%1' Takeoff to the %2 location.").arg(_controllerVehicle.vtol ? qsTr("V") : qsTr("T")).arg(_controllerVehicle.vtol ? qsTr("desired") : qsTr("climbout"))
Layout.fillWidth: true Layout.fillWidth: true
wrapMode: Text.WordWrap wrapMode: Text.WordWrap
visible: !initialClickLabel.visible visible: !initialClickLabel.visible
...@@ -77,7 +87,7 @@ Rectangle { ...@@ -77,7 +87,7 @@ Rectangle {
text: qsTr("Ensure clear of obstacles and into the wind.") text: qsTr("Ensure clear of obstacles and into the wind.")
Layout.fillWidth: true Layout.fillWidth: true
wrapMode: Text.WordWrap wrapMode: Text.WordWrap
visible: !initialClickLabel.visible && !_controllerVehicle.vtol visible: !initialClickLabel.visible
} }
QGCButton { QGCButton {
...@@ -107,15 +117,6 @@ Rectangle { ...@@ -107,15 +117,6 @@ Rectangle {
spacing: _margin spacing: _margin
visible: !missionItem.wizardMode visible: !missionItem.wizardMode
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize
text: missionItem.rawEdit ?
qsTr("Provides advanced access to all commands/parameters. Be very careful!") :
missionItem.commandDescription
}
GridLayout { GridLayout {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
...@@ -162,6 +163,14 @@ Rectangle { ...@@ -162,6 +163,14 @@ Rectangle {
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize
text: qsTr("Altitude below specifies the approximate altitude of the ground. Normally 0 for landing back at original launch location.")
visible: missionItem.isLandCommand
}
Item { Item {
width: altHamburger.x + altHamburger.width width: altHamburger.x + altHamburger.width
height: altModeLabel.height height: altModeLabel.height
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment