diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index fcfda5db95dcfa5246604af363fc2e7991f7cc67..3594b5f0a6099171c57cdd6d42246d657be21b1f 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -722,41 +722,39 @@ void APMFirmwarePlugin::addMetaDataToFact(QObject* parameterMetaData, Fact* fact QList APMFirmwarePlugin::supportedMissionCommands(void) { - QList list; - - 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_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_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; + return { + 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_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_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; + MAV_CMD_DO_SET_REVERSE, #endif - - return list; + }; } QString APMFirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const