From b334b2897d348f246ea64d70cce7aeed9e9d65ad Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sat, 9 Jul 2016 12:26:57 -0400 Subject: [PATCH] PX4 LOITER_TO_ALT and metadata update --- .../APM/MavCmdInfoFixedWing.json | 57 ++++++++++++++- .../PX4/MavCmdInfoFixedWing.json | 73 +++++++++++++------ src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc | 7 +- src/MissionManager/MavCmdInfoCommon.json | 4 +- 4 files changed, 109 insertions(+), 32 deletions(-) diff --git a/src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json b/src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json index 788bc885d..0494750b1 100644 --- a/src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json +++ b/src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json @@ -33,7 +33,7 @@ "param3": { "label": "Radius:", "units": "m", - "default": 100, + "default": 50, "decimalPlaces": 0 }, "param7": { @@ -59,9 +59,16 @@ "param3": { "label": "Radius:", "units": "m", - "default": 100, + "default": 50, "decimalPlaces": 0 }, + "param4": { + "label": "Next waypoint start:", + "enumStrings": "Center,On Loiter", + "enumValues": "0,1", + "default": 1, + "decimalPlaces": 0 + }, "param7": { "label": "Altitude:", "units": "m", @@ -86,9 +93,16 @@ "param3": { "label": "Radius:", "units": "m", - "default": 100, + "default": 50, "decimalPlaces": 0 }, + "param4": { + "label": "Next waypoint start:", + "enumStrings": "Center,On Loiter", + "enumValues": "0,1", + "default": 1, + "decimalPlaces": 0 + }, "param7": { "label": "Altitude:", "units": "m", @@ -134,7 +148,7 @@ "param1": { "label": "Pitch:", "units": "degrees", - "default": 0, + "default": 10, "decimalPlaces": 0 }, "param4": { @@ -150,6 +164,41 @@ "decimalPlaces": 0 } }, + { + "id": 31, + "rawName": "MAV_CMD_NAV_LOITER_TO_ALT", + "friendlyName": "Loiter (altitude)", + "description": "Travel to a position and Loiter around the specified radius until the given altitude.", + "specifiesCoordinate": true, + "friendlyEdit": true, + "category": "Loiter", + "param1": { + "label": "Heading wait:", + "enumStrings": "False,True", + "enumValues": "0,1", + "default": 1, + "decimalPlaces": 0 + }, + "param2": { + "label": "Radius:", + "units": "m", + "default": 50, + "decimalPlaces": 0 + }, + "param4": { + "label": "Next waypoint start:", + "enumStrings": "Center,On Loiter", + "enumValues": "0,1", + "default": 1, + "decimalPlaces": 0 + }, + "param7": { + "label": "Altitude:", + "units": "m", + "default": 50, + "decimalPlaces": 0 + } + }, { "id": 206, "rawName": "MAV_CMD_DO_SET_CAM_TRIGG_DIST", diff --git a/src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json b/src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json index 788bc885d..acaa58088 100644 --- a/src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json +++ b/src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json @@ -33,7 +33,7 @@ "param3": { "label": "Radius:", "units": "m", - "default": 100, + "default": 50, "decimalPlaces": 0 }, "param7": { @@ -59,9 +59,16 @@ "param3": { "label": "Radius:", "units": "m", - "default": 100, + "default": 50, "decimalPlaces": 0 }, + "param4": { + "label": "Next waypoint start:", + "enumStrings": "Center,On Loiter", + "enumValues": "0,1", + "default": 1, + "decimalPlaces": 0 + }, "param7": { "label": "Altitude:", "units": "m", @@ -86,9 +93,16 @@ "param3": { "label": "Radius:", "units": "m", - "default": 100, + "default": 50, "decimalPlaces": 0 }, + "param4": { + "label": "Next waypoint start:", + "enumStrings": "Center,On Loiter", + "enumValues": "0,1", + "default": 1, + "decimalPlaces": 0 + }, "param7": { "label": "Altitude:", "units": "m", @@ -104,18 +118,6 @@ "specifiesCoordinate": true, "friendlyEdit": true, "category": "Basic", - "param1": { - "label": "Abort Alt:", - "units": "m", - "default": 25, - "decimalPlaces": 0 - }, - "param4": { - "label": "Heading:", - "units": "radians", - "default": 0, - "decimalPlaces": 2 - }, "param7": { "label": "Altitude:", "units": "m", @@ -134,19 +136,48 @@ "param1": { "label": "Pitch:", "units": "degrees", - "default": 0, + "default": 10, + "decimalPlaces": 0 + }, + "param7": { + "label": "Altitude:", + "units": "m", + "default": 25, + "decimalPlaces": 0 + } + }, + { + "id": 31, + "rawName": "MAV_CMD_NAV_LOITER_TO_ALT", + "friendlyName": "Loiter (altitude)", + "description": "Travel to a position and Loiter around the specified radius until the given altitude.", + "specifiesCoordinate": true, + "friendlyEdit": true, + "category": "Loiter", + "param1": { + "label": "Heading wait:", + "enumStrings": "False,True", + "enumValues": "0,1", + "default": 1, + "decimalPlaces": 0 + }, + "param2": { + "label": "Radius:", + "units": "m", + "default": 50, "decimalPlaces": 0 }, "param4": { - "label": "Heading:", - "units": "radians", - "default": 0, - "decimalPlaces": 1 + "label": "Next waypoint start:", + "enumStrings": "Center,On Loiter", + "enumValues": "0,1", + "default": 1, + "decimalPlaces": 0 }, "param7": { "label": "Altitude:", "units": "m", - "default": 25, + "default": 50, "decimalPlaces": 0 } }, diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index 0c781d991..d98863e72 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -199,7 +199,7 @@ QList PX4FirmwarePlugin::supportedMissionCommands(void) QList list; list << MAV_CMD_NAV_WAYPOINT - << MAV_CMD_NAV_LOITER_UNLIM << MAV_CMD_NAV_LOITER_TIME + << MAV_CMD_NAV_LOITER_UNLIM << MAV_CMD_NAV_LOITER_TIME << MAV_CMD_NAV_LOITER_TO_ALT << MAV_CMD_NAV_LAND << MAV_CMD_NAV_TAKEOFF << MAV_CMD_DO_JUMP << MAV_CMD_DO_VTOL_TRANSITION << MAV_CMD_NAV_VTOL_TAKEOFF << MAV_CMD_NAV_VTOL_LAND @@ -207,10 +207,9 @@ QList PX4FirmwarePlugin::supportedMissionCommands(void) << MAV_CMD_DO_SET_CAM_TRIGG_DIST << MAV_CMD_DO_SET_SERVO << MAV_CMD_DO_CHANGE_SPEED - << MAV_CMD_DO_SET_ROI + << MAV_CMD_DO_LAND_START << MAV_CMD_DO_MOUNT_CONFIGURE - << MAV_CMD_DO_MOUNT_CONTROL - << MAV_CMD_NAV_PATHPLANNING; + << MAV_CMD_DO_MOUNT_CONTROL; return list; } diff --git a/src/MissionManager/MavCmdInfoCommon.json b/src/MissionManager/MavCmdInfoCommon.json index c1282def0..9f2651367 100644 --- a/src/MissionManager/MavCmdInfoCommon.json +++ b/src/MissionManager/MavCmdInfoCommon.json @@ -543,10 +543,8 @@ "rawName": "MAV_CMD_DO_LAND_START", "friendlyName": "Land start", "description": "Marker to indicate start of landing sequence.", - "specifiesCoordinate": true, - "standaloneCoordinate": true, "friendlyEdit": true, - "category": "Basic" + "category": "Flight control" }, { "id": 190, "rawName": "MAV_CMD_DO_RALLY_LAND", "friendlyName": "Rally land" }, { "id": 191, "rawName": "MAV_CMD_DO_GO_AROUND", "friendlyName": "Go around" }, -- 2.22.0