Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
41a81a78
Commit
41a81a78
authored
Dec 02, 2015
by
Don Gagne
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #2326 from DonLakeFlyer/APMMissionFriendly
Friendly edit for APM supported mission items
parents
7e110aa4
51d0f00e
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
486 additions
and
105 deletions
+486
-105
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+10
-3
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+8
-2
MavCmdInfo.json
src/MissionManager/MavCmdInfo.json
+338
-22
MissionItem.cc
src/MissionManager/MissionItem.cc
+95
-65
MissionItem.h
src/MissionManager/MissionItem.h
+16
-8
MissionItemEditor.qml
src/QmlControls/MissionItemEditor.qml
+19
-5
No files found.
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
41a81a78
...
...
@@ -394,8 +394,15 @@ QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void)
{
QList
<
MAV_CMD
>
list
;
// FIXME: Temp list, just dup of PX4
list
<<
MAV_CMD_NAV_WAYPOINT
<<
MAV_CMD_NAV_LOITER_UNLIM
<<
MAV_CMD_NAV_LOITER_TURNS
<<
MAV_CMD_NAV_LOITER_TIME
<<
MAV_CMD_NAV_RETURN_TO_LAUNCH
<<
MAV_CMD_NAV_LAND
<<
MAV_CMD_NAV_TAKEOFF
<<
MAV_CMD_CONDITION_DELAY
<<
MAV_CMD_DO_JUMP
;
list
<<
MAV_CMD_NAV_WAYPOINT
<<
MAV_CMD_NAV_LOITER_UNLIM
<<
MAV_CMD_NAV_LOITER_TURNS
<<
MAV_CMD_NAV_LOITER_TIME
<<
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
<<
MAV_CMD_DO_SET_RELAY
<<
MAV_CMD_DO_REPEAT_RELAY
<<
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
;
return
list
;
}
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
41a81a78
...
...
@@ -214,8 +214,14 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
list
<<
MAV_CMD_NAV_WAYPOINT
<<
MAV_CMD_NAV_LOITER_UNLIM
<<
MAV_CMD_NAV_LOITER_TURNS
<<
MAV_CMD_NAV_LOITER_TIME
<<
MAV_CMD_NAV_RETURN_TO_LAUNCH
<<
MAV_CMD_NAV_LAND
<<
MAV_CMD_NAV_TAKEOFF
<<
MAV_CMD_NAV_ROI
<<
MAV_CMD_NAV_LAND
<<
MAV_CMD_NAV_TAKEOFF
<<
MAV_CMD_DO_JUMP
<<
MAV_CMD_DO_SET_SERVO
;
<<
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
<<
MAV_CMD_DO_SET_RELAY
<<
MAV_CMD_DO_REPEAT_RELAY
<<
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
;
return
list
;
}
src/MissionManager/MavCmdInfo.json
View file @
41a81a78
...
...
@@ -5,9 +5,10 @@
{
"comment"
:
"MAV_CMD_NAV_LAST: Used for fake home position waypoint"
,
"id"
:
95
,
"rawName"
:
"Home"
,
"rawName"
:
"Home
Raw
"
,
"friendlyName"
:
"Home"
,
"description"
:
"Home Position"
,
"description"
:
"Home Position"
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
},
...
...
@@ -100,7 +101,7 @@
},
"param4"
:
{
"label"
:
"Heading:"
,
"units"
:
"degrees"
,
"units"
:
"degrees
Convert
"
,
"default"
:
0.0
,
"decimalPlaces"
:
2
}
...
...
@@ -114,13 +115,13 @@
"friendlyEdit"
:
true
,
"param1"
:
{
"label"
:
"Pitch:"
,
"units"
:
"degrees"
,
"units"
:
"degrees
Convert
"
,
"default"
:
0.26179939
,
"decimalPlaces"
:
2
},
"param4"
:
{
"label"
:
"Heading:"
,
"units"
:
"degrees"
,
"units"
:
"degrees
Convert
"
,
"default"
:
0.0
,
"decimalPlaces"
:
2
}
...
...
@@ -133,7 +134,7 @@
{
"id"
:
80
,
"rawName"
:
"MAV_CMD_NAV_ROI"
,
"friendlyName"
:
"Region of interest"
,
"friendlyName"
:
"Region of interest
(nav)
"
,
"description"
:
"Sets the region of interest for cameras."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
...
...
@@ -150,7 +151,7 @@
"decimalPlaces"
:
0
},
"param3"
:
{
"label"
:
"ROI
i
ndex:"
,
"label"
:
"ROI
I
ndex:"
,
"default"
:
0
,
"decimalPlaces"
:
0
}
...
...
@@ -158,7 +159,17 @@
{
"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"
:
83
,
"rawName"
:
"MAV_CMD_NAV_ALTITUDE_WAIT", "friendlyName"
:
"MAV_CMD_NAV_ALTITUDE_WAIT"
},
{
"id"
:
92
,
"rawName"
:
"MAV_CMD_NAV_GUIDED_ENABLE", "friendlyName"
:
"MAV_CMD_NAV_GUIDED_ENABLE"
},
{
"id"
:
92
,
"rawName"
:
"MAV_CMD_NAV_GUIDED_ENABLE"
,
"friendlyName"
:
"Guided enable"
,
"description"
:
"Enable/Disabled guided mode."
,
"param1"
:
{
"label"
:
"Enable:"
,
"default"
:
1
,
"decimalPlaces"
:
0
}
},
{
"id"
:
112
,
"rawName"
:
"MAV_CMD_CONDITION_DELAY"
,
...
...
@@ -172,9 +183,65 @@
"decimalPlaces"
:
0
}
},
{
"id"
:
113
,
"rawName"
:
"MAV_CMD_CONDITION_CHANGE_ALT", "friendlyName"
:
"MAV_CMD_CONDITION_CHANGE_ALT"
},
{
"id"
:
114
,
"rawName"
:
"MAV_CMD_CONDITION_DISTANCE", "friendlyName"
:
"MAV_CMD_CONDITION_DISTANCE"
},
{
"id"
:
115
,
"rawName"
:
"MAV_CMD_CONDITION_YAW", "friendlyName"
:
"MAV_CMD_CONDITION_YAW"
},
{
"id"
:
113
,
"rawName"
:
"MAV_CMD_CONDITION_CHANGE_ALT"
,
"description"
:
"Delay the mission until the specified altitide is reached."
,
"friendlyName"
:
"Wait for altitude"
,
"param1"
:
{
"label"
:
"Rate:"
,
"units"
:
"m/s"
,
"default"
:
5
,
"decimalPlaces"
:
2
},
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"meters"
,
"default"
:
55
,
"decimalPlaces"
:
2
}
},
{
"id"
:
114
,
"rawName"
:
"MAV_CMD_CONDITION_DISTANCE"
,
"description"
:
"Delay the mission until within the specified distance of the next waypoint."
,
"friendlyName"
:
"Wait for distance"
,
"param1"
:
{
"label"
:
"Distance:"
,
"units"
:
"meters"
,
"default"
:
0
,
"decimalPlaces"
:
2
}
},
{
"id"
:
115
,
"rawName"
:
"MAV_CMD_CONDITION_YAW"
,
"friendlyName"
:
"Wait for Heading"
,
"description"
:
"Delay the mission until the specified heading is reached."
,
"param1"
:
{
"label"
:
"Heading:"
,
"units"
:
"degrees"
,
"default"
:
0
,
"decimalPlaces"
:
1
},
"param2"
:
{
"label"
:
"Rate:"
,
"units"
:
"degrees/s"
,
"default"
:
5
,
"decimalPlaces"
:
1
},
"param3"
:
{
"label"
:
"Direction:"
,
"default"
:
1
,
"decimalPlaces"
:
0
},
"param3"
:
{
"label"
:
"Offset:"
,
"enumStrings"
:
"Relative,Absolute"
,
"enumValues"
:
"1,0"
,
"default"
:
5
}
},
{
"id"
:
159
,
"rawName"
:
"MAV_CMD_CONDITION_LAST", "friendlyName"
:
"MAV_CMD_CONDITION_LAST"
},
{
"id"
:
176
,
"rawName"
:
"MAV_CMD_DO_SET_MODE", "friendlyName"
:
"MAV_CMD_DO_SET_MODE"
},
{
...
...
@@ -194,11 +261,68 @@
"decimalPlaces"
:
0
}
},
{
"id"
:
178
,
"rawName"
:
"MAV_CMD_DO_CHANGE_SPEED", "friendlyName"
:
"MAV_CMD_DO_CHANGE_SPEED"
},
{
"id"
:
178
,
"rawName"
:
"MAV_CMD_DO_CHANGE_SPEED"
,
"friendlyName"
:
"Change speed"
,
"description"
:
"Change speed and/or throttle set points."
,
"param1"
:
{
"label"
:
"Type:"
,
"enumStrings"
:
"Airspeed,Ground Speed"
,
"enumValues"
:
"0,1"
,
"default"
:
1
},
"param2"
:
{
"label"
:
"Speed:"
,
"units"
:
"m/s"
,
"default"
:
-1
},
"param3"
:
{
"label"
:
"Throttle:"
,
"units"
:
"%"
,
"default"
:
-1
}
},
{
"id"
:
179
,
"rawName"
:
"MAV_CMD_DO_SET_HOME", "friendlyName"
:
"MAV_CMD_DO_SET_HOME"
},
{
"id"
:
180
,
"rawName"
:
"MAV_CMD_DO_SET_PARAMETER", "friendlyName"
:
"MAV_CMD_DO_SET_PARAMETER"
},
{
"id"
:
181
,
"rawName"
:
"MAV_CMD_DO_SET_RELAY", "friendlyName"
:
"MAV_CMD_DO_SET_RELAY"
},
{
"id"
:
182
,
"rawName"
:
"MAV_CMD_DO_REPEAT_RELAY", "friendlyName"
:
"MAV_CMD_DO_REPEAT_RELAY"
},
{
"id"
:
181
,
"rawName"
:
"MAV_CMD_DO_SET_RELAY"
,
"friendlyName"
:
"Set relay"
,
"description"
:
"Set relay to a condition."
,
"param1"
:
{
"label"
:
"Relay #:"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
"param2"
:
{
"label"
:
"Value:"
,
"default"
:
0
}
},
{
"id"
:
182
,
"rawName"
:
"MAV_CMD_DO_REPEAT_RELAY"
,
"friendlyName"
:
"Cycle relay"
,
"description"
:
"Cycle relay on/off for desired cycles/time."
,
"param1"
:
{
"label"
:
"Relay #:"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
"param2"
:
{
"label"
:
"Cycles:"
,
"default"
:
1
,
"units"
:
"count"
,
"decimalPlaces"
:
0
},
"param3"
:
{
"label"
:
"Time:"
,
"default"
:
10
,
"units"
:
"seconds"
,
"decimalPlaces"
:
0
}
},
{
"id"
:
183
,
"rawName"
:
"MAV_CMD_DO_SET_SERVO"
,
...
...
@@ -216,27 +340,219 @@
"decimalPlaces"
:
0
}
},
{
"id"
:
184
,
"rawName"
:
"MAV_CMD_DO_REPEAT_SERVO", "friendlyName"
:
"MAV_CMD_DO_REPEAT_SERVO"
},
{
"id"
:
184
,
"rawName"
:
"MAV_CMD_DO_REPEAT_SERVO"
,
"friendlyName"
:
"Cycle servo"
,
"description"
:
"Set servo to specified PWM value."
,
"param1"
:
{
"label"
:
"Servo:"
,
"default"
:
1
,
"decimalPlaces"
:
0
},
"param2"
:
{
"label"
:
"PWM:"
,
"default"
:
1000
,
"decimalPlaces"
:
0
},
"param3"
:
{
"label"
:
"Cycles:"
,
"default"
:
1
,
"units"
:
"count"
,
"decimalPlaces"
:
0
},
"param4"
:
{
"label"
:
"Time:"
,
"default"
:
10
,
"units"
:
"seconds"
,
"decimalPlaces"
:
0
}
},
{
"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"
:
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"
},
{
"id"
:
201
,
"rawName"
:
"MAV_CMD_DO_SET_ROI", "friendlyName"
:
"MAV_CMD_DO_SET_ROI"
},
{
"id"
:
202
,
"rawName"
:
"MAV_CMD_DO_DIGICAM_CONFIGURE", "friendlyName"
:
"MAV_CMD_DO_DIGICAM_CONFIGURE"
},
{
"id"
:
203
,
"rawName"
:
"MAV_CMD_DO_DIGICAM_CONTROL", "friendlyName"
:
"MAV_CMD_DO_DIGICAM_CONTROL"
},
{
"id"
:
201
,
"rawName"
:
"MAV_CMD_DO_SET_ROI"
,
"friendlyName"
:
"Region of interest (cmd)"
,
"description"
:
"Sets the region of interest for cameras."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"param1"
:
{
"label"
:
"Mode:"
,
"enumStrings"
:
"None,Next waypoint,Mission item,Location,ROI item"
,
"enumValues"
:
"0,1,2,3,4"
,
"default"
:
3
,
"decimalPlaces"
:
0
},
"param2"
:
{
"label"
:
"Mission Index:"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
"param3"
:
{
"label"
:
"ROI Index:"
,
"default"
:
0
,
"decimalPlaces"
:
0
}
},
{
"id"
:
202
,
"rawName"
:
"MAV_CMD_DO_DIGICAM_CONFIGURE"
,
"friendlyName"
:
"Camera config"
,
"description"
:
"Configure onboard camera controller."
,
"param1"
:
{
"label"
:
"Mode:"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
"param2"
:
{
"label"
:
"Shutter spd:"
,
"default"
:
60
,
"units"
:
"1/secs"
,
"decimalPlaces"
:
0
},
"param3"
:
{
"label"
:
"Aperture:"
,
"default"
:
4
,
"units"
:
"F stop"
,
"decimalPlaces"
:
1
},
"param4"
:
{
"label"
:
"ISO:"
,
"default"
:
200
,
"decimalPlaces"
:
0
},
"param5"
:
{
"label"
:
"Exposure:"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
"param6"
:
{
"label"
:
"Command:"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
"param7"
:
{
"label"
:
"Cut off:"
,
"default"
:
0
,
"decimalPlaces"
:
2
}
},
{
"id"
:
203
,
"friendlyName"
:
"Camera control"
,
"rawName"
:
"MAV_CMD_DO_DIGICAM_CONTROL"
,
"description"
:
"Control onboard camera."
,
"param1"
:
{
"label"
:
"Session:"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
"param2"
:
{
"label"
:
"Zoom:"
,
"default"
:
0
,
"decimalPlaces"
:
3
},
"param3"
:
{
"label"
:
"Step:"
,
"default"
:
0
,
"decimalPlaces"
:
3
},
"param4"
:
{
"label"
:
"Focus lock:"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
"param5"
:
{
"label"
:
"Command:"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
"param6"
:
{
"label"
:
"Id:"
,
"default"
:
0
,
"decimalPlaces"
:
0
}
},
{
"id"
:
204
,
"rawName"
:
"MAV_CMD_DO_MOUNT_CONFIGURE", "friendlyName"
:
"MAV_CMD_DO_MOUNT_CONFIGURE"
},
{
"id"
:
205
,
"rawName"
:
"MAV_CMD_DO_MOUNT_CONTROL", "friendlyName"
:
"MAV_CMD_DO_MOUNT_CONTROL"
},
{
"id"
:
206
,
"rawName"
:
"MAV_CMD_DO_SET_CAM_TRIGG_DIST", "friendlyName"
:
"MAV_CMD_DO_SET_CAM_TRIGG_DIST"
},
{
"id"
:
205
,
"rawName"
:
"MAV_CMD_DO_MOUNT_CONTROL"
,
"friendlyName"
:
"Mount config"
,
"description"
:
"Control antenna mount or camera."
,
"param1"
:
{
"label"
:
"Lat/Pitch:"
,
"default"
:
0
,
"decimalPlaces"
:
7
},
"param2"
:
{
"label"
:
"Lon/Roll:"
,
"default"
:
0
,
"decimalPlaces"
:
7
},
"param3"
:
{
"label"
:
"Alt/Yaw:"
,
"default"
:
0
,
"decimalPlaces"
:
7
},
"param7"
:
{
"label"
:
"Mode:"
,
"default"
:
0
,
"decimalPlaces"
:
0
,
"enumStrings"
:
"Retract,Neutral,Mavlink Targetting,RC Targetting, GPS Point"
,
"enumValues"
:
"0,1,2,3,4"
}
},
{
"id"
:
206
,
"rawName"
:
"MAV_CMD_DO_SET_CAM_TRIGG_DIST"
,
"friendlyName"
:
"Camera trigger distance"
,
"description"
:
"Set camera trigger distance."
,
"param1"
:
{
"label"
:
"Distance:"
,
"default"
:
25
,
"units"
:
"meters"
,
"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"
:
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"
:
211
,
"rawName"
:
"MAV_CMD_DO_GRIPPER", "friendlyName"
:
"MAV_CMD_DO_GRIPPER"
},
{
"id"
:
212
,
"rawName"
:
"MAV_CMD_DO_AUTOTUNE_ENABLE", "friendlyName"
:
"MAV_CMD_DO_AUTOTUNE_ENABLE"
},
{
"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"
:
"MAV_CMD_DO_GUIDED_LIMITS"
},
{
"id"
:
222
,
"rawName"
:
"MAV_CMD_DO_GUIDED_LIMITS"
,
"friendlyName"
:
"Exetrnal control limits"
,
"description"
:
"Set limits for external control"
,
"param1"
:
{
"label"
:
"Timeout:"
,
"default"
:
0
,
"units"
:
"seconds"
,
"decimalPlaces"
:
0
},
"param2"
:
{
"label"
:
"Min Alt:"
,
"default"
:
25
,
"units"
:
"m(AMSL)"
,
"decimalPlaces"
:
2
},
"param3"
:
{
"label"
:
"Max Alt:"
,
"default"
:
100
,
"decimalPlaces"
:
7
},
"param4"
:
{
"label"
:
"H Limit:"
,
"default"
:
25
,
"units"
:
"m(AMSL)"
,
"decimalPlaces"
:
2
}
},
{
"id"
:
252
,
"rawName"
:
"MAV_CMD_OVERRIDE_GOTO", "friendlyName"
:
"MAV_CMD_OVERRIDE_GOTO"
},
{
"id"
:
300
,
"rawName"
:
"MAV_CMD_MISSION_START", "friendlyName"
:
"MAV_CMD_MISSION_START"
},
{
"id"
:
400
,
"rawName"
:
"MAV_CMD_COMPONENT_ARM_DISARM", "friendlyName"
:
"MAV_CMD_COMPONENT_ARM_DISARM"
},
...
...
src/MissionManager/MissionItem.cc
View file @
41a81a78
...
...
@@ -49,6 +49,8 @@ FactMetaData* MissionItem::_supportedCommandMetaData = NULL;
const
QString
MissionItem
::
_decimalPlacesJsonKey
(
QStringLiteral
(
"decimalPlaces"
));
const
QString
MissionItem
::
_defaultJsonKey
(
QStringLiteral
(
"default"
));
const
QString
MissionItem
::
_descriptionJsonKey
(
QStringLiteral
(
"description"
));
const
QString
MissionItem
::
_enumStringsJsonKey
(
QStringLiteral
(
"enumStrings"
));
const
QString
MissionItem
::
_enumValuesJsonKey
(
QStringLiteral
(
"enumValues"
));
const
QString
MissionItem
::
_friendlyEditJsonKey
(
QStringLiteral
(
"friendlyEdit"
));
const
QString
MissionItem
::
_friendlyNameJsonKey
(
QStringLiteral
(
"friendlyName"
));
const
QString
MissionItem
::
_idJsonKey
(
QStringLiteral
(
"id"
));
...
...
@@ -64,6 +66,7 @@ const QString MissionItem::_specifiesCoordinateJsonKey (QStringLiteral("specifi
const
QString
MissionItem
::
_unitsJsonKey
(
QStringLiteral
(
"units"
));
const
QString
MissionItem
::
_versionJsonKey
(
QStringLiteral
(
"version"
));
const
QString
MissionItem
::
_degreesConvertUnits
(
QStringLiteral
(
"degreesConvert"
));
const
QString
MissionItem
::
_degreesUnits
(
QStringLiteral
(
"degrees"
));
QMap
<
MAV_CMD
,
MissionItem
::
MavCmdInfo_t
>
MissionItem
::
_mavCmdInfoMap
;
...
...
@@ -116,8 +119,8 @@ MissionItem::MissionItem(QObject* parent)
,
_homePositionValid
(
false
)
,
_altitudeRelativeToHomeFact
(
0
,
"Altitude is relative to home"
,
FactMetaData
::
valueTypeUint32
)
,
_autoContinueFact
(
0
,
"AutoContinue"
,
FactMetaData
::
valueTypeUint32
)
,
_commandFact
(
0
,
"
Command:"
,
FactMetaData
::
valueTypeUint32
)
,
_frameFact
(
0
,
"
Frame:"
,
FactMetaData
::
valueTypeUint32
)
,
_commandFact
(
0
,
"
"
,
FactMetaData
::
valueTypeUint32
)
,
_frameFact
(
0
,
"
"
,
FactMetaData
::
valueTypeUint32
)
,
_param1Fact
(
0
,
"Param1:"
,
FactMetaData
::
valueTypeDouble
)
,
_param2Fact
(
0
,
"Param2:"
,
FactMetaData
::
valueTypeDouble
)
,
_param3Fact
(
0
,
"Param3:"
,
FactMetaData
::
valueTypeDouble
)
...
...
@@ -130,6 +133,9 @@ MissionItem::MissionItem(QObject* parent)
,
_param2MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_param3MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_param4MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_param5MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_param6MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_param7MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_syncingAltitudeRelativeToHomeAndFrame
(
false
)
,
_syncingHeadingDegreesAndParam4
(
false
)
,
_syncingSupportedCommandAndCommand
(
false
)
...
...
@@ -177,6 +183,9 @@ MissionItem::MissionItem(int sequenceNumber,
,
_param2MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_param3MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_param4MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_param5MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_param6MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_param7MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_syncingAltitudeRelativeToHomeAndFrame
(
false
)
,
_syncingHeadingDegreesAndParam4
(
false
)
,
_syncingSupportedCommandAndCommand
(
false
)
...
...
@@ -293,6 +302,9 @@ void MissionItem::_connectSignals(void)
connect
(
&
_commandFact
,
&
Fact
::
valueChanged
,
this
,
&
MissionItem
::
_sendFriendlyEditAllowedChanged
);
connect
(
&
_frameFact
,
&
Fact
::
valueChanged
,
this
,
&
MissionItem
::
_sendFriendlyEditAllowedChanged
);
// When the command changes we need to set defaults. This must go out before the signals below so it must be registered first.
connect
(
&
_commandFact
,
&
Fact
::
valueChanged
,
this
,
&
MissionItem
::
setDefaultsForCommand
);
// Whenever these properties change the ui model changes as well
connect
(
this
,
&
MissionItem
::
commandChanged
,
this
,
&
MissionItem
::
_sendUiModelChanged
);
connect
(
this
,
&
MissionItem
::
rawEditChanged
,
this
,
&
MissionItem
::
_sendUiModelChanged
);
...
...
@@ -301,8 +313,6 @@ void MissionItem::_connectSignals(void)
connect
(
&
_commandFact
,
&
Fact
::
valueChanged
,
this
,
&
MissionItem
::
_sendCommandChanged
);
connect
(
&
_frameFact
,
&
Fact
::
valueChanged
,
this
,
&
MissionItem
::
_sendFrameChanged
);
// When the command changes we need to set defaults
connect
(
&
_commandFact
,
&
Fact
::
valueChanged
,
this
,
&
MissionItem
::
setDefaultsForCommand
);
}
bool
MissionItem
::
_validateKeyTypes
(
QJsonObject
&
jsonObject
,
const
QStringList
&
keys
,
const
QList
<
QJsonValue
::
Type
>&
types
)
...
...
@@ -398,7 +408,7 @@ bool MissionItem::_loadMavCmdInfoJson(void)
// Read params
for
(
int
i
=
1
;
i
<
5
;
i
++
)
{
for
(
int
i
=
1
;
i
<
=
7
;
i
++
)
{
QString
paramKey
=
QString
(
_paramJsonKeyFormat
).
arg
(
i
);
if
(
jsonObject
.
contains
(
paramKey
))
{
...
...
@@ -407,8 +417,8 @@ bool MissionItem::_loadMavCmdInfoJson(void)
// Validate key types
QStringList
keys
;
QList
<
QJsonValue
::
Type
>
types
;
keys
<<
_
labelJsonKey
<<
_unitsJsonKey
<<
_defaultJsonKey
<<
_decimalPlace
sJsonKey
;
types
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
Double
<<
QJsonValue
::
Double
;
keys
<<
_
defaultJsonKey
<<
_decimalPlacesJsonKey
<<
_enumStringsJsonKey
<<
_enumValuesJsonKey
<<
_labelJsonKey
<<
_unit
sJsonKey
;
types
<<
QJsonValue
::
Double
<<
QJsonValue
::
Double
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
String
;
if
(
!
_validateKeyTypes
(
paramObject
,
keys
,
types
))
{
return
false
;
}
...
...
@@ -420,10 +430,41 @@ bool MissionItem::_loadMavCmdInfoJson(void)
return
false
;
}
_mavCmdInfoMap
[
mavCmdInfo
.
command
].
paramInfoMap
[
i
].
param
=
i
;
_mavCmdInfoMap
[
mavCmdInfo
.
command
].
paramInfoMap
[
i
].
units
=
paramObject
.
value
(
_unitsJsonKey
).
toString
();
_mavCmdInfoMap
[
mavCmdInfo
.
command
].
friendlyEdit
=
true
;
// Assume friendly edit if we have params
_mavCmdInfoMap
[
mavCmdInfo
.
command
].
paramInfoMap
[
i
].
defaultValue
=
paramObject
.
value
(
_defaultJsonKey
).
toDouble
(
0.0
);
_mavCmdInfoMap
[
mavCmdInfo
.
command
].
paramInfoMap
[
i
].
decimalPlaces
=
paramObject
.
value
(
_decimalPlacesJsonKey
).
toInt
(
FactMetaData
::
defaultDecimalPlaces
);
_mavCmdInfoMap
[
mavCmdInfo
.
command
].
paramInfoMap
[
i
].
enumStrings
=
paramObject
.
value
(
_enumStringsJsonKey
).
toString
().
split
(
","
,
QString
::
SkipEmptyParts
);
_mavCmdInfoMap
[
mavCmdInfo
.
command
].
paramInfoMap
[
i
].
param
=
i
;
_mavCmdInfoMap
[
mavCmdInfo
.
command
].
paramInfoMap
[
i
].
units
=
paramObject
.
value
(
_unitsJsonKey
).
toString
();
QStringList
enumValues
=
paramObject
.
value
(
_enumValuesJsonKey
).
toString
().
split
(
","
,
QString
::
SkipEmptyParts
);
foreach
(
QString
enumValue
,
enumValues
)
{
bool
convertOk
;
double
value
=
enumValue
.
toDouble
(
&
convertOk
);
if
(
!
convertOk
)
{
qWarning
()
<<
"Bad enumValue"
<<
enumValue
;
return
false
;
}
_mavCmdInfoMap
[
mavCmdInfo
.
command
].
paramInfoMap
[
i
].
enumValues
<<
QVariant
(
value
);
}
if
(
_mavCmdInfoMap
[
mavCmdInfo
.
command
].
paramInfoMap
[
i
].
enumStrings
.
count
()
!=
_mavCmdInfoMap
[
mavCmdInfo
.
command
].
paramInfoMap
[
i
].
enumStrings
.
count
())
{
qWarning
()
<<
"enum strings/values count mismatch"
<<
_mavCmdInfoMap
[
mavCmdInfo
.
command
].
paramInfoMap
[
i
].
enumStrings
.
count
()
<<
_mavCmdInfoMap
[
mavCmdInfo
.
command
].
paramInfoMap
[
i
].
enumStrings
.
count
();
return
false
;
}
}
}
if
(
mavCmdInfo
.
friendlyEdit
)
{
if
(
mavCmdInfo
.
description
.
isEmpty
())
{
qWarning
()
<<
"Missing description"
<<
mavCmdInfo
.
rawName
;
return
false
;
}
if
(
mavCmdInfo
.
rawName
==
mavCmdInfo
.
friendlyName
)
{
qWarning
()
<<
"Missing friendly name"
<<
mavCmdInfo
.
rawName
<<
mavCmdInfo
.
friendlyName
;
return
false
;
}
}
}
...
...
@@ -692,48 +733,26 @@ QmlObjectListModel* MissionItem::textFieldFacts(void)
MAV_CMD
command
=
(
MAV_CMD
)
this
->
command
();
if
(
_mavCmdInfoMap
[
command
].
paramInfoMap
.
contains
(
1
))
{
_param1Fact
.
_setName
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
1
].
label
);
_param1MetaData
.
setUnits
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
1
].
units
);
_param1MetaData
.
setDecimalPlaces
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
1
].
decimalPlaces
);
if
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
1
].
units
==
_degreesUnits
)
{
_param1MetaData
.
setTranslators
(
_radiansToDegrees
,
_degreesToRadians
);
}
_param1Fact
.
setMetaData
(
&
_param1MetaData
);
model
->
append
(
&
_param1Fact
);
}
if
(
_mavCmdInfoMap
[
command
].
paramInfoMap
.
contains
(
2
))
{
_param2Fact
.
_setName
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
2
].
label
);
_param2MetaData
.
setUnits
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
2
].
units
);
_param2MetaData
.
setDecimalPlaces
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
2
].
decimalPlaces
);
if
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
2
].
units
==
_degreesUnits
)
{
_param2MetaData
.
setTranslators
(
_radiansToDegrees
,
_degreesToRadians
);
}
_param2Fact
.
setMetaData
(
&
_param2MetaData
);
model
->
append
(
&
_param2Fact
);
}
Fact
*
rgParamFacts
[
7
]
=
{
&
_param1Fact
,
&
_param2Fact
,
&
_param3Fact
,
&
_param4Fact
,
&
_param5Fact
,
&
_param6Fact
,
&
_param7Fact
};
FactMetaData
*
rgParamMetaData
[
7
]
=
{
&
_param1MetaData
,
&
_param2MetaData
,
&
_param3MetaData
,
&
_param4MetaData
,
&
_param5MetaData
,
&
_param6MetaData
,
&
_param7MetaData
};
if
(
_mavCmdInfoMap
[
command
].
paramInfoMap
.
contains
(
3
))
{
_param3Fact
.
_setName
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
3
].
label
);
_param3MetaData
.
setUnits
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
3
].
units
);
_param3MetaData
.
setDecimalPlaces
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
3
].
decimalPlaces
);
if
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
3
].
units
==
_degreesUnits
)
{
_param3MetaData
.
setTranslators
(
_radiansToDegrees
,
_degreesToRadians
);
}
_param3Fact
.
setMetaData
(
&
_param3MetaData
);
model
->
append
(
&
_param3Fact
);
}
for
(
int
i
=
1
;
i
<=
7
;
i
++
)
{
if
(
_mavCmdInfoMap
[
command
].
paramInfoMap
.
contains
(
i
)
&&
_mavCmdInfoMap
[
command
].
paramInfoMap
[
i
].
enumStrings
.
count
()
==
0
)
{
Fact
*
paramFact
=
rgParamFacts
[
i
-
1
];
FactMetaData
*
paramMetaData
=
rgParamMetaData
[
i
-
1
];
if
(
_mavCmdInfoMap
[
command
].
paramInfoMap
.
contains
(
4
))
{
_param4Fact
.
_setName
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
4
].
label
);
_param4MetaData
.
setUnits
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
4
].
units
);
_param4MetaData
.
setDecimalPlaces
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
4
].
decimalPlaces
);
if
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
4
].
units
==
_degreesUnits
)
{
_param4MetaData
.
setTranslators
(
_radiansToDegrees
,
_degreesToRadians
);
paramFact
->
_setName
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
i
].
label
);
paramMetaData
->
setDecimalPlaces
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
i
].
decimalPlaces
);
paramMetaData
->
setEnumInfo
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
i
].
enumStrings
,
_mavCmdInfoMap
[
command
].
paramInfoMap
[
i
].
enumValues
);
if
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
i
].
units
==
_degreesConvertUnits
)
{
paramMetaData
->
setTranslators
(
_radiansToDegrees
,
_degreesToRadians
);
paramMetaData
->
setUnits
(
_degreesUnits
);
}
else
{
paramMetaData
->
setUnits
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
i
].
units
);
}
paramFact
->
setMetaData
(
paramMetaData
);
model
->
append
(
paramFact
);
}
_param4Fact
.
setMetaData
(
&
_param4MetaData
);
model
->
append
(
&
_param4Fact
);
}
if
(
specifiesCoordinate
())
{
...
...
@@ -767,6 +786,30 @@ QmlObjectListModel* MissionItem::comboboxFacts(void)
if
(
rawEdit
())
{
model
->
append
(
&
_commandFact
);
model
->
append
(
&
_frameFact
);
}
else
{
Fact
*
rgParamFacts
[
7
]
=
{
&
_param1Fact
,
&
_param2Fact
,
&
_param3Fact
,
&
_param4Fact
,
&
_param5Fact
,
&
_param6Fact
,
&
_param7Fact
};
FactMetaData
*
rgParamMetaData
[
7
]
=
{
&
_param1MetaData
,
&
_param2MetaData
,
&
_param3MetaData
,
&
_param4MetaData
,
&
_param5MetaData
,
&
_param6MetaData
,
&
_param7MetaData
};
MAV_CMD
command
=
(
MAV_CMD
)
this
->
command
();
for
(
int
i
=
1
;
i
<=
7
;
i
++
)
{
if
(
_mavCmdInfoMap
[
command
].
paramInfoMap
.
contains
(
i
)
&&
_mavCmdInfoMap
[
command
].
paramInfoMap
[
i
].
enumStrings
.
count
())
{
Fact
*
paramFact
=
rgParamFacts
[
i
-
1
];
FactMetaData
*
paramMetaData
=
rgParamMetaData
[
i
-
1
];
paramFact
->
_setName
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
i
].
label
);
paramMetaData
->
setDecimalPlaces
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
i
].
decimalPlaces
);
paramMetaData
->
setEnumInfo
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
i
].
enumStrings
,
_mavCmdInfoMap
[
command
].
paramInfoMap
[
i
].
enumValues
);
if
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
i
].
units
==
_degreesConvertUnits
)
{
paramMetaData
->
setTranslators
(
_radiansToDegrees
,
_degreesToRadians
);
paramMetaData
->
setUnits
(
_degreesUnits
);
}
else
{
paramMetaData
->
setUnits
(
_mavCmdInfoMap
[
command
].
paramInfoMap
[
i
].
units
);
}
paramFact
->
setMetaData
(
paramMetaData
);
model
->
append
(
paramFact
);
}
}
}
return
model
;
...
...
@@ -808,7 +851,7 @@ bool MissionItem::rawEdit(void) const
void
MissionItem
::
setRawEdit
(
bool
rawEdit
)
{
if
(
_rawEdit
!=
rawEdit
)
{
if
(
this
->
rawEdit
()
!=
rawEdit
)
{
_rawEdit
=
rawEdit
;
emit
rawEditChanged
(
this
->
rawEdit
());
}
...
...
@@ -893,22 +936,9 @@ void MissionItem::_syncCommandToSupportedCommand(const QVariant& value)
void
MissionItem
::
setDefaultsForCommand
(
void
)
{
foreach
(
ParamInfo_t
paramInfo
,
_mavCmdInfoMap
[(
MAV_CMD
)
command
()].
paramInfoMap
)
{
double
defaultValue
=
paramInfo
.
defaultValue
;
switch
(
paramInfo
.
param
)
{
case
1
:
_param1Fact
.
setRawValue
(
defaultValue
);
break
;
case
2
:
_param2Fact
.
setRawValue
(
defaultValue
);
break
;
case
3
:
_param3Fact
.
setRawValue
(
defaultValue
);
break
;
case
4
:
_param4Fact
.
setRawValue
(
defaultValue
);
break
;
}
Fact
*
rgParamFacts
[
7
]
=
{
&
_param1Fact
,
&
_param2Fact
,
&
_param3Fact
,
&
_param4Fact
,
&
_param5Fact
,
&
_param6Fact
,
&
_param7Fact
};
rgParamFacts
[
paramInfo
.
param
-
1
]
->
setRawValue
(
paramInfo
.
defaultValue
);
}
setParam7
(
defaultAltitude
);
...
...
src/MissionManager/MissionItem.h
View file @
41a81a78
...
...
@@ -215,21 +215,23 @@ private:
private:
typedef
struct
{
int
param
;
QString
label
;
QString
units
;
double
defaultValue
;
int
decimalPlaces
;
double
defaultValue
;
int
decimalPlaces
;
QStringList
enumStrings
;
QVariantList
enumValues
;
QString
label
;
int
param
;
QString
units
;
}
ParamInfo_t
;
typedef
struct
{
MAV_CMD
command
;
QString
rawName
;
QString
friendlyName
;
QString
description
;
bool
specifiesCoordinate
;
bool
friendlyEdit
;
QString
friendlyName
;
QMap
<
int
,
ParamInfo_t
>
paramInfoMap
;
QString
rawName
;
bool
specifiesCoordinate
;
}
MavCmdInfo_t
;
bool
_rawEdit
;
...
...
@@ -266,6 +268,9 @@ private:
FactMetaData
_param2MetaData
;
FactMetaData
_param3MetaData
;
FactMetaData
_param4MetaData
;
FactMetaData
_param5MetaData
;
FactMetaData
_param6MetaData
;
FactMetaData
_param7MetaData
;
/// This is used to reference any subsequent mission items which do not specify a coordinate.
QmlObjectListModel
_childItems
;
...
...
@@ -279,6 +284,8 @@ private:
static
const
QString
_decimalPlacesJsonKey
;
static
const
QString
_defaultJsonKey
;
static
const
QString
_descriptionJsonKey
;
static
const
QString
_enumStringsJsonKey
;
static
const
QString
_enumValuesJsonKey
;
static
const
QString
_friendlyNameJsonKey
;
static
const
QString
_friendlyEditJsonKey
;
static
const
QString
_idJsonKey
;
...
...
@@ -295,6 +302,7 @@ private:
static
const
QString
_versionJsonKey
;
static
const
QString
_degreesUnits
;
static
const
QString
_degreesConvertUnits
;
};
QDebug
operator
<<
(
QDebug
dbg
,
const
MissionItem
&
missionItem
);
...
...
src/QmlControls/MissionItemEditor.qml
View file @
41a81a78
...
...
@@ -133,11 +133,25 @@ Rectangle {
Repeater
{
model
:
missionItem
.
comboboxFacts
FactComboBox
{
width
:
valuesColumn
.
width
indexModel
:
false
model
:
object
.
enumStrings
fact
:
object
Item
{
width
:
valuesColumn
.
width
height
:
comboBoxFact
.
height
QGCLabel
{
id
:
comboBoxLabel
anchors.baseline
:
comboBoxFact
.
baseline
text
:
object
.
name
visible
:
object
.
name
!=
""
}
FactComboBox
{
id
:
comboBoxFact
anchors.right
:
parent
.
right
width
:
comboBoxLabel
.
visible
?
_editFieldWidth
:
parent
.
width
indexModel
:
false
model
:
object
.
enumStrings
fact
:
object
}
}
}
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a 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