QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
ArduPlaneFirmwarePlugin.h
Go to the documentation of this file.
1#pragma once
2
3#include "APMFirmwarePlugin.h"
4
6{
7 enum Mode : uint32_t {
8 MANUAL = 0,
9 CIRCLE = 1,
12 ACRO = 4,
15 CRUISE = 7,
17 RESERVED_9 = 9, // RESERVED FOR FUTURE USE
18 AUTO = 10,
19 RTL = 11,
20 LOITER = 12,
21 TAKEOFF = 13,
23 GUIDED = 15,
26 QHOVER = 18,
27 QLOITER = 19,
28 QLAND = 20,
29 QRTL = 21,
31 QACRO = 23,
32 THERMAL = 24,
35 };
36};
37
39{
40 Q_OBJECT
41
42public:
43 explicit ArduPlaneFirmwarePlugin(QObject *parent = nullptr);
45
46 QString offlineEditingParamFile(Vehicle *vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Plane.OfflineEditing.params"); }
47 QString autoDisarmParameter(Vehicle *vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("LAND_DISARMDELAY"); }
48 int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const override;
49 const FirmwarePlugin::remapParamNameMajorVersionMap_t &paramNameRemapMajorVersionMap() const override { return _remapParamName; }
50 QString pauseFlightMode() const override;
51 QString takeOffFlightMode() const override;
52 QString stabilizedFlightMode() const override;
53 void updateAvailableFlightModes(FlightModeList &modeList) override;
54
55protected:
56 uint32_t _convertToCustomFlightModeEnum(uint32_t val) const override;
57
58 const QString _manualFlightMode = tr("Manual");
59 const QString _circleFlightMode = tr("Circle");
60 const QString _stabilizeFlightMode = tr("Stabilize");
61 const QString _trainingFlightMode = tr("Training");
62 const QString _acroFlightMode = tr("Acro");
63 const QString _flyByWireAFlightMode = tr("FBW A");
64 const QString _flyByWireBFlightMode = tr("FBW B");
65 const QString _cruiseFlightMode = tr("Cruise");
66 const QString _autoTuneFlightMode = tr("Autotune");
67 const QString _autoFlightMode = tr("Auto");
68 const QString _rtlFlightMode = tr("RTL");
69 const QString _loiterFlightMode = tr("Loiter");
70 const QString _takeoffFlightMode = tr("Takeoff");
71 const QString _avoidADSBFlightMode = tr("Avoid ADSB");
72 const QString _guidedFlightMode = tr("Guided");
73 const QString _initializingFlightMode = tr("Initializing");
74 const QString _qStabilizeFlightMode = tr("QuadPlane Stabilize");
75 const QString _qHoverFlightMode = tr("QuadPlane Hover");
76 const QString _qLoiterFlightMode = tr("QuadPlane Loiter");
77 const QString _qLandFlightMode = tr("QuadPlane Land");
78 const QString _qRTLFlightMode = tr("QuadPlane RTL");
79 const QString _qAutotuneFlightMode = tr("QuadPlane AutoTune");
80 const QString _qAcroFlightMode = tr("QuadPlane Acro");
81 const QString _thermalFlightMode = tr("Thermal");
82 const QString _loiter2qlandFlightMode = tr("Loiter to QLand");
83 const QString _autolandFlightMode = tr("Autoland");
84
85private:
86 static bool _remapParamNameIntialized;
88};
QList< FirmwareFlightMode > FlightModeList
This is the base class for all stack specific APM firmware plugins.
QString pauseFlightMode() const override
Returns The flight mode which indicates the vehicle is paused.
int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const override
Returns the highest major version number that is known to the remap for this specified major version.
void updateAvailableFlightModes(FlightModeList &modeList) override
Update Available flight modes recieved from vehicle.
uint32_t _convertToCustomFlightModeEnum(uint32_t val) const override
QString stabilizedFlightMode() const override
Returns the flight mode for Stabilized.
QString offlineEditingParamFile(Vehicle *vehicle) const override
Return the resource file which contains the set of params loaded for offline editing.
QString autoDisarmParameter(Vehicle *vehicle) const override
const FirmwarePlugin::remapParamNameMajorVersionMap_t & paramNameRemapMajorVersionMap() const override
Returns the mapping structure which is used to map from one parameter name to another based on firmwa...
QString takeOffFlightMode() const override
Returns the flight mode for TakeOff.
QMap< int, remapParamNameMinorVersionRemapMap_t > remapParamNameMajorVersionMap_t