Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

PX4 MAV_CMD_NAV_LOITER_TO_ALT and cleanup #3730

Merged
merged 1 commit into from
Jul 12, 2016
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
57 changes: 53 additions & 4 deletions src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@
"param3": {
"label": "Radius:",
"units": "m",
"default": 100,
"default": 50,
"decimalPlaces": 0
},
"param7": {
Expand All @@ -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",
Expand All @@ -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",
Expand Down Expand Up @@ -134,7 +148,7 @@
"param1": {
"label": "Pitch:",
"units": "degrees",
"default": 0,
"default": 10,
"decimalPlaces": 0
},
"param4": {
Expand All @@ -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",
Expand Down
73 changes: 52 additions & 21 deletions src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@
"param3": {
"label": "Radius:",
"units": "m",
"default": 100,
"default": 50,
"decimalPlaces": 0
},
"param7": {
Expand All @@ -59,9 +59,16 @@
"param3": {
"label": "Radius:",
"units": "m",
"default": 100,
"default": 50,
"decimalPlaces": 0
},
"param4": {
"label": "Next waypoint start:",
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

A bit concerned about such a long label fitting on all form factors. I'm going to have to merge and try on a phone to see.

"enumStrings": "Center,On Loiter",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
},
"param7": {
"label": "Altitude:",
"units": "m",
Expand All @@ -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",
Expand All @@ -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",
Expand All @@ -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
}
},
Expand Down
7 changes: 3 additions & 4 deletions src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -199,18 +199,17 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
QList<MAV_CMD> 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
<< MAV_CMD_DO_DIGICAM_CONTROL
<< 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;
}
Expand Down
4 changes: 1 addition & 3 deletions src/MissionManager/MavCmdInfoCommon.json
Original file line number Diff line number Diff line change
Expand Up @@ -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" },
Expand Down