QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
ArduPlaneFirmwarePlugin.cc
Go to the documentation of this file.
2#include "Vehicle.h"
3
4bool ArduPlaneFirmwarePlugin::_remapParamNameIntialized = false;
5FirmwarePlugin::remapParamNameMajorVersionMap_t ArduPlaneFirmwarePlugin::_remapParamName;
6
8 : APMFirmwarePlugin(parent)
9{
37
38 });
39
40 static FlightModeList availableFlightModes = {
41 // Mode Name , Custom Mode CanBeSet adv
42 { _manualFlightMode , APMPlaneMode::MANUAL , true , true },
43 { _circleFlightMode , APMPlaneMode::CIRCLE , true , true },
46 { _acroFlightMode , APMPlaneMode::ACRO , true , true },
49 { _cruiseFlightMode , APMPlaneMode::CRUISE , true , true },
51 { _autoFlightMode , APMPlaneMode::AUTO , true , true },
52 { _rtlFlightMode , APMPlaneMode::RTL , true , true },
53 { _loiterFlightMode , APMPlaneMode::LOITER , true , true },
54 { _takeoffFlightMode , APMPlaneMode::TAKEOFF , true , true },
56 { _guidedFlightMode , APMPlaneMode::GUIDED , true , true },
59 { _qHoverFlightMode , APMPlaneMode::QHOVER , true , true },
60 { _qLoiterFlightMode , APMPlaneMode::QLOITER , true , true },
61 { _qLandFlightMode , APMPlaneMode::QLAND , true , true },
62 { _qRTLFlightMode , APMPlaneMode::QRTL , true , true },
64 { _qAcroFlightMode , APMPlaneMode::QACRO , true , true },
65 { _thermalFlightMode , APMPlaneMode::THERMAL , true , true },
68 };
69 updateAvailableFlightModes(availableFlightModes);
70
71 if (!_remapParamNameIntialized) {
72 FirmwarePlugin::remapParamNameMap_t &remapV4_5 = _remapParamName[4][5];
73
74 remapV4_5["AIRSPEED_MIN"] = QStringLiteral("ARSPD_FBW_MIN");
75 remapV4_5["AIRSPEED_MAX"] = QStringLiteral("ARSPD_FBW_MAX");
76 remapV4_5["RTL_ALTITUDE"] = QStringLiteral("ALT_HOLD_RTL");
77 // LAND_SPEED is only used in a Copter component
78
79 _remapParamNameIntialized = true;
80 }
81}
82
87
89{
90 // Remapping supports up to 4.5
91 return ((majorVersionNumber == 4) ? 5 : Vehicle::versionNotSetValue);
92}
93
98
103
108
110{
111 for (FirmwareFlightMode &mode: modeList) {
112 mode.fixedWing = true;
113 mode.multiRotor = true;
114 }
115
116 _updateFlightModeList(modeList);
117}
118
120{
121 switch (val) {
123 return APMPlaneMode::AUTO;
127 return APMPlaneMode::RTL;
129 return APMPlaneMode::RTL;
130 default:
131 return UINT32_MAX;
132 }
133}
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.
ArduPlaneFirmwarePlugin(QObject *parent=nullptr)
QString takeOffFlightMode() const override
Returns the flight mode for TakeOff.
void _setModeEnumToModeStringMapping(FlightModeCustomModeMap enumToString)
void _updateFlightModeList(FlightModeList &flightModeList)
QMap< QString, QString > remapParamNameMap_t
FlightModeCustomModeMap _modeEnumToString
QMap< int, remapParamNameMinorVersionRemapMap_t > remapParamNameMajorVersionMap_t
static const int versionNotSetValue
Definition Vehicle.h:702