QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
ArduCopterFirmwarePlugin.cc
Go to the documentation of this file.
2#include "ParameterManager.h"
3#include "Vehicle.h"
4
5bool ArduCopterFirmwarePlugin::_remapParamNameIntialized = false;
6FirmwarePlugin::remapParamNameMajorVersionMap_t ArduCopterFirmwarePlugin::_remapParamName;
7
9 : APMFirmwarePlugin(parent)
10{
12 { APMCopterMode::STABILIZE, _stabilizeFlightMode },
13 { APMCopterMode::ACRO, _acroFlightMode },
14 { APMCopterMode::ALT_HOLD, _altHoldFlightMode },
15 { APMCopterMode::AUTO, _autoFlightMode },
16 { APMCopterMode::GUIDED, _guidedFlightMode },
17 { APMCopterMode::LOITER, _loiterFlightMode },
18 { APMCopterMode::RTL, _rtlFlightMode },
19 { APMCopterMode::CIRCLE, _circleFlightMode },
20 { APMCopterMode::LAND, _landFlightMode },
21 { APMCopterMode::DRIFT, _driftFlightMode },
22 { APMCopterMode::SPORT, _sportFlightMode },
23 { APMCopterMode::FLIP, _flipFlightMode },
24 { APMCopterMode::AUTOTUNE, _autotuneFlightMode },
25 { APMCopterMode::POS_HOLD, _posHoldFlightMode },
26 { APMCopterMode::BRAKE, _brakeFlightMode },
27 { APMCopterMode::THROW, _throwFlightMode },
28 { APMCopterMode::AVOID_ADSB, _avoidADSBFlightMode },
29 { APMCopterMode::GUIDED_NOGPS, _guidedNoGPSFlightMode },
30 { APMCopterMode::SMART_RTL, _smartRtlFlightMode },
31 { APMCopterMode::FLOWHOLD, _flowHoldFlightMode },
32 { APMCopterMode::FOLLOW, _followFlightMode },
33 { APMCopterMode::ZIGZAG, _zigzagFlightMode },
34 { APMCopterMode::SYSTEMID, _systemIDFlightMode },
35 { APMCopterMode::AUTOROTATE, _autoRotateFlightMode },
36 { APMCopterMode::AUTO_RTL, _autoRTLFlightMode },
37 { APMCopterMode::TURTLE, _turtleFlightMode },
38 });
39
40 static FlightModeList availableFlightModes = {
41 // Mode Name , Custom Mode CanBeSet adv
42 { _stabilizeFlightMode , APMCopterMode::STABILIZE, true , true },
43 { _acroFlightMode , APMCopterMode::ACRO, true , true },
44 { _altHoldFlightMode , APMCopterMode::ALT_HOLD, true , true },
45 { _autoFlightMode , APMCopterMode::AUTO, true , true },
46 { _guidedFlightMode , APMCopterMode::GUIDED, true , true },
47 { _loiterFlightMode , APMCopterMode::LOITER, true , true },
48 { _rtlFlightMode , APMCopterMode::RTL, true , true },
49 { _circleFlightMode , APMCopterMode::CIRCLE, true , true },
50 { _landFlightMode , APMCopterMode::LAND, true , true },
51 { _driftFlightMode , APMCopterMode::DRIFT, true , true },
52 { _sportFlightMode , APMCopterMode::SPORT, true , true },
53 { _flipFlightMode , APMCopterMode::FLIP, true , true },
54 { _autotuneFlightMode , APMCopterMode::AUTOTUNE, true , true },
55 { _posHoldFlightMode , APMCopterMode::POS_HOLD, true , true },
56 { _brakeFlightMode , APMCopterMode::BRAKE, true , true },
57 { _throwFlightMode , APMCopterMode::THROW, true , true },
58 { _avoidADSBFlightMode , APMCopterMode::AVOID_ADSB, true , true },
59 { _guidedNoGPSFlightMode , APMCopterMode::GUIDED_NOGPS, true , true },
60 { _smartRtlFlightMode , APMCopterMode::SMART_RTL, true , true },
61 { _flowHoldFlightMode , APMCopterMode::FLOWHOLD, true , true },
62 { _followFlightMode , APMCopterMode::FOLLOW, true , true },
63 { _zigzagFlightMode , APMCopterMode::ZIGZAG, true , true },
64 { _systemIDFlightMode , APMCopterMode::SYSTEMID, true , true },
65 { _autoRotateFlightMode , APMCopterMode::AUTOROTATE, true , true },
66 { _autoRTLFlightMode , APMCopterMode::AUTO_RTL, true , true },
67 { _turtleFlightMode , APMCopterMode::TURTLE, true , true },
68 };
69 updateAvailableFlightModes(availableFlightModes);
70
71 if (!_remapParamNameIntialized) {
72 FirmwarePlugin::remapParamNameMap_t &remapV4_0 = _remapParamName[4][0];
73
74 remapV4_0["TUNE_MIN"] = QStringLiteral("TUNE_LOW");
75 remapV4_0["TUNE_MAX"] = QStringLiteral("TUNE_HIGH");
76
77 _remapParamNameIntialized = true;
78 }
79}
80
85
87{
88 return ((majorVersionNumber == 4) ? 0 : Vehicle::versionNotSetValue);
89}
90
92{
93 return (vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, "FRAME")->rawValue().toInt() != 0);
94}
95
97{
98 return _modeEnumToString.value(APMCopterMode::BRAKE, _brakeFlightMode);
99}
100
102{
103 return _modeEnumToString.value(APMCopterMode::LAND, _landFlightMode);
104}
105
107{
108 return _modeEnumToString.value(APMCopterMode::LOITER, _loiterFlightMode);
109}
110
112{
113 return _modeEnumToString.value(APMCopterMode::FOLLOW, _followFlightMode);
114}
115
117{
118 return _modeEnumToString.value(APMCopterMode::STABILIZE, _stabilizeFlightMode);
119}
120
122{
123 for (FirmwareFlightMode &mode: modeList) {
124 mode.fixedWing = false;
125 mode.multiRotor = true;
126 }
127
128 _updateFlightModeList(modeList);
129
130}
131
133{
134 switch (val) {
136 return APMCopterMode::AUTO;
140 return APMCopterMode::RTL;
143 default:
144 return UINT32_MAX;
145 }
146}
QList< FirmwareFlightMode > FlightModeList
This is the base class for all stack specific APM firmware plugins.
ArduCopterFirmwarePlugin(QObject *parent=nullptr)
uint32_t _convertToCustomFlightModeEnum(uint32_t val) const override
void updateAvailableFlightModes(FlightModeList &modeList) override
Update Available flight modes recieved from vehicle.
QString followFlightMode() const override
Returns the flight mode which the vehicle will be for follow me.
int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const override
Returns the highest major version number that is known to the remap for this specified major version.
QString landFlightMode() const override
Returns the flight mode for Land.
QString stabilizedFlightMode() const override
Returns the flight mode for Stabilized.
bool multiRotorXConfig(Vehicle *vehicle) const override
QString pauseFlightMode() const override
Returns The flight mode which indicates the vehicle is paused.
QString takeControlFlightMode() const override
Returns the flight mode to use when the operator wants to take back control from autonomouse flight.
void _setModeEnumToModeStringMapping(FlightModeCustomModeMap enumToString)
void _updateFlightModeList(FlightModeList &flightModeList)
QMap< QString, QString > remapParamNameMap_t
FlightModeCustomModeMap _modeEnumToString
QMap< int, remapParamNameMinorVersionRemapMap_t > remapParamNameMajorVersionMap_t
Fact * getParameter(int componentId, const QString &paramName)
static constexpr int defaultComponentId
static const int versionNotSetValue
Definition Vehicle.h:702
ParameterManager * parameterManager()
Definition Vehicle.h:578