diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h index 1353e0ca087947550cbf0b5a33bb0920bc312bd7..336f3ee3b20a34aeefe9de0bb32ff05cb5fbb095 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h @@ -102,6 +102,7 @@ public: QObject* loadParameterMetaData (const QString& metaDataFile) override; QString brandImageIndoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImage"); } QString brandImageOutdoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImage"); } + bool supportsTerrainFrame (void) const override { return true; } protected: /// All access to singleton is through stack specific implementation diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc index 96efc3a1015fcf9d127f69aaca137f60e84daef9..39b5c7689572c3571fdec8d3777d9ae26b2698d0 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.cc +++ b/src/FirmwarePlugin/FirmwarePlugin.cc @@ -150,6 +150,12 @@ bool FirmwarePlugin::supportsJSButton(void) return false; } +bool FirmwarePlugin::supportsTerrainFrame(void) const +{ + // Generic firmware supports this since we don't know + return true; +} + bool FirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) { Q_UNUSED(vehicle); diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index 07971cd226a865a7f55763bba7883fd59091984b..c161e096c5b3d685143d7a23b3a04f9ff2a4d646 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -180,6 +180,9 @@ public: /// (CompassMot). Default is true. virtual bool supportsMotorInterference(void); + /// Returns true if the firmware supports MAV_FRAME_GLOBAL_TERRAIN_ALT + virtual bool supportsTerrainFrame(void) const; + /// Called before any mavlink message is processed by Vehicle such that the firmwre plugin /// can adjust any message characteristics. This is handy to adjust or differences in mavlink /// spec implementations such that the base code can remain mavlink generic. diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h index 7aefe54d8080acc5e714e69440634e4ae14eaef7..ddc69af0df0ef9292f603fcf143cfd51c895acfd 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h @@ -71,6 +71,7 @@ public: QGCCameraManager* createCameraManager (Vehicle* vehicle) override; QGCCameraControl* createCameraControl (const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = NULL) override; uint32_t highLatencyCustomModeTo32Bits (uint16_t hlCustomMode) override; + bool supportsTerrainFrame (void) const override { return false; } protected: typedef struct { diff --git a/src/MissionManager/MissionSettingsItem.cc b/src/MissionManager/MissionSettingsItem.cc index abe14a452a8f4e67363b8592349c89a54f3c2161..3ddc6c30a984a32aaf0f067d2e5d8ad103ddd29c 100644 --- a/src/MissionManager/MissionSettingsItem.cc +++ b/src/MissionManager/MissionSettingsItem.cc @@ -57,7 +57,7 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent) connect(this, &MissionSettingsItem::terrainAltitudeChanged, this, &MissionSettingsItem::_setHomeAltFromTerrain); - connect(&_plannedHomePositionAltitudeFact, &Fact::valueChanged, this, &MissionSettingsItem::_updateAltitudeInCoordinate); + connect(&_plannedHomePositionAltitudeFact, &Fact::rawValueChanged, this, &MissionSettingsItem::_updateAltitudeInCoordinate); connect(&_cameraSection, &CameraSection::dirtyChanged, this, &MissionSettingsItem::_sectionDirtyChanged); connect(&_speedSection, &SpeedSection::dirtyChanged, this, &MissionSettingsItem::_sectionDirtyChanged); diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc index 76ebceb84dd3fe946034e258bab9e2c00d408fd0..71a1fadbc8a6508681491eba95aeb0b133144b99 100644 --- a/src/MissionManager/SimpleMissionItem.cc +++ b/src/MissionManager/SimpleMissionItem.cc @@ -81,11 +81,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent) setDefaultsForCommand(); _rebuildFacts(); - connect(&_missionItem, &MissionItem::specifiedFlightSpeedChanged, this, &SimpleMissionItem::specifiedFlightSpeedChanged); - - connect(this, &SimpleMissionItem::sequenceNumberChanged, this, &SimpleMissionItem::lastSequenceNumberChanged); - connect(this, &SimpleMissionItem::cameraSectionChanged, this, &SimpleMissionItem::_setDirty); - connect(this, &SimpleMissionItem::cameraSectionChanged, this, &SimpleMissionItem::_updateLastSequenceNumber); + setDirty(false); } SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool editMode, const MissionItem& missionItem, QObject* parent) @@ -98,7 +94,6 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool editMode, const Miss , _cameraSection (NULL) , _commandTree (qgcApp()->toolbox()->missionCommandTree()) , _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32) - , _altitudeMode (missionItem.relativeAltitude() ? AltitudeRelative : AltitudeAMSL) , _altitudeFact (0, "Altitude", FactMetaData::valueTypeDouble) , _amslAltAboveTerrainFact (0, "Alt above terrain", FactMetaData::valueTypeDouble) , _param1MetaData (FactMetaData::valueTypeDouble) @@ -112,6 +107,25 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool editMode, const Miss { _editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml"); + struct MavFrame2AltMode_s { + MAV_FRAME mavFrame; + AltitudeMode altMode; + }; + + const struct MavFrame2AltMode_s rgMavFrame2AltMode[] = { + { MAV_FRAME_GLOBAL_TERRAIN_ALT, AltitudeTerrainFrame }, + { MAV_FRAME_GLOBAL, AltitudeAbsolute }, + { MAV_FRAME_GLOBAL_RELATIVE_ALT, AltitudeRelative }, + }; + _altitudeMode = AltitudeRelative; + for (size_t i=0; isupportsTerrainFrame(); } CameraSection* cameraSection (void) { return _cameraSection; } SpeedSection* speedSection (void) { return _speedSection; } @@ -141,6 +144,7 @@ signals: void cameraSectionChanged (QObject* cameraSection); void speedSectionChanged (QObject* cameraSection); void altitudeModeChanged (void); + void supportsTerrainFrameChanged(void); private slots: void _setDirty (void); diff --git a/src/MissionManager/SimpleMissionItemTest.cc b/src/MissionManager/SimpleMissionItemTest.cc index 1e8cc5443ff8424ce707df5346360f857ad95bee..7a91914b4751c3229a41462e3f78a269b5cce50e 100644 --- a/src/MissionManager/SimpleMissionItemTest.cc +++ b/src/MissionManager/SimpleMissionItemTest.cc @@ -53,11 +53,11 @@ const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesDoJ const SimpleMissionItemTest::ItemExpected_t SimpleMissionItemTest::_rgItemExpected[] = { // Text field facts count Fact Values Altitude Altitude Mode { sizeof(SimpleMissionItemTest::_rgFactValuesWaypoint)/sizeof(SimpleMissionItemTest::_rgFactValuesWaypoint[0]), SimpleMissionItemTest::_rgFactValuesWaypoint, 70.1234567, SimpleMissionItem::AltitudeRelative }, - { sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim[0]), SimpleMissionItemTest::_rgFactValuesLoiterUnlim, 70.1234567, SimpleMissionItem::AltitudeAMSL }, + { sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim[0]), SimpleMissionItemTest::_rgFactValuesLoiterUnlim, 70.1234567, SimpleMissionItem::AltitudeAbsolute }, { sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns[0]), SimpleMissionItemTest::_rgFactValuesLoiterTurns, 70.1234567, SimpleMissionItem::AltitudeRelative }, - { sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime[0]), SimpleMissionItemTest::_rgFactValuesLoiterTime, 70.1234567, SimpleMissionItem::AltitudeAMSL }, + { sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime[0]), SimpleMissionItemTest::_rgFactValuesLoiterTime, 70.1234567, SimpleMissionItem::AltitudeAbsolute }, { 0, NULL, 70.1234567, SimpleMissionItem::AltitudeRelative }, - { sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff)/sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff[0]), SimpleMissionItemTest::_rgFactValuesTakeoff, 70.1234567, SimpleMissionItem::AltitudeAMSL }, + { sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff)/sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff[0]), SimpleMissionItemTest::_rgFactValuesTakeoff, 70.1234567, SimpleMissionItem::AltitudeAbsolute }, { sizeof(SimpleMissionItemTest::_rgFactValuesDoJump)/sizeof(SimpleMissionItemTest::_rgFactValuesDoJump[0]), SimpleMissionItemTest::_rgFactValuesDoJump, qQNaN(), SimpleMissionItem::AltitudeRelative }, }; @@ -222,7 +222,7 @@ void SimpleMissionItemTest::_testSignals(void) QVERIFY(_spyVisualItem->checkOnlySignalByMask(dirtyChangedMask)); _spyVisualItem->clearAllSignals(); - _simpleItem->setAltitudeMode(_simpleItem->altitudeMode() == SimpleMissionItem::AltitudeRelative ? SimpleMissionItem::AltitudeAMSL : SimpleMissionItem::AltitudeRelative); + _simpleItem->setAltitudeMode(_simpleItem->altitudeMode() == SimpleMissionItem::AltitudeRelative ? SimpleMissionItem::AltitudeAbsolute : SimpleMissionItem::AltitudeRelative); QVERIFY(_spySimpleItem->checkOnlySignalByMask(dirtyChangedMask | friendlyEditAllowedChangedMask | altitudeModeChangedMask | coordinateHasRelativeAltitudeChangedMask)); _spySimpleItem->clearAllSignals(); _spyVisualItem->clearAllSignals(); @@ -314,7 +314,7 @@ void SimpleMissionItemTest::_testAltitudePropogation(void) QCOMPARE(_simpleItem->altitude()->rawValue().toDouble(), _simpleItem->missionItem().param7()); QCOMPARE(_simpleItem->missionItem().frame(), MAV_FRAME_GLOBAL_RELATIVE_ALT); - _simpleItem->setAltitudeMode(SimpleMissionItem::AltitudeAMSL); + _simpleItem->setAltitudeMode(SimpleMissionItem::AltitudeAbsolute); _simpleItem->altitude()->setRawValue(_simpleItem->altitude()->rawValue().toDouble() + 1); QCOMPARE(_simpleItem->altitude()->rawValue().toDouble(), _simpleItem->missionItem().param7()); QCOMPARE(_simpleItem->missionItem().frame(), MAV_FRAME_GLOBAL); diff --git a/src/PlanView/SimpleItemEditor.qml b/src/PlanView/SimpleItemEditor.qml index d9bbe4f2dfe374b8f0a96bec0b33c21648db6f4e..93b5b64d97d740eb70e7bcdaf068b405cd4be84d 100644 --- a/src/PlanView/SimpleItemEditor.qml +++ b/src/PlanView/SimpleItemEditor.qml @@ -17,9 +17,14 @@ Rectangle { color: qgcPal.windowShadeDark radius: _radius - property bool _specifiesAltitude: missionItem.specifiesAltitude - property bool _altModeIsTerrain: missionItem.altitudeMode === 2 - property real _margin: ScreenTools.defaultFontPixelHeight / 2 + property bool _specifiesAltitude: missionItem.specifiesAltitude + property real _margin: ScreenTools.defaultFontPixelHeight / 2 + property bool _supportsTerrainFrame: missionItem + + readonly property int _altModeRelative: 0 + readonly property int _altModeAbsolute: 1 + readonly property int _altModeAboveTerrain: 2 + readonly property int _altModeTerrainFrame: 3 ExclusiveGroup { id: altRadios @@ -74,10 +79,11 @@ Rectangle { } Rectangle { - anchors.left: parent.left - anchors.right: parent.right - height: altColumn.y + altColumn.height + _margin - color: qgcPal.windowShade + anchors.left: parent.left + anchors.right: parent.right + height: altColumn.y + altColumn.height + _margin + color: qgcPal.windowShade + visible: _specifiesAltitude Column { id: altColumn @@ -93,31 +99,36 @@ Rectangle { } RowLayout { - QGCRadioButton { text: qsTr("Rel"); exclusiveGroup: altRadios; checked: missionItem.altitudeMode === value; readonly property int value: 0 } - QGCRadioButton { text: qsTr("Abs"); exclusiveGroup: altRadios; checked: missionItem.altitudeMode === value; readonly property int value: 1 } - QGCRadioButton { text: qsTr("AGL"); exclusiveGroup: altRadios; checked: missionItem.altitudeMode === value; readonly property int value: 2 } + QGCRadioButton { text: qsTr("Rel"); exclusiveGroup: altRadios; checked: missionItem.altitudeMode === value; readonly property int value: _altModeRelative } + QGCRadioButton { text: qsTr("Abs"); exclusiveGroup: altRadios; checked: missionItem.altitudeMode === value; readonly property int value: _altModeAbsolute } + QGCRadioButton { text: qsTr("AGL"); exclusiveGroup: altRadios; checked: missionItem.altitudeMode === value; readonly property int value: _altModeAboveTerrain } + QGCRadioButton { text: qsTr("TerrF"); exclusiveGroup: altRadios; checked: missionItem.altitudeMode === value; visible: missionItem.supportsTerrainFrame; readonly property int value: _altModeTerrainFrame } } FactValueSlider { fact: missionItem.altitude digitCount: 3 incrementSlots: 1 - visible: _specifiesAltitude } RowLayout { spacing: _margin + visible: missionItem.altitudeMode === _altModeAboveTerrain QGCLabel { text: qsTr("Calculated Abs Alt") font.pointSize: ScreenTools.smallFontPointSize - visible: _altModeIsTerrain } QGCLabel { text: missionItem.amslAltAboveTerrain.valueString + " " + missionItem.amslAltAboveTerrain.units - visible: _altModeIsTerrain } } + + QGCLabel { + text: qsTr("Using terrain reference frame") + font.pointSize: ScreenTools.smallFontPointSize + visible: missionItem.altitudeMode === _altModeTerrainFrame + } } } diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 6f0596eaaa11207936c6f23c2eccb27f7da4cb4a..a6adf280414841da791ca34eeeb6f65c8e90d41a 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -494,6 +494,7 @@ void Vehicle::prepareDelete() void Vehicle::_offlineFirmwareTypeSettingChanged(QVariant value) { _firmwareType = static_cast(value.toInt()); + _firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType); emit firmwareTypeChanged(); if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) { _capabilityBits = 0; @@ -2452,6 +2453,11 @@ bool Vehicle::supportsMotorInterference(void) const return _firmwarePlugin->supportsMotorInterference(); } +bool Vehicle::supportsTerrainFrame(void) const +{ + return _firmwarePlugin->supportsTerrainFrame(); +} + QString Vehicle::vehicleTypeName() const { static QMap typeNames = { { MAV_TYPE_GENERIC, tr("Generic micro air vehicle" )}, diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 1b6bbd37dc1edae9c6edcfc10e3478b686263b5b..f410e13fbb9e43c331bc7ff27650e9240faff70f 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -457,6 +457,7 @@ public: Q_PROPERTY(QString hobbsMeter READ hobbsMeter NOTIFY hobbsMeterChanged) Q_PROPERTY(bool vtolInFwdFlight READ vtolInFwdFlight WRITE setVtolInFwdFlight NOTIFY vtolInFwdFlightChanged) Q_PROPERTY(bool highLatencyLink READ highLatencyLink NOTIFY highLatencyLinkChanged) + Q_PROPERTY(bool supportsTerrainFrame READ supportsTerrainFrame NOTIFY firmwareTypeChanged) // Vehicle state used for guided control Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged) ///< Vehicle is flying @@ -665,11 +666,12 @@ public: bool rover(void) const; bool sub(void) const; - bool supportsThrottleModeCenterZero(void) const; - bool supportsNegativeThrust(void) const; - bool supportsRadio(void) const; - bool supportsJSButton(void) const; - bool supportsMotorInterference(void) const; + bool supportsThrottleModeCenterZero (void) const; + bool supportsNegativeThrust (void) const; + bool supportsRadio (void) const; + bool supportsJSButton (void) const; + bool supportsMotorInterference (void) const; + bool supportsTerrainFrame (void) const; void setGuidedMode(bool guidedMode);