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
0cecf13f
Commit
0cecf13f
authored
Aug 18, 2016
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Major rewrite of Mission Item json editor support
parent
4335dbad
Changes
61
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
61 changed files
with
2138 additions
and
1190 deletions
+2138
-1190
UnitTest.qrc
UnitTest.qrc
+10
-0
qgroundcontrol.pro
qgroundcontrol.pro
+12
-2
qgroundcontrol.qrc
qgroundcontrol.qrc
+11
-0
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+49
-13
APMFirmwarePlugin.h
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
+14
-14
MavCmdInfoCommon.json
src/FirmwarePlugin/APM/MavCmdInfoCommon.json
+61
-31
MavCmdInfoFixedWing.json
src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json
+16
-203
MavCmdInfoMultiRotor.json
src/FirmwarePlugin/APM/MavCmdInfoMultiRotor.json
+30
-51
MavCmdInfoRover.json
src/FirmwarePlugin/APM/MavCmdInfoRover.json
+8
-0
MavCmdInfoSub.json
src/FirmwarePlugin/APM/MavCmdInfoSub.json
+8
-0
MavCmdInfoVTOL.json
src/FirmwarePlugin/APM/MavCmdInfoVTOL.json
+8
-0
FirmwarePlugin.cc
src/FirmwarePlugin/FirmwarePlugin.cc
+30
-11
FirmwarePlugin.h
src/FirmwarePlugin/FirmwarePlugin.h
+3
-5
FirmwarePluginManager.cc
src/FirmwarePlugin/FirmwarePluginManager.cc
+7
-0
FirmwarePluginManager.h
src/FirmwarePlugin/FirmwarePluginManager.h
+2
-0
MavCmdInfoCommon.json
src/FirmwarePlugin/PX4/MavCmdInfoCommon.json
+2
-0
MavCmdInfoFixedWing.json
src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json
+12
-187
MavCmdInfoMultiRotor.json
src/FirmwarePlugin/PX4/MavCmdInfoMultiRotor.json
+14
-32
MavCmdInfoRover.json
src/FirmwarePlugin/PX4/MavCmdInfoRover.json
+8
-0
MavCmdInfoSub.json
src/FirmwarePlugin/PX4/MavCmdInfoSub.json
+8
-0
MavCmdInfoVTOL.json
src/FirmwarePlugin/PX4/MavCmdInfoVTOL.json
+8
-0
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+24
-5
PX4FirmwarePlugin.h
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
+1
-1
MavCmdInfoCommon.json
src/MissionManager/MavCmdInfoCommon.json
+150
-37
MavCmdInfoFixedWing.json
src/MissionManager/MavCmdInfoFixedWing.json
+13
-0
MavCmdInfoMultiRotor.json
src/MissionManager/MavCmdInfoMultiRotor.json
+8
-0
MavCmdInfoRover.json
src/MissionManager/MavCmdInfoRover.json
+8
-0
MavCmdInfoSub.json
src/MissionManager/MavCmdInfoSub.json
+8
-0
MavCmdInfoVTOL.json
src/MissionManager/MavCmdInfoVTOL.json
+8
-0
MissionCommandList.cc
src/MissionManager/MissionCommandList.cc
+24
-162
MissionCommandList.h
src/MissionManager/MissionCommandList.h
+16
-121
MissionCommandTree.cc
src/MissionManager/MissionCommandTree.cc
+239
-0
MissionCommandTree.h
src/MissionManager/MissionCommandTree.h
+97
-0
MissionCommandTreeTest.cc
src/MissionManager/MissionCommandTreeTest.cc
+206
-0
MissionCommandTreeTest.h
src/MissionManager/MissionCommandTreeTest.h
+44
-0
MissionCommandUIInfo.cc
src/MissionManager/MissionCommandUIInfo.cc
+387
-0
MissionCommandUIInfo.h
src/MissionManager/MissionCommandUIInfo.h
+191
-0
MissionCommands.cc
src/MissionManager/MissionCommands.cc
+0
-162
MissionCommands.h
src/MissionManager/MissionCommands.h
+0
-62
MissionItem.h
src/MissionManager/MissionItem.h
+0
-1
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+38
-33
SimpleMissionItem.h
src/MissionManager/SimpleMissionItem.h
+3
-2
MavCmdInfoCommon.json
src/MissionManager/UnitTest/MavCmdInfoCommon.json
+222
-0
MavCmdInfoFixedWing.json
src/MissionManager/UnitTest/MavCmdInfoFixedWing.json
+50
-0
MavCmdInfoMultiRotor.json
src/MissionManager/UnitTest/MavCmdInfoMultiRotor.json
+8
-0
MavCmdInfoRover.json
src/MissionManager/UnitTest/MavCmdInfoRover.json
+8
-0
MavCmdInfoSub.json
src/MissionManager/UnitTest/MavCmdInfoSub.json
+8
-0
MavCmdInfoVTOL.json
src/MissionManager/UnitTest/MavCmdInfoVTOL.json
+8
-0
VisualMissionItem.h
src/MissionManager/VisualMissionItem.h
+1
-1
QGCApplication.cc
src/QGCApplication.cc
+2
-2
QGCToolbox.cc
src/QGCToolbox.cc
+5
-5
QGCToolbox.h
src/QGCToolbox.h
+3
-3
MissionCommandDialog.qml
src/QmlControls/MissionCommandDialog.qml
+3
-3
QGroundControlQmlGlobal.cc
src/QmlControls/QGroundControlQmlGlobal.cc
+9
-6
QGroundControlQmlGlobal.h
src/QmlControls/QGroundControlQmlGlobal.h
+3
-4
MultiVehicleManager.cc
src/Vehicle/MultiVehicleManager.cc
+1
-1
MultiVehicleManager.h
src/Vehicle/MultiVehicleManager.h
+1
-1
Vehicle.cc
src/Vehicle/Vehicle.cc
+15
-25
Vehicle.h
src/Vehicle/Vehicle.h
+3
-3
UnitTestList.cc
src/qgcunittest/UnitTestList.cc
+2
-0
UAS.cc
src/uas/UAS.cc
+0
-1
No files found.
UnitTest.qrc
0 → 100644
View file @
0cecf13f
<RCC>
<qresource prefix="/json/unittest">
<file alias="MavCmdInfoCommon.json">src/MissionManager/UnitTest/MavCmdInfoCommon.json</file>
<file alias="MavCmdInfoFixedWing.json">src/MissionManager/UnitTest/MavCmdInfoFixedWing.json</file>
<file alias="MavCmdInfoMultiRotor.json">src/MissionManager/UnitTest/MavCmdInfoMultiRotor.json</file>
<file alias="MavCmdInfoRover.json">src/MissionManager/UnitTest/MavCmdInfoRover.json</file>
<file alias="MavCmdInfoSub.json">src/MissionManager/UnitTest/MavCmdInfoSub.json</file>
<file alias="MavCmdInfoVTOL.json">src/MissionManager/UnitTest/MavCmdInfoVTOL.json</file>
</qresource>
</RCC>
qgroundcontrol.pro
View file @
0cecf13f
...
...
@@ -178,6 +178,11 @@ RESOURCES += \
qgroundcontrol.qrc \
qgcresources.qrc
DebugBuild {
# Unit Test resources
RESOURCES += UnitTest.qrc
}
DEPENDPATH += \
. \
plugins
...
...
@@ -268,7 +273,8 @@ HEADERS += \
src/LogCompressor.h \
src/MG.h \
src/MissionManager/MissionCommandList.h \
src/MissionManager/MissionCommands.h \
src/MissionManager/MissionCommandTree.h \
src/MissionManager/MissionCommandUIInfo.h \
src/MissionManager/MissionController.h \
src/MissionManager/MissionItem.h \
src/MissionManager/MissionManager.h \
...
...
@@ -412,6 +418,7 @@ SOURCES += \
src/comm/LinkConfiguration.cc \
src/comm/LinkManager.cc \
src/comm/MAVLinkProtocol.cc \
src/comm/QGCMAVLink.cc \
src/comm/TCPLink.cc \
src/comm/UDPLink.cc \
src/FlightDisplay/FlightDisplayViewController.cc \
...
...
@@ -427,7 +434,8 @@ SOURCES += \
src/LogCompressor.cc \
src/main.cc \
src/MissionManager/MissionCommandList.cc \
src/MissionManager/MissionCommands.cc \
src/MissionManager/MissionCommandTree.cc \
src/MissionManager/MissionCommandUIInfo.cc \
src/MissionManager/MissionController.cc \
src/MissionManager/MissionItem.cc \
src/MissionManager/MissionManager.cc \
...
...
@@ -554,6 +562,7 @@ HEADERS += \
src/FactSystem/FactSystemTestGeneric.h \
src/FactSystem/FactSystemTestPX4.h \
src/MissionManager/ComplexMissionItemTest.h \
src/MissionManager/MissionCommandTreeTest.h \
src/MissionManager/MissionControllerTest.h \
src/MissionManager/MissionControllerManagerTest.h \
src/MissionManager/MissionItemTest.h \
...
...
@@ -580,6 +589,7 @@ SOURCES += \
src/FactSystem/FactSystemTestGeneric.cc \
src/FactSystem/FactSystemTestPX4.cc \
src/MissionManager/ComplexMissionItemTest.cc \
src/MissionManager/MissionCommandTreeTest.cc \
src/MissionManager/MissionControllerTest.cc \
src/MissionManager/MissionControllerManagerTest.cc \
src/MissionManager/MissionItemTest.cc \
...
...
qgroundcontrol.qrc
View file @
0cecf13f
...
...
@@ -163,12 +163,23 @@
</qresource>
<qresource prefix="/json">
<file alias="MavCmdInfoCommon.json">src/MissionManager/MavCmdInfoCommon.json</file>
<file alias="MavCmdInfoFixedWing.json">src/MissionManager/MavCmdInfoFixedWing.json</file>
<file alias="MavCmdInfoMultiRotor.json">src/MissionManager/MavCmdInfoMultiRotor.json</file>
<file alias="MavCmdInfoRover.json">src/MissionManager/MavCmdInfoRover.json</file>
<file alias="MavCmdInfoSub.json">src/MissionManager/MavCmdInfoSub.json</file>
<file alias="MavCmdInfoVTOL.json">src/MissionManager/MavCmdInfoVTOL.json</file>
<file alias="APM/MavCmdInfoCommon.json">src/FirmwarePlugin/APM/MavCmdInfoCommon.json</file>
<file alias="APM/MavCmdInfoFixedWing.json">src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json</file>
<file alias="APM/MavCmdInfoMultiRotor.json">src/FirmwarePlugin/APM/MavCmdInfoMultiRotor.json</file>
<file alias="APM/MavCmdInfoRover.json">src/FirmwarePlugin/APM/MavCmdInfoRover.json</file>
<file alias="APM/MavCmdInfoSub.json">src/FirmwarePlugin/APM/MavCmdInfoSub.json</file>
<file alias="APM/MavCmdInfoVTOL.json">src/FirmwarePlugin/APM/MavCmdInfoVTOL.json</file>
<file alias="PX4/MavCmdInfoCommon.json">src/FirmwarePlugin/PX4/MavCmdInfoCommon.json</file>
<file alias="PX4/MavCmdInfoFixedWing.json">src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json</file>
<file alias="PX4/MavCmdInfoMultiRotor.json">src/FirmwarePlugin/PX4/MavCmdInfoMultiRotor.json</file>
<file alias="PX4/MavCmdInfoRover.json">src/FirmwarePlugin/PX4/MavCmdInfoRover.json</file>
<file alias="PX4/MavCmdInfoSub.json">src/FirmwarePlugin/PX4/MavCmdInfoSub.json</file>
<file alias="PX4/MavCmdInfoVTOL.json">src/FirmwarePlugin/PX4/MavCmdInfoVTOL.json</file>
<file alias="Vehicle/VehicleFact.json">src/Vehicle/VehicleFact.json</file>
<file alias="Vehicle/BatteryFact.json">src/Vehicle/BatteryFact.json</file>
<file alias="Vehicle/GPSFact.json">src/Vehicle/GPSFact.json</file>
...
...
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
0cecf13f
...
...
@@ -576,30 +576,66 @@ QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void)
{
QList
<
MAV_CMD
>
list
;
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
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_CONTINUE_AND_CHANGE_ALT
<<
MAV_CMD_NAV_LOITER_TO_ALT
<<
MAV_CMD_NAV_SPLINE_WAYPOINT
<<
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_NAV_DELAY
<<
MAV_CMD_CONDITION_DELAY
<<
MAV_CMD_CONDITION_DISTANCE
<<
MAV_CMD_CONDITION_YAW
<<
MAV_CMD_DO_SET_MODE
<<
MAV_CMD_DO_JUMP
<<
MAV_CMD_DO_CHANGE_SPEED
<<
MAV_CMD_DO_SET_HOME
<<
MAV_CMD_DO_SET_RELAY
<<
MAV_CMD_DO_REPEAT_RELAY
<<
MAV_CMD_DO_SET_SERVO
<<
MAV_CMD_DO_REPEAT_SERVO
<<
MAV_CMD_DO_LAND_START
<<
MAV_CMD_DO_SET_ROI
<<
MAV_CMD_DO_DIGICAM_CONFIGURE
<<
MAV_CMD_DO_DIGICAM_CONTROL
<<
MAV_CMD_DO_MOUNT_CONTROL
<<
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
;
<<
MAV_CMD_DO_SET_CAM_TRIGG_DIST
<<
MAV_CMD_DO_FENCE_ENABLE
<<
MAV_CMD_DO_PARACHUTE
<<
MAV_CMD_DO_INVERTED_FLIGHT
<<
MAV_CMD_DO_GRIPPER
<<
MAV_CMD_DO_GUIDED_LIMITS
<<
MAV_CMD_DO_AUTOTUNE_ENABLE
<<
MAV_CMD_NAV_VTOL_TAKEOFF
<<
MAV_CMD_NAV_VTOL_LAND
<<
MAV_CMD_DO_VTOL_TRANSITION
;
#if 0
// Waiting for module update
<< MAV_CMD_DO_SET_REVERSE;
#endif
return
list
;
}
void
APMFirmwarePlugin
::
missionCommandOverrides
(
QString
&
commonJsonFilename
,
QString
&
fixedWingJsonFilename
,
QString
&
multiRotorJsonFilenam
e
)
const
QString
APMFirmwarePlugin
::
missionCommandOverrides
(
MAV_TYPE
vehicleTyp
e
)
const
{
commonJsonFilename
=
QStringLiteral
(
":/json/APM/MavCmdInfoCommon.json"
);
fixedWingJsonFilename
=
QStringLiteral
(
":/json/APM/MavCmdInfoFixedWing.json"
);
multiRotorJsonFilename
=
QStringLiteral
(
":/json/APM/MavCmdInfoMultiRotor.json"
);
switch
(
vehicleType
)
{
case
MAV_TYPE_GENERIC
:
return
QStringLiteral
(
":/json/APM/MavCmdInfoCommon.json"
);
break
;
case
MAV_TYPE_FIXED_WING
:
return
QStringLiteral
(
":/json/APM/MavCmdInfoFixedWing.json"
);
break
;
case
MAV_TYPE_QUADROTOR
:
return
QStringLiteral
(
":/json/APM/MavCmdInfoMultiRotor.json"
);
break
;
case
MAV_TYPE_VTOL_QUADROTOR
:
return
QStringLiteral
(
":/json/APM/MavCmdInfoVTOL.json"
);
break
;
case
MAV_TYPE_SUBMARINE
:
return
QStringLiteral
(
":/json/APM/MavCmdInfoSub.json"
);
break
;
case
MAV_TYPE_GROUND_ROVER
:
return
QStringLiteral
(
":/json/APM/MavCmdInfoRover.json"
);
break
;
default:
qWarning
()
<<
"APMFirmwarePlugin::missionCommandOverrides called with bad MAV_TYPE:"
<<
vehicleType
;
return
QString
();
}
}
QObject
*
APMFirmwarePlugin
::
loadParameterMetaData
(
const
QString
&
metaDataFile
)
...
...
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
View file @
0cecf13f
...
...
@@ -73,21 +73,21 @@ public:
QList
<
VehicleComponent
*>
componentsForVehicle
(
AutoPilotPlugin
*
vehicle
)
final
;
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
)
final
;
bool
isCapable
(
const
Vehicle
*
vehicle
,
FirmwareCapabilities
capabilities
);
QStringList
flightModes
(
Vehicle
*
vehicle
)
final
;
QString
flightMode
(
uint8_t
base_mode
,
uint32_t
custom_mode
)
const
final
;
bool
setFlightMode
(
const
QString
&
flightMode
,
uint8_t
*
base_mode
,
uint32_t
*
custom_mode
)
final
;
bool
isGuidedMode
(
const
Vehicle
*
vehicle
)
const
final
;
void
pauseVehicle
(
Vehicle
*
vehicle
);
bool
isCapable
(
const
Vehicle
*
vehicle
,
FirmwareCapabilities
capabilities
);
QStringList
flightModes
(
Vehicle
*
vehicle
)
final
;
QString
flightMode
(
uint8_t
base_mode
,
uint32_t
custom_mode
)
const
final
;
bool
setFlightMode
(
const
QString
&
flightMode
,
uint8_t
*
base_mode
,
uint32_t
*
custom_mode
)
final
;
bool
isGuidedMode
(
const
Vehicle
*
vehicle
)
const
final
;
void
pauseVehicle
(
Vehicle
*
vehicle
);
int
manualControlReservedButtonCount
(
void
);
bool
adjustIncomingMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
final
;
void
adjustOutgoingMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
final
;
void
initializeVehicle
(
Vehicle
*
vehicle
)
final
;
bool
sendHomePositionToVehicle
(
void
)
final
;
void
addMetaDataToFact
(
QObject
*
parameterMetaData
,
Fact
*
fact
,
MAV_TYPE
vehicleType
)
final
;
QString
getDefaultComponentIdParam
(
void
)
const
final
{
return
QString
(
"SYSID_SW_TYPE"
);
}
void
missionCommandOverrides
(
QString
&
commonJsonFilename
,
QString
&
fixedWingJsonFilename
,
QString
&
multiRotorJsonFilename
)
const
final
;
QString
getVersionParam
(
void
)
final
{
return
QStringLiteral
(
"SYSID_SW_MREV"
);
}
bool
adjustIncomingMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
final
;
void
adjustOutgoingMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
final
;
void
initializeVehicle
(
Vehicle
*
vehicle
)
final
;
bool
sendHomePositionToVehicle
(
void
)
final
;
void
addMetaDataToFact
(
QObject
*
parameterMetaData
,
Fact
*
fact
,
MAV_TYPE
vehicleType
)
final
;
QString
getDefaultComponentIdParam
(
void
)
const
final
{
return
QString
(
"SYSID_SW_TYPE"
);
}
QString
missionCommandOverrides
(
MAV_TYPE
vehicleType
)
const
;
QString
getVersionParam
(
void
)
final
{
return
QStringLiteral
(
"SYSID_SW_MREV"
);
}
QString
internalParameterMetaDataFile
(
void
)
final
{
return
QString
(
":/FirmwarePlugin/APM/APMParameterFactMetaData.xml"
);
}
void
getParameterMetaDataVersionInfo
(
const
QString
&
metaDataFile
,
int
&
majorVersion
,
int
&
minorVersion
)
final
{
APMParameterMetaData
::
getParameterMetaDataVersionInfo
(
metaDataFile
,
majorVersion
,
minorVersion
);
}
QObject
*
loadParameterMetaData
(
const
QString
&
metaDataFile
);
...
...
src/FirmwarePlugin/APM/MavCmdInfoCommon.json
View file @
0cecf13f
{
"comment"
:
"ArduPilot, Any Vehicle"
,
"version"
:
1
,
"mavCmdInfo"
:
[
{
"id"
:
22
,
"rawName"
:
"MAV_CMD_NAV_TAKEOFF"
,
"friendlyName"
:
"Takeoff"
,
"description"
:
"Take off from the ground."
,
"specifiesCoordinate"
:
false
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param1"
:
{
"label"
:
"Pitch:"
,
"units"
:
"deg"
,
"default"
:
15
,
"decimalPlaces"
:
2
},
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"m"
,
"default"
:
25.0
,
"decimalPlaces"
:
2
}
},
{
"id"
:
84
,
"rawName"
:
"MAV_CMD_NAV_VTOL_TAKEOFF"
,
"friendlyName"
:
"VTOL takeoff"
,
"description"
:
"Takeoff from ground using VTOL mode."
,
"comment"
:
"MAV_CMD_NAV_VTOL_TAKEOFF"
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"VTOL"
},
{
"id"
:
85
,
"rawName"
:
"MAV_CMD_NAV_VTOL_LAND"
,
"friendlyName"
:
"VTOL land"
,
"comment"
:
"MAV_CMD_NAV_VTOL_LAND"
,
"description"
:
"Land using VTOL mode."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"VTOL"
,
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"m"
,
"default"
:
0.0
,
"category"
:
"VTOL"
},
{
"id"
:
176
,
"comment"
:
"MAV_CMD_DO_SET_MODE"
,
"paramRemove"
:
"2,3"
},
{
"id"
:
178
,
"comment"
:
"MAV_CMD_DO_CHANGE_SPEED"
,
"paramRemove"
:
"4"
},
{
"id"
:
181
,
"comment"
:
"MAV_CMD_DO_SET_RELAY"
,
"param2"
:
{
"label"
:
"Setting:"
,
"enumStrings"
:
"On,Off"
,
"enumValues"
:
"1,0"
,
"default"
:
1
}
},
{
"id"
:
201
,
"comment"
:
"MAV_CMD_DO_SET_ROI"
,
"paramRemove"
:
"2,3"
},
{
"id"
:
205
,
"comment"
:
"MAV_CMD_DO_MOUNT_CONTROL"
,
"paramRemove"
:
"7"
,
"param1"
:
{
"label"
:
"Pitch:"
,
"default"
:
0
,
"units"
:
"deg"
,
"decimalPlaces"
:
2
},
"param2"
:
{
"label"
:
"Roll:"
,
"default"
:
0
,
"units"
:
"deg"
,
"decimalPlaces"
:
2
},
"param3"
:
{
"label"
:
"Yaw:"
,
"default"
:
0
,
"units"
:
"deg"
,
"decimalPlaces"
:
2
}
},
{
"id"
:
207
,
"comment"
:
"MAV_CMD_DO_FENCE_ENABLE"
,
"param1"
:
{
"label"
:
"Enable:"
,
"enumStrings"
:
"Enable,Disable"
,
"enumValues"
:
"1,0"
,
"default"
:
1
}
}
]
}
src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json
View file @
0cecf13f
{
"comment"
:
"ArduPilot, Fixed Wing"
,
"version"
:
1
,
"mavCmdInfo"
:
[
{
"id"
:
16
,
"rawName"
:
"MAV_CMD_NAV_WAYPOINT"
,
"friendlyName"
:
"Waypoint"
,
"description"
:
"Travel to a position in 3D space."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param1"
:
{
"label"
:
"Hold:"
,
"units"
:
"secs"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"m"
,
"default"
:
50
,
"decimalPlaces"
:
0
}
"id"
:
16
,
"comment"
:
"MAV_CMD_NAV_WAYPOINT"
,
"paramRemove"
:
"1,3,4"
},
{
"id"
:
17
,
"rawName"
:
"MAV_CMD_NAV_LOITER_UNLIM"
,
"friendlyName"
:
"Loiter"
,
"description"
:
"Travel to a position and Loiter around the specified radius indefinitely."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Loiter"
,
"param3"
:
{
"label"
:
"Radius:"
,
"units"
:
"m"
,
"default"
:
50
,
"decimalPlaces"
:
0
},
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"m"
,
"default"
:
50
,
"decimalPlaces"
:
0
}
"id"
:
21
,
"comment"
:
"MAV_CMD_NAV_LAND"
,
"paramRemove"
:
"4"
},
{
"id"
:
18
,
"rawName"
:
"MAV_CMD_NAV_LOITER_TURNS"
,
"friendlyName"
:
"Loiter (turns)"
,
"description"
:
"Travel to a position and Loiter around the specified radius for a number of turns."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Loiter"
,
"param1"
:
{
"label"
:
"Turns:"
,
"default"
:
1
,
"decimalPlaces"
:
0
},
"param3"
:
{
"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"
:
22
,
"comment"
:
"MAV_CMD_NAV_TAKEOFF"
,
"specifiesCoordinate"
:
false
,
"paramRemove"
:
"2,3,4,5,6"
},
{
"id"
:
19
,
"rawName"
:
"MAV_CMD_NAV_LOITER_TIME"
,
"friendlyName"
:
"Loiter (time)"
,
"description"
:
"Travel to a position and Loiter around the specified radius for a number of seconds."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Loiter"
,
"param1"
:
{
"label"
:
"Seconds:"
,
"units"
:
"secs"
,
"default"
:
30
,
"decimalPlaces"
:
1
},
"param3"
:
{
"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"
:
21
,
"rawName"
:
"MAV_CMD_NAV_LAND"
,
"friendlyName"
:
"Land"
,
"description"
:
"Land vehicle at the specified location."
,
"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"
,
"default"
:
0
,
"decimalPlaces"
:
1
}
},
{
"id"
:
22
,
"rawName"
:
"MAV_CMD_NAV_TAKEOFF"
,
"friendlyName"
:
"Takeoff"
,
"description"
:
"Take off from the ground and travel towards the specified position."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param1"
:
{
"label"
:
"Pitch:"
,
"units"
:
"deg"
,
"default"
:
10
,
"decimalPlaces"
:
0
},
"param4"
:
{
"label"
:
"Heading:"
,
"units"
:
"radians"
,
"default"
:
0
,
"decimalPlaces"
:
1
},
"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"
:
"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"
,
"friendlyName"
:
"Camera trigger distance"
,
"description"
:
"Set camera trigger distance."
,
"category"
:
"Camera"
,
"param1"
:
{
"label"
:
"Distance:"
,
"default"
:
25
,
"units"
:
"m"
,
"decimalPlaces"
:
1
}
"id"
:
82
,
"comment"
:
"MAV_CMD_NAV_SPLINE_WAYPOINT"
,
"paramRemove"
:
"1"
}
]
}
src/FirmwarePlugin/APM/MavCmdInfoMultiRotor.json
View file @
0cecf13f
{
"comment"
:
"ArduPilot, Multi Rotor"
,
"version"
:
1
,
"mavCmdInfo"
:
[
{
"id"
:
22
,
"rawName"
:
"MAV_CMD_NAV_TAKEOFF"
,
"friendlyName"
:
"Takeoff"
,
"description"
:
"Take off from the ground."
,
"specifiesCoordinate"
:
false
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"m"
,
"default"
:
25.0
,
"decimalPlaces"
:
2
}
"id"
:
16
,
"comment"
:
"MAV_CMD_NAV_WAYPOINT"
,
"paramRemove"
:
"2,3,4"
},
{
"id"
:
17
,
"rawName"
:
"MAV_CMD_NAV_LOITER_UNLIM"
,
"friendlyName"
:
"Loiter"
,
"description"
:
"Travel to a position and Loiter indefinitely."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
"id"
:
17
,
"comment"
:
"MAV_CMD_NAV_LOITER_UNLIM"
,
"paramRemove"
:
"3"
},
{
"id"
:
18
,
"rawName"
:
"MAV_CMD_NAV_LOITER_TURNS"
,
"friendlyName"
:
"Loiter (turns)"
,
"description"
:
"Travel to a position and Circle with the specified radius for a number of turns."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param1"
:
{
"label"
:
"Turns:"
,
"default"
:
1
,
"decimalPlaces"
:
0
},
"param3"
:
{
"label"
:
"Radius:"
,
"units"
:
"m"
,
"default"
:
10.0
,
"decimalPlaces"
:
2
}
"id"
:
18
,
"comment"
:
"MAV_CMD_NAV_LOITER_TURNS"
,
"paramRemove"
:
"4"
},
{
"id"
:
19
,
"comment"
:
"MAV_CMD_NAV_LOITER_TIME"
,
"paramRemove"
:
"4"
},
{
"id"
:
21
,
"comment"
:
"MAV_CMD_NAV_LAND"
,
"paramRemove"
:
"1,4"
},
{
"id"
:
22
,
"comment"
:
"MAV_CMD_NAV_TAKEOFF"
,
"specifiesCoordinate"
:
false
,
"paramRemove"
:
"1,2,3,4,5,6"
},
{
"id"
:
19
,
"rawName"
:
"MAV_CMD_NAV_LOITER_TIME"
,
"friendlyName"
:
"Loiter (time)"
,
"description"
:
"Travel to a position and Loiter for an amount of time."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param1"
:
{
"label"
:
"Hold:"
,
"units"
:
"secs"
,
"default"
:
30
,
"decimalPlaces"
:
0
}
"id"
:
31
,
"comment"
:
"MAV_CMD_NAV_LOITER_TO_ALT"
,
"paramRemove"
:
"4"
}
]
}
src/FirmwarePlugin/APM/MavCmdInfoRover.json
0 → 100644
View file @
0cecf13f
{
"comment"
:
"ArduPilot, Rover"
,
"version"
:
1
,
"mavCmdInfo"
:
[
]
}
src/FirmwarePlugin/APM/MavCmdInfoSub.json
0 → 100644
View file @
0cecf13f
{
"comment"
:
"ArduPilot, Sub"
,
"version"
:
1
,
"mavCmdInfo"
:
[
]
}
src/FirmwarePlugin/APM/MavCmdInfoVTOL.json
0 → 100644
View file @
0cecf13f
{
"comment"
:
"ArduPilot, VTOL"
,
"version"
:
1
,
"mavCmdInfo"
:
[
]
}
src/FirmwarePlugin/FirmwarePlugin.cc
View file @
0cecf13f
...
...
@@ -38,12 +38,12 @@ QString FirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mode) cons
const
char
*
name
;
};