From 53e85a51bb7400a645cc514946cb97fa1a30258c Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 16 Apr 2019 11:13:05 -0700 Subject: [PATCH 1/2] No camera commands for ArduPilot --- src/MissionManager/FixedWingLandingComplexItem.cc | 6 ++++++ src/PlanView/FWLandingPatternEditor.qml | 11 ++++++++--- 2 files changed, 14 insertions(+), 3 deletions(-) diff --git a/src/MissionManager/FixedWingLandingComplexItem.cc b/src/MissionManager/FixedWingLandingComplexItem.cc index db3ad99..bb41883 100644 --- a/src/MissionManager/FixedWingLandingComplexItem.cc +++ b/src/MissionManager/FixedWingLandingComplexItem.cc @@ -100,6 +100,12 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool connect(this, &FixedWingLandingComplexItem::altitudesAreRelativeChanged, this, &FixedWingLandingComplexItem::coordinateHasRelativeAltitudeChanged); connect(this, &FixedWingLandingComplexItem::altitudesAreRelativeChanged, this, &FixedWingLandingComplexItem::exitCoordinateHasRelativeAltitudeChanged); + if (vehicle->apmFirmware()) { + // ArduPilot does not support camera commands + _stopTakingVideoFact.setRawValue(false); + _stopTakingPhotosFact.setRawValue(false); + } + if (_valueSetIsDistanceFact.rawValue().toBool()) { _recalcFromHeadingAndDistanceChange(); } else { diff --git a/src/PlanView/FWLandingPatternEditor.qml b/src/PlanView/FWLandingPatternEditor.qml index 2bfbd1e..fd3ed3f 100644 --- a/src/PlanView/FWLandingPatternEditor.qml +++ b/src/PlanView/FWLandingPatternEditor.qml @@ -32,11 +32,15 @@ Rectangle { //property real availableWidth ///< Width for control //property var missionItem ///< Mission Item for editor + property var _masterControler: masterController + property var _missionController: _masterControler.missionController + property var _missionVehicle: _masterControler.controllerVehicle property real _margin: ScreenTools.defaultFontPixelWidth / 2 property real _spacer: ScreenTools.defaultFontPixelWidth / 2 property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property string _setToVehicleHeadingStr: qsTr("Set to vehicle heading") property string _setToVehicleLocationStr: qsTr("Set to vehicle location") + property bool _showCameraSection: !_missionVehicle.apmFirmware ExclusiveGroup { id: distanceGlideGroup } @@ -166,15 +170,16 @@ Rectangle { } SectionHeader { - id: cameraSection - text: qsTr("Camera") + id: cameraSection + text: qsTr("Camera") + visible: _showCameraSection } Column { anchors.left: parent.left anchors.right: parent.right spacing: _margin - visible: cameraSection.checked + visible: _showCameraSection && cameraSection.checked Item { width: 1; height: _spacer } From 929d4210ec07c457d034a6937b3f3201b3c7772b Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 16 Apr 2019 11:13:27 -0700 Subject: [PATCH 2/2] Work around quirkiness with ArduPilot and LOITER_* NaN handling on heading. --- src/FirmwarePlugin/APM/MavCmdInfoCommon.json | 30 ++++++++++++++++++++++ src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json | 22 +++++++++++++++++ src/FirmwarePlugin/PX4/MavCmdInfoCommon.json | 33 ------------------------- src/MissionManager/MavCmdInfoCommon.json | 6 +++-- 4 files changed, 56 insertions(+), 35 deletions(-) diff --git a/src/FirmwarePlugin/APM/MavCmdInfoCommon.json b/src/FirmwarePlugin/APM/MavCmdInfoCommon.json index 4a50818..8f35edd 100644 --- a/src/FirmwarePlugin/APM/MavCmdInfoCommon.json +++ b/src/FirmwarePlugin/APM/MavCmdInfoCommon.json @@ -10,6 +10,36 @@ "paramRemove": "2" }, { + "id": 17, + "comment": "MAV_CMD_NAV_LOITER_UNLIM", + "param4": { + "label": "Heading", + "units": "radians", + "default": 0, + "decimalPlaces": 2 + } + }, + { + "id": 18, + "comment": "MAV_CMD_NAV_LOITER_TURNS", + "param4": { + "label": "Heading", + "units": "radians", + "default": 0, + "decimalPlaces": 2 + } + }, + { + "id": 19, + "comment": "MAV_CMD_NAV_LOITER_TIME", + "param4": { + "label": "Heading", + "units": "radians", + "default": 0, + "decimalPlaces": 2 + } + }, + { "id": 22, "comment": "MAV_CMD_NAV_TAKEOFF", "specifiesCoordinate": false, diff --git a/src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json b/src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json index 6fa8db8..9cca751 100644 --- a/src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json +++ b/src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json @@ -10,6 +10,28 @@ "paramRemove": "1,3,4" }, { + "id": 18, + "comment": "MAV_CMD_NAV_LOITER_TURNS", + "param4": { + "label": "Exit loiter from", + "enumStrings": "Center,Tangent", + "enumValues": "0,1", + "default": 1, + "decimalPlaces": 0 + } + }, + { + "id": 19, + "comment": "MAV_CMD_NAV_LOITER_TIME", + "param4": { + "label": "Exit loiter from", + "enumStrings": "Center,Tangent", + "enumValues": "0,1", + "default": 1, + "decimalPlaces": 0 + } + }, + { "id": 21, "comment": "MAV_CMD_NAV_LAND", "paramRemove": "4" diff --git a/src/FirmwarePlugin/PX4/MavCmdInfoCommon.json b/src/FirmwarePlugin/PX4/MavCmdInfoCommon.json index e8f236b..8657261 100644 --- a/src/FirmwarePlugin/PX4/MavCmdInfoCommon.json +++ b/src/FirmwarePlugin/PX4/MavCmdInfoCommon.json @@ -10,39 +10,6 @@ "paramRemove": "2,3" }, { - "id": 17, - "comment": "MAV_CMD_NAV_LOITER_UNLIM", - "param4": { - "label": "Heading", - "units": "radians", - "nanUnchanged": true, - "default": null, - "decimalPlaces": 2 - } - }, - { - "id": 18, - "comment": "MAV_CMD_NAV_LOITER_TURNS", - "param4": { - "label": "Heading", - "units": "radians", - "nanUnchanged": true, - "default": null, - "decimalPlaces": 2 - } - }, - { - "id": 19, - "comment": "MAV_CMD_NAV_LOITER_TIME", - "param4": { - "label": "Heading", - "units": "radians", - "nanUnchanged": true, - "default": null, - "decimalPlaces": 2 - } - }, - { "id": 21, "comment": "MAV_CMD_NAV_LAND", "paramRemove": "1" diff --git a/src/MissionManager/MavCmdInfoCommon.json b/src/MissionManager/MavCmdInfoCommon.json index 93cf032..5841b02 100644 --- a/src/MissionManager/MavCmdInfoCommon.json +++ b/src/MissionManager/MavCmdInfoCommon.json @@ -101,7 +101,8 @@ "param4": { "label": "Heading", "units": "radians", - "default": 0, + "nanUnchanged": true, + "default": null, "decimalPlaces": 2 } }, @@ -128,7 +129,8 @@ "param4": { "label": "Heading", "units": "radians", - "default": 0, + "nanUnchanged": true, + "default": null, "decimalPlaces": 2 } },