Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
068a385b
Commit
068a385b
authored
Feb 10, 2016
by
Don Gagne
Browse files
Merge pull request #2769 from DonLakeFlyer/MissionCommands
Add missing mission commands for PX4 and ArduPilot stacks
parents
307bae05
69ecfb7b
Changes
5
Show whitespace changes
Inline
Side-by-side
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
068a385b
...
...
@@ -483,8 +483,8 @@ QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void)
{
QList
<
MAV_CMD
>
list
;
list
<<
MAV_CMD_NAV_WAYPOINT
<<
MAV_CMD_NAV_LOITER_UNLIM
<<
MAV_CMD_NAV_LOITER_TURNS
<<
MAV_CMD_NAV_LOITER_TIME
list
<<
MAV_CMD_NAV_WAYPOINT
<<
MAV_CMD_NAV_SPLINE_WAYPOINT
<<
MAV_CMD_NAV_LOITER_UNLIM
<<
MAV_CMD_NAV_LOITER_TURNS
<<
MAV_CMD_NAV_LOITER_TIME
<<
MAV_CMD_NAV_LOITER_TO_ALT
<<
MAV_CMD_NAV_RETURN_TO_LAUNCH
<<
MAV_CMD_NAV_LAND
<<
MAV_CMD_NAV_TAKEOFF
<<
MAV_CMD_NAV_GUIDED_ENABLE
<<
MAV_CMD_DO_SET_ROI
<<
MAV_CMD_DO_GUIDED_LIMITS
<<
MAV_CMD_DO_JUMP
<<
MAV_CMD_DO_CHANGE_SPEED
<<
MAV_CMD_DO_SET_CAM_TRIGG_DIST
...
...
@@ -492,7 +492,13 @@ QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void)
<<
MAV_CMD_DO_SET_SERVO
<<
MAV_CMD_DO_REPEAT_SERVO
<<
MAV_CMD_DO_DIGICAM_CONFIGURE
<<
MAV_CMD_DO_DIGICAM_CONTROL
<<
MAV_CMD_DO_MOUNT_CONTROL
<<
MAV_CMD_CONDITION_DELAY
<<
MAV_CMD_CONDITION_CHANGE_ALT
<<
MAV_CMD_CONDITION_DISTANCE
<<
MAV_CMD_CONDITION_YAW
;
<<
MAV_CMD_DO_SET_HOME
<<
MAV_CMD_DO_LAND_START
<<
MAV_CMD_DO_FENCE_ENABLE
<<
MAV_CMD_DO_PARACHUTE
<<
MAV_CMD_DO_INVERTED_FLIGHT
<<
MAV_CMD_DO_GRIPPER
<<
MAV_CMD_CONDITION_DELAY
<<
MAV_CMD_CONDITION_CHANGE_ALT
<<
MAV_CMD_CONDITION_DISTANCE
<<
MAV_CMD_CONDITION_YAW
<<
MAV_CMD_NAV_VTOL_TAKEOFF
<<
MAV_CMD_NAV_VTOL_LAND
<<
MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT
;
return
list
;
}
...
...
src/FirmwarePlugin/APM/MavCmdInfoCommon.json
View file @
068a385b
...
...
@@ -16,6 +16,24 @@
"default"
:
0.26179939
,
"decimalPlaces"
:
2
}
},
{
"id"
:
84
,
"rawName"
:
"MAV_CMD_NAV_VTOL_TAKEOFF"
,
"friendlyName"
:
"VTOL takeoff"
,
"description"
:
"Takeoff from ground using VTOL mode."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"VTOL"
},
{
"id"
:
85
,
"rawName"
:
"MAV_CMD_NAV_VTOL_LAND"
,
"friendlyName"
:
"VTOL land"
,
"description"
:
"Land using VTOL mode."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"VTOL"
}
]
}
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
068a385b
...
...
@@ -215,14 +215,15 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
list
<<
MAV_CMD_NAV_WAYPOINT
<<
MAV_CMD_NAV_LOITER_UNLIM
<<
MAV_CMD_NAV_LOITER_TIME
<<
MAV_CMD_NAV_RETURN_TO_LAUNCH
<<
MAV_CMD_NAV_LAND
<<
MAV_CMD_NAV_TAKEOFF
<<
MAV_CMD_NAV_LAND
<<
MAV_CMD_NAV_TAKEOFF
<<
MAV_CMD_NAV_ROI
<<
MAV_CMD_DO_JUMP
<<
MAV_CMD_CONDITION_DELAY
<<
MAV_CMD_DO_VTOL_TRANSITION
<<
MAV_CMD_DO_VTOL_TRANSITION
<<
MAV_CMD_NAV_VTOL_TAKEOFF
<<
MAV_CMD_NAV_VTOL_LAND
<<
MAV_CMD_DO_DIGICAM_CONTROL
<<
MAV_CMD_DO_SET_SERVO
<<
MAV_CMD_DO_CHANGE_SPEED
;
<<
MAV_CMD_DO_CHANGE_SPEED
<<
MAV_CMD_NAV_PATHPLANNING
;
return
list
;
}
...
...
src/MissionManager/MavCmdInfoCommon.json
View file @
068a385b
...
...
@@ -50,7 +50,7 @@
"description"
:
"Travel to a position and Loiter around the specified radius indefinitely."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"
Basic
"
,
"category"
:
"
Loiter
"
,
"param3"
:
{
"label"
:
"Radius:"
,
"units"
:
"meters"
,
...
...
@@ -65,7 +65,7 @@
"description"
:
"Travel to a position and Loiter around the specified radius for a number of turns."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"
Basic
"
,
"category"
:
"
Loiter
"
,
"param1"
:
{
"label"
:
"Turns:"
,
"default"
:
1
,
...
...
@@ -85,7 +85,7 @@
"description"
:
"Travel to a position and Loiter around the specified radius for an amount of time."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"
Basic
"
,
"category"
:
"
Loiter
"
,
"param1"
:
{
"label"
:
"Hold:"
,
"units"
:
"seconds"
,
...
...
@@ -152,8 +152,50 @@
{
"id"
:
23
,
"rawName"
:
"MAV_CMD_NAV_LAND_LOCAL"
,
"friendlyName"
:
"MAV_CMD_NAV_LAND_LOCAL"
},
{
"id"
:
24
,
"rawName"
:
"MAV_CMD_NAV_TAKEOFF_LOCAL"
,
"friendlyName"
:
"MAV_CMD_NAV_TAKEOFF_LOCAL"
},
{
"id"
:
25
,
"rawName"
:
"MAV_CMD_NAV_FOLLOW"
,
"friendlyName"
:
"MAV_CMD_NAV_FOLLOW"
},
{
"id"
:
30
,
"rawName"
:
"MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT"
,
"friendlyName"
:
"MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT"
},
{
"id"
:
31
,
"rawName"
:
"MAV_CMD_NAV_LOITER_TO_ALT"
},
{
"id"
:
30
,
"rawName"
:
"MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT"
,
"friendlyName"
:
"Change Altitude"
,
"description"
:
"Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command."
,
"specifiesCoordinate"
:
false
,
"friendlyEdit"
:
true
,
"category"
:
"Flight control"
,
"param1"
:
{
"label"
:
"Mode:"
,
"enumStrings"
:
"Climb,Neutral,Descend"
,
"enumValues"
:
"1,0,2"
,
"default"
:
1
,
"decimalPlaces"
:
0
},
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"meters"
,
"default"
:
55
,
"decimalPlaces"
:
2
}
},
{
"id"
:
31
,
"rawName"
:
"MAV_CMD_NAV_LOITER_TO_ALT"
,
"friendlyName"
:
"Loiter (altitude)"
,
"description"
:
"Loiter at specified position until altitude reached."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Loiter"
,
"param1"
:
{
"label"
:
"Heading wait:"
,
"enumStrings"
:
"False,True"
,
"enumValues"
:
"0,1"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
"param2"
:
{
"label"
:
"Radius:"
,
"units"
:
"meters"
,
"default"
:
10.0
,
"decimalPlaces"
:
2
}
},
{
"id"
:
80
,
"rawName"
:
"MAV_CMD_NAV_ROI"
,
...
...
@@ -181,9 +223,81 @@
"decimalPlaces"
:
0
}
},
{
"id"
:
81
,
"rawName"
:
"MAV_CMD_NAV_PATHPLANNING"
,
"friendlyName"
:
"MAV_CMD_NAV_PATHPLANNING"
},
{
"id"
:
82
,
"rawName"
:
"MAV_CMD_NAV_SPLINE_WAYPOINT"
,
"friendlyName"
:
"MAV_CMD_NAV_SPLINE_WAYPOINT"
},
{
"id"
:
81
,
"rawName"
:
"MAV_CMD_NAV_PATHPLANNING"
,
"friendlyName"
:
"Path planning"
,
"description"
:
"Control autonomous path planning."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Advanced"
,
"param1"
:
{
"label"
:
"Local planning:"
,
"enumStrings"
:
"Disable,Enable,Enable+reset"
,
"enumValues"
:
"0,1,2"
,
"default"
:
1
,
"decimalPlaces"
:
0
},
"param2"
:
{
"label"
:
"Full planning:"
,
"enumStrings"
:
"Disable,Enable,Enable+reset,Enable+reset route only"
,
"enumValues"
:
"0,1,2,3"
,
"default"
:
1
,
"decimalPlaces"
:
0
},
"param4"
:
{
"label"
:
"Heading goal:"
,
"default"
:
0
,
"units"
:
"degrees"
,
"decimalPlaces"
:
2
}
},
{
"id"
:
82
,
"rawName"
:
"MAV_CMD_NAV_SPLINE_WAYPOINT"
,
"friendlyName"
:
"Spline waypoint"
,
"description"
:
"Travel to a position in 3D space using spline path."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param1"
:
{
"label"
:
"Hold:"
,
"units"
:
"seconds"
,
"default"
:
0
,
"decimalPlaces"
:
0
}
},
{
"id"
:
83
,
"rawName"
:
"MAV_CMD_NAV_ALTITUDE_WAIT"
,
"friendlyName"
:
"MAV_CMD_NAV_ALTITUDE_WAIT"
},
{
"id"
:
84
,
"rawName"
:
"MAV_CMD_NAV_VTOL_TAKEOFF"
,
"friendlyName"
:
"VTOL takeoff"
,
"description"
:
"Takeoff from ground using VTOL mode."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"VTOL"
,
"param4"
:
{
"label"
:
"Heading:"
,
"units"
:
"degrees"
,
"default"
:
0.0
,
"decimalPlaces"
:
2
}
},
{
"id"
:
85
,
"rawName"
:
"MAV_CMD_NAV_VTOL_LAND"
,
"friendlyName"
:
"VTOL land"
,
"description"
:
"Land using VTOL mode."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"VTOL"
,
"param4"
:
{
"label"
:
"Heading:"
,
"units"
:
"degrees"
,
"default"
:
0.0
,
"decimalPlaces"
:
2
}
},
{
"id"
:
92
,
"rawName"
:
"MAV_CMD_NAV_GUIDED_ENABLE"
,
...
...
@@ -296,6 +410,7 @@
"rawName"
:
"MAV_CMD_DO_CHANGE_SPEED"
,
"friendlyName"
:
"Change speed"
,
"description"
:
"Change speed and/or throttle set points."
,
"category"
:
"Flight control"
,
"param1"
:
{
"label"
:
"Type:"
,
"enumStrings"
:
"Airspeed,Ground Speed"
,
...
...
@@ -313,7 +428,23 @@
"default"
:
-1
}
},
{
"id"
:
179
,
"rawName"
:
"MAV_CMD_DO_SET_HOME"
,
"friendlyName"
:
"MAV_CMD_DO_SET_HOME"
},
{
"id"
:
179
,
"rawName"
:
"MAV_CMD_DO_SET_HOME"
,
"friendlyName"
:
"Set home location"
,
"description"
:
"Changes the home location either to the current location or a specified location."
,
"specifiesCoordinate"
:
true
,
"standaloneCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Advanced"
,
"param1"
:
{
"label"
:
"Mode:"
,
"enumStrings"
:
"Vehicle position,Specified position"
,
"enumValues"
:
"1,0"
,
"default"
:
0
,
"decimalPlaces"
:
0
}
},
{
"id"
:
180
,
"rawName"
:
"MAV_CMD_DO_SET_PARAMETER"
,
"friendlyName"
:
"MAV_CMD_DO_SET_PARAMETER"
},
{
"id"
:
181
,
...
...
@@ -399,7 +530,15 @@
}
},
{
"id"
:
185
,
"rawName"
:
"MAV_CMD_DO_FLIGHTTERMINATION"
,
"friendlyName"
:
"MAV_CMD_DO_FLIGHTTERMINATION"
},
{
"id"
:
189
,
"rawName"
:
"MAV_CMD_DO_LAND_START"
,
"friendlyName"
:
"MAV_CMD_DO_LAND_START"
},
{
"id"
:
189
,
"rawName"
:
"MAV_CMD_DO_LAND_START"
,
"friendlyName"
:
"Land start"
,
"description"
:
"Marker to indicate start of landing sequence."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
},
{
"id"
:
190
,
"rawName"
:
"MAV_CMD_DO_RALLY_LAND"
,
"friendlyName"
:
"MAV_CMD_DO_RALLY_LAND"
},
{
"id"
:
191
,
"rawName"
:
"MAV_CMD_DO_GO_AROUND"
,
"friendlyName"
:
"MAV_CMD_DO_GO_AROUND"
},
{
"id"
:
200
,
"rawName"
:
"MAV_CMD_DO_CONTROL_VIDEO"
,
"friendlyName"
:
"MAV_CMD_DO_CONTROL_VIDEO"
},
...
...
@@ -554,16 +693,82 @@
"decimalPlaces"
:
2
}
},
{
"id"
:
207
,
"rawName"
:
"MAV_CMD_DO_FENCE_ENABLE"
,
"friendlyName"
:
"MAV_CMD_DO_FENCE_ENABLE"
},
{
"id"
:
208
,
"rawName"
:
"MAV_CMD_DO_PARACHUTE"
,
"friendlyName"
:
"MAV_CMD_DO_PARACHUTE"
},
{
"id"
:
207
,
"rawName"
:
"MAV_CMD_DO_FENCE_ENABLE"
,
"friendlyName"
:
"Enable geofence"
,
"description"
:
"Enable/Disable geofence."
,
"specifiesCoordinate"
:
false
,
"friendlyEdit"
:
true
,
"category"
:
"Safety"
,
"param1"
:
{
"label"
:
"Enable:"
,
"enumStrings"
:
"Disable,Disable floor only,Enable"
,
"enumValues"
:
"0,2,1"
,
"default"
:
1
,
"decimalPlaces"
:
0
}
},
{
"id"
:
208
,
"rawName"
:
"MAV_CMD_DO_PARACHUTE"
,
"friendlyName"
:
"Trigger parachute"
,
"description"
:
"Enable/Disable geofence."
,
"specifiesCoordinate"
:
false
,
"friendlyEdit"
:
true
,
"category"
:
"Safety"
,
"param1"
:
{
"label"
:
"Trigger:"
,
"enumStrings"
:
"Disable,Enable,Release"
,
"enumValues"
:
"0,1,2"
,
"default"
:
1
,
"decimalPlaces"
:
0
}
},
{
"id"
:
209
,
"rawName"
:
"MAV_CMD_DO_MOTOR_TEST"
,
"friendlyName"
:
"MAV_CMD_DO_MOTOR_TEST"
},
{
"id"
:
210
,
"rawName"
:
"MAV_CMD_DO_INVERTED_FLIGHT"
,
"friendlyName"
:
"MAV_CMD_DO_INVERTED_FLIGHT"
},
{
"id"
:
210
,
"rawName"
:
"MAV_CMD_DO_INVERTED_FLIGHT"
,
"friendlyName"
:
"Inverted flight"
,
"description"
:
"Change to/from inverted flight."
,
"specifiesCoordinate"
:
false
,
"friendlyEdit"
:
true
,
"category"
:
"Flight control"
,
"param1"
:
{
"label"
:
"Inverted:"
,
"enumStrings"
:
"Normal,Inverted"
,
"enumValues"
:
"0,1"
,
"default"
:
0
,
"decimalPlaces"
:
0
}
},
{
"id"
:
211
,
"rawName"
:
"MAV_CMD_DO_GRIPPER"
,
"friendlyName"
:
"Gripper"
,
"description"
:
"Operate EPM gripper."
,
"specifiesCoordinate"
:
false
,
"friendlyEdit"
:
true
,
"category"
:
"Advanced"
,
"param1"
:
{
"label"
:
"Gripper id:"
,
"default"
:
1
,
"decimalPlaces"
:
0
},
"param2"
:
{
"label"
:
"Action:"
,
"enumStrings"
:
"Release,Grab"
,
"enumValues"
:
"0,1"
,
"default"
:
0
,
"decimalPlaces"
:
0
}
},
{
"id"
:
220
,
"rawName"
:
"MAV_CMD_DO_MOUNT_CONTROL_QUAT"
,
"friendlyName"
:
"MAV_CMD_DO_MOUNT_CONTROL_QUAT"
},
{
"id"
:
221
,
"rawName"
:
"MAV_CMD_DO_GUIDED_MASTER"
,
"friendlyName"
:
"MAV_CMD_DO_GUIDED_MASTER"
},
{
"id"
:
222
,
"rawName"
:
"MAV_CMD_DO_GUIDED_LIMITS"
,
"friendlyName"
:
"
External control
limits"
,
"friendlyName"
:
"
Guided
limits"
,
"description"
:
"Set limits for external control"
,
"param1"
:
{
"label"
:
"Timeout:"
,
...
...
@@ -579,8 +784,9 @@
},
"param3"
:
{
"label"
:
"Max Alt:"
,
"units"
:
"m(AMSL)"
,
"default"
:
100
,
"decimalPlaces"
:
7
"decimalPlaces"
:
2
},
"param4"
:
{
"label"
:
"H Limit:"
,
...
...
@@ -603,7 +809,7 @@
"rawName"
:
"MAV_CMD_DO_VTOL_TRANSITION"
,
"friendlyName"
:
"VTOL Transition"
,
"description"
:
"Perform flight mode transition"
,
"category"
:
"
Basic
"
,
"category"
:
"
VTOL
"
,
"param1"
:
{
"label"
:
"Mode:"
,
"default"
:
3
,
...
...
src/MissionManager/MissionCommands.cc
View file @
068a385b
...
...
@@ -77,10 +77,14 @@ void MissionCommands::_createCategories(void)
foreach
(
MAV_CMD
command
,
cmdList
)
{
MavCmdInfo
*
mavCmdInfo
=
_commonMissionCommands
.
getMavCmdInfo
(
command
);
if
(
mavCmdInfo
)
{
if
(
mavCmdInfo
->
friendlyEdit
())
{
_categoryToMavCmdListMap
[
firmwareType
][
mavCmdInfo
->
category
()].
append
(
command
);
}
else
if
(
!
allCommandsSupported
)
{
qWarning
()
<<
"Attempt to add non friendly edit supported command"
;
qWarning
()
<<
"Attempt to add non friendly edit supported command"
<<
command
;
}
}
else
{
qCDebug
(
MissionCommandsLog
)
<<
"Command missing from json"
<<
command
;
}
}
}
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment