diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index c4d45172d6f5ade671abf7896be6fd41183d612f..fedc1e49b7a7106d5db14d01e405f13697978d68 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -568,7 +568,6 @@ HEADERS += \ src/QmlControls/AppMessages.h \ src/QmlControls/CoordinateVector.h \ src/QmlControls/EditPositionDialogController.h \ - src/QmlControls/MavlinkQmlSingleton.h \ src/QmlControls/ParameterEditorController.h \ src/QmlControls/QGCFileDialogController.h \ src/QmlControls/QGCImageProvider.h \ diff --git a/src/FlightMap/FlightMap.qml b/src/FlightMap/FlightMap.qml index f478186ae1d2b8e80edf8f7b3d41f25468251825..4a7266b754b0250edfa10ce47161183e7612287c 100644 --- a/src/FlightMap/FlightMap.qml +++ b/src/FlightMap/FlightMap.qml @@ -19,7 +19,6 @@ import QGroundControl.FlightMap 1.0 import QGroundControl.ScreenTools 1.0 import QGroundControl.MultiVehicleManager 1.0 import QGroundControl.Vehicle 1.0 -import QGroundControl.Mavlink 1.0 import QGroundControl.QGCPositionManager 1.0 Map { diff --git a/src/MissionManager/MissionCommandList.h b/src/MissionManager/MissionCommandList.h index 79c6ef633dc1c29c9307269e8cfae6ef0e2e47b3..319020002311e3b50400e6eb2679326ff1cb6c96 100644 --- a/src/MissionManager/MissionCommandList.h +++ b/src/MissionManager/MissionCommandList.h @@ -14,7 +14,6 @@ #include "QGCMAVLink.h" #include "QGCLoggingCategory.h" #include "QmlObjectListModel.h" -#include "MavlinkQmlSingleton.h" #include #include diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index f9ffdc18546eda2909dca3f0493f80bfdaa660d4..38e37aa6baa712c5a85b1b5bd52d5c4b61d9576e 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -335,10 +335,10 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i) SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, this); newItem->setSequenceNumber(sequenceNumber); newItem->setCoordinate(coordinate); - newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT); + newItem->setCommand(MAV_CMD_NAV_WAYPOINT); _initVisualItem(newItem); if (_visualItems->count() == 1) { - MavlinkQmlSingleton::Qml_MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF : MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF; + MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF; if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)takeoffCmd)) { newItem->setCommand(takeoffCmd); } @@ -366,7 +366,7 @@ int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i) int sequenceNumber = _nextSequenceNumber(); SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, this); newItem->setSequenceNumber(sequenceNumber); - newItem->setCommand((MavlinkQmlSingleton::Qml_MAV_CMD)(_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)MAV_CMD_DO_SET_ROI_LOCATION) ? + newItem->setCommand((MAV_CMD)(_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)MAV_CMD_DO_SET_ROI_LOCATION) ? MAV_CMD_DO_SET_ROI_LOCATION : MAV_CMD_DO_SET_ROI)); _initVisualItem(newItem); @@ -840,7 +840,7 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM // Update sequence numbers in DO_JUMP commands to take into account added home position in index 0 for (int i=1; icount(); i++) { SimpleMissionItem* item = qobject_cast(visualItems->get(i)); - if (item && item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) { + if (item && item->command() == MAV_CMD_DO_JUMP) { item->missionItem().setParam1((int)item->missionItem().param1() + 1); } } @@ -1297,7 +1297,7 @@ void MissionController::_recalcMissionFlightStatus() } // Link back to home if first item is takeoff and we have home position - if (firstCoordinateItem && simpleItem && (simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) { + if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) { if (showHomePosition) { linkStartToHome = true; if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) { @@ -1313,19 +1313,19 @@ void MissionController::_recalcMissionFlightStatus() // Update VTOL state if (simpleItem && _controllerVehicle->vtol()) { switch (simpleItem->command()) { - case MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF: + case MAV_CMD_NAV_TAKEOFF: vtolInHover = false; break; - case MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF: + case MAV_CMD_NAV_VTOL_TAKEOFF: vtolInHover = true; break; - case MavlinkQmlSingleton::MAV_CMD_NAV_LAND: + case MAV_CMD_NAV_LAND: vtolInHover = false; break; - case MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_LAND: + case MAV_CMD_NAV_VTOL_LAND: vtolInHover = true; break; - case MavlinkQmlSingleton::MAV_CMD_DO_VTOL_TRANSITION: + case MAV_CMD_DO_VTOL_TRANSITION: { int transitionState = simpleItem->missionItem().param1(); if (transitionState == MAV_VTOL_STATE_TRANSITION_TO_MC) { diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h index f0655e852e4fef33e07206e81a872d15364abde9..ba75d962f15ee5778ebef71ac197e07263fcebd4 100644 --- a/src/MissionManager/MissionController.h +++ b/src/MissionManager/MissionController.h @@ -15,7 +15,6 @@ #include "QmlObjectListModel.h" #include "Vehicle.h" #include "QGCLoggingCategory.h" -#include "MavlinkQmlSingleton.h" #include diff --git a/src/MissionManager/MissionControllerTest.cc b/src/MissionManager/MissionControllerTest.cc index c1bcdfc5c4b6c4bd7da7c8d5135ae31bd66e49c4..ef7946246d32e57f73fc99b8749798e19f3bd180 100644 --- a/src/MissionManager/MissionControllerTest.cc +++ b/src/MissionManager/MissionControllerTest.cc @@ -132,7 +132,7 @@ void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType) QVERIFY(settingsItem); QVERIFY(simpleItem); - QCOMPARE(simpleItem->command(), MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF); + QCOMPARE((MAV_CMD)simpleItem->command(), MAV_CMD_NAV_TAKEOFF); QCOMPARE(simpleItem->childItems()->count(), 0); // If the first item added specifies a coordinate, then planned home position will be set diff --git a/src/MissionManager/MissionItem.h b/src/MissionManager/MissionItem.h index 8202a8480535ffdd41aaef21af3edb43fadfbc16..9e2848669e64c9504a60c2ebc5552639fe4ffcd1 100644 --- a/src/MissionManager/MissionItem.h +++ b/src/MissionManager/MissionItem.h @@ -20,7 +20,6 @@ #include "QGCMAVLink.h" #include "QGC.h" -#include "MavlinkQmlSingleton.h" #include "QmlObjectListModel.h" #include "Fact.h" #include "QGCLoggingCategory.h" diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc index 0c913ec6b0a3348931b2a3b9c076df3374a96e17..40b68604db83e8686e3fa627ad01f21dc3eca1ca 100644 --- a/src/MissionManager/SimpleMissionItem.cc +++ b/src/MissionManager/SimpleMissionItem.cc @@ -392,15 +392,15 @@ QString SimpleMissionItem::abbreviation() const return tr("H"); switch(command()) { - case MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF: + case MAV_CMD_NAV_TAKEOFF: return tr("Takeoff"); - case MavlinkQmlSingleton::MAV_CMD_NAV_LAND: + case MAV_CMD_NAV_LAND: return tr("Land"); - case MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF: + case MAV_CMD_NAV_VTOL_TAKEOFF: return tr("VTOL Takeoff"); - case MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_LAND: + case MAV_CMD_NAV_VTOL_LAND: return tr("VTOL Land"); - case MavlinkQmlSingleton::MAV_CMD_DO_SET_ROI: + case MAV_CMD_DO_SET_ROI: return tr("ROI"); default: return QString(); @@ -750,7 +750,7 @@ QString SimpleMissionItem::category(void) const return _commandTree->getUIInfo(_vehicle, (MAV_CMD)command())->category(); } -void SimpleMissionItem::setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command) +void SimpleMissionItem::setCommand(int command) { if ((MAV_CMD)command != _missionItem.command()) { _missionItem.setCommand((MAV_CMD)command); diff --git a/src/MissionManager/SimpleMissionItem.h b/src/MissionManager/SimpleMissionItem.h index 3f1c4c44736404842570f0a8ce741153129f1fde..5d0db11406829485a658536338fd4dbc4a1e5a03 100644 --- a/src/MissionManager/SimpleMissionItem.h +++ b/src/MissionManager/SimpleMissionItem.h @@ -44,7 +44,7 @@ public: Q_PROPERTY(Fact* altitude READ altitude CONSTANT) ///< Altitude as specified by altitudeMode. Not necessarily true mission item altitude Q_PROPERTY(AltitudeMode altitudeMode READ altitudeMode WRITE setAltitudeMode NOTIFY altitudeModeChanged) Q_PROPERTY(Fact* amslAltAboveTerrain READ amslAltAboveTerrain CONSTANT) ///< Actual AMSL altitude for item if altitudeMode == AltitudeAboveTerrain - Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged) + Q_PROPERTY(int command READ command WRITE setCommand NOTIFY commandChanged) /// Optional sections Q_PROPERTY(QObject* speedSection READ speedSection NOTIFY speedSectionChanged) @@ -65,7 +65,7 @@ public: // Property accesors QString category (void) const; - MavlinkQmlSingleton::Qml_MAV_CMD command(void) const { return (MavlinkQmlSingleton::Qml_MAV_CMD)_missionItem._commandFact.cookedValue().toInt(); } + int command(void) const { return _missionItem._commandFact.cookedValue().toInt(); } bool friendlyEditAllowed (void) const; bool rawEdit (void) const; bool specifiesAltitude (void) const; @@ -85,7 +85,7 @@ public: void setCommandByIndex(int index); - void setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command); + void setCommand(int command); void setAltDifference (double altDifference); void setAltPercent (double altPercent); diff --git a/src/MissionManager/SimpleMissionItemTest.cc b/src/MissionManager/SimpleMissionItemTest.cc index 54b15897c78de46892e3a05557b3ec3a5765a37e..6706fadcd8f6c69a67e23689d2d046575f728846 100644 --- a/src/MissionManager/SimpleMissionItemTest.cc +++ b/src/MissionManager/SimpleMissionItemTest.cc @@ -236,11 +236,11 @@ void SimpleMissionItemTest::_testSignals(void) // dirtyChanged // coordinateChanged - since altitude will be set back to default - _simpleItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT); + _simpleItem->setCommand(MAV_CMD_NAV_WAYPOINT); QVERIFY(_spyVisualItem->checkNoSignals()); QVERIFY(_spySimpleItem->checkNoSignals()); - _simpleItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_LOITER_TIME); + _simpleItem->setCommand(MAV_CMD_NAV_LOITER_TIME); QVERIFY(_spySimpleItem->checkSignalsByMask(commandChangedMask)); QVERIFY(_spyVisualItem->checkSignalsByMask(commandNameChangedMask | dirtyChangedMask | coordinateChangedMask)); } diff --git a/src/MissionManager/VisualMissionItem.h b/src/MissionManager/VisualMissionItem.h index 2257e95630913628e176bc4af5c004bfafdda5cf..96cb4fc1a24c3cbd3c54a79fdba128cb71cc7a0a 100644 --- a/src/MissionManager/VisualMissionItem.h +++ b/src/MissionManager/VisualMissionItem.h @@ -18,7 +18,6 @@ #include "QGCMAVLink.h" #include "QGC.h" -#include "MavlinkQmlSingleton.h" #include "QmlObjectListModel.h" #include "Fact.h" #include "QGCLoggingCategory.h" diff --git a/src/PlanView/PlanView.qml b/src/PlanView/PlanView.qml index 3e28282f7e529c2aa26c7422852b8fcaa005ce3f..0b352354fc9ebb3ce902d6134f7f8c6929d3f8dc 100644 --- a/src/PlanView/PlanView.qml +++ b/src/PlanView/PlanView.qml @@ -23,7 +23,6 @@ import QGroundControl.Controls 1.0 import QGroundControl.FactSystem 1.0 import QGroundControl.FactControls 1.0 import QGroundControl.Palette 1.0 -import QGroundControl.Mavlink 1.0 import QGroundControl.Controllers 1.0 /// Mission Editor diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index ec3d865182f5c6a34c42ab8291559ce7dfa4816f..2ff9a34098773392751688586fc196619eb95ebf 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -57,7 +57,6 @@ #include "FirmwarePluginManager.h" #include "MultiVehicleManager.h" #include "Vehicle.h" -#include "MavlinkQmlSingleton.h" #include "JoystickConfigController.h" #include "JoystickManager.h" #include "QmlObjectListModel.h" @@ -130,11 +129,6 @@ static QObject* screenToolsControllerSingletonFactory(QQmlEngine*, QJSEngine*) return screenToolsController; } -static QObject* mavlinkQmlSingletonFactory(QQmlEngine*, QJSEngine*) -{ - return new MavlinkQmlSingleton; -} - static QObject* qgroundcontrolQmlGlobalSingletonFactory(QQmlEngine*, QJSEngine*) { // We create this object as a QGCTool even though it isn't in the toolbox @@ -404,7 +398,6 @@ void QGCApplication::_initCommon(void) // Register Qml Singletons qmlRegisterSingletonType ("QGroundControl", 1, 0, "QGroundControl", qgroundcontrolQmlGlobalSingletonFactory); qmlRegisterSingletonType ("QGroundControl.ScreenToolsController", 1, 0, "ScreenToolsController", screenToolsControllerSingletonFactory); - qmlRegisterSingletonType ("QGroundControl.Mavlink", 1, 0, "Mavlink", mavlinkQmlSingletonFactory); } bool QGCApplication::_initForNormalAppBoot(void) diff --git a/src/QmlControls/MavlinkQmlSingleton.h b/src/QmlControls/MavlinkQmlSingleton.h deleted file mode 100644 index 28c625f4c2e945b62d8fd11f3b899300a554ca99..0000000000000000000000000000000000000000 --- a/src/QmlControls/MavlinkQmlSingleton.h +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * - * (c) 2009-2016 QGROUNDCONTROL PROJECT - * - * QGroundControl is licensed according to the terms in the file - * COPYING.md in the root of the source code directory. - * - ****************************************************************************/ - - -#ifndef MavlinkQmlSingleton_H -#define MavlinkQmlSingleton_H - -#include - -class MavlinkQmlSingleton : public QObject -{ - Q_OBJECT - Q_ENUMS(Qml_MAV_CMD) - -public: - // Couldn't figure a way to get MAV_CMD enum out to Qml so I had to copy it. Sigh! - - typedef enum { - MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LAND_LOCAL=23, /* Land at local position (local frame only) |Landing target number (if available)| Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land| Landing descend rate [ms^-1]| Desired yaw angle [rad]| Y-axis position [m]| X-axis position [m]| Z-axis / ground level position [m]| */ - MAV_CMD_NAV_TAKEOFF_LOCAL=24, /* Takeoff from local position (local frame only) |Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]| Empty| Takeoff ascend rate [ms^-1]| Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these| Y-axis position [m]| X-axis position [m]| Z-axis position [m]| */ - MAV_CMD_NAV_FOLLOW=25, /* Vehicle following, i.e. this waypoint represents the position of a moving vehicle |Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation| Ground speed of vehicle to be followed| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT=30, /* Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. |Empty| Empty| Empty| Empty| Empty| Empty| Desired altitude in meters| */ - MAV_CMD_NAV_LOITER_TO_ALT=31, /* Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. |Heading Required (0 = False)| Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.| Empty| Empty| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_ALTITUDE_WAIT=83, /* Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up. |altitude (m)| descent speed (m/s)| Wiggle Time (s)| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_VTOL_TAKEOFF=84, - MAV_CMD_NAV_VTOL_LAND=85, - MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ - MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ - MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ - MAV_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_LAND_START=189, /* Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. |Empty| Empty| Empty| Empty| Latitude| Longitude| Empty| */ - MAV_CMD_DO_RALLY_LAND=190, /* Mission command to perform a landing from a rally point. |Break altitude (meters)| Landing speed (m/s)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_GO_AROUND=191, /* Mission command to safely abort an autonmous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */ - MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */ - MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */ - MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */ - MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable, 2=disable_floor_only)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_MOTOR_TEST=209, /* Mission command to perform motor test |motor sequence number (a number from 1 to max number of motors on the vehicle)| throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)| throttle| timeout (in seconds)| Empty| Empty| Empty| */ - MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_GRIPPER=211, /* Mission command to operate EPM gripper |gripper number (a number from 1 to max number of grippers on the vehicle)| gripper action (0=release, 1=grab. See GRIPPER_ACTIONS enum)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_AUTOTUNE_ENABLE=212, /* Enable/disable autotune |enable (1: enable, 0:disable)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| */ - MAV_CMD_DO_GUIDED_MASTER=221, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_GUIDED_LIMITS=222, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */ - MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */ - MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ - MAV_CMD_PREFLIGHT_UAVCAN=243, /* Trigger UAVCAN config. This command will be only accepted if in pre-flight mode. |1: Trigger actuator ID assignment and direction mapping.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ - MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)| Reserved| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ - MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ - MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ - MAV_CMD_GET_HOME_POSITION=410, /* Request the home position from the vehicle. |Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ - MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ - MAV_CMD_GET_MESSAGE_INTERVAL=510, /* Request the interval between messages for a particular MAVLink message ID |The MAVLink message ID| */ - MAV_CMD_SET_MESSAGE_INTERVAL=511, /* Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM |The MAVLink message ID| The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.| */ - MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES=520, /* Request autopilot capabilities |1: Request autopilot version| Reserved (all remaining params)| */ - MAV_CMD_IMAGE_START_CAPTURE=2000, /* Start image capture sequence */ - MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* Stop image capture sequence */ - MAV_CMD_DO_TRIGGER_CONTROL=2003, /* Enable or disable on-board camera triggering system. |Trigger enable/disable (0 for disable, 1 for start)| Shutter integration time (in ms)| Reserved| */ - MAV_CMD_VIDEO_START_CAPTURE=2500, /* Starts video capture */ - MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* Stop the current video capture */ - MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)| Viewing angle vertical of panorama (in degrees)| Speed of the horizontal rotation (in degrees per second)| Speed of the vertical rotation (in degrees per second)| */ - MAV_CMD_DO_VTOL_TRANSITION=3000, /* Request VTOL transition |The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.| */ - MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overridden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.| Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Altitude, in meters AMSL| */ - MAV_CMD_PAYLOAD_CONTROL_DEPLOY=30002, /* Control the payload deployment. |Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ - MAV_CMD_DO_START_MAG_CAL=42424, /* Initiate a magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Automatically retry on failure (0=no retry, 1=retry).| Save without user input (0=require input, 1=autosave).| Delay (seconds)| Empty| Empty| Empty| */ - MAV_CMD_DO_ACCEPT_MAG_CAL=42425, /* Initiate a magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CANCEL_MAG_CAL=42426, /* Cancel a running magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_ENUM_END=42427, /* | */ - } Qml_MAV_CMD; -}; - -#endif // MavlinkQmlSingleton_H