QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
ArduRoverFirmwarePlugin.cc
Go to the documentation of this file.
2#include "AppMessages.h"
3#include "Vehicle.h"
4
5bool ArduRoverFirmwarePlugin::_remapParamNameIntialized = false;
6FirmwarePlugin::remapParamNameMajorVersionMap_t ArduRoverFirmwarePlugin::_remapParamName;
7
9 : APMFirmwarePlugin(parent)
10{
27 });
28
29 static FlightModeList availableFlightModes = {
30 // Mode Name , Custom Mode CanBeSet adv
31 { _manualFlightMode , APMRoverMode::MANUAL , true , true},
32 { _acroFlightMode , APMRoverMode::ACRO , true , true},
35 { _holdFlightMode , APMRoverMode::HOLD , true , true},
36 { _loiterFlightMode , APMRoverMode::LOITER , true , true},
37 { _followFlightMode , APMRoverMode::FOLLOW , true , true},
38 { _simpleFlightMode , APMRoverMode::SIMPLE , true , true},
39 { _dockFlightMode , APMRoverMode::DOCK , true , true},
40 { _circleFlightMode , APMRoverMode::CIRCLE , true , true},
41 { _autoFlightMode , APMRoverMode::AUTO , true , true},
42 { _rtlFlightMode , APMRoverMode::RTL , true , true},
44 { _guidedFlightMode , APMRoverMode::GUIDED , true , true},
46 };
47 updateAvailableFlightModes(availableFlightModes);
48
49 if (!_remapParamNameIntialized) {
50 // ArduPilot 4.7: parameter renames and SI unit conversion
51 FirmwarePlugin::remapParamNameMap_t &remapV4_7 = _remapParamName[4][7];
52
53 // EKF
54 remapV4_7["EK3_FLOW_MAX"] = QStringLiteral("EK3_MAX_FLOW");
55
56 // Common
57 remapV4_7["ARMING_SKIPCHK"] = QStringLiteral("ARMING_CHECK");
58
59 _remapParamNameIntialized = true;
60 }
61}
62
67
69{
70 return ((majorVersionNumber == 4) ? 7 : Vehicle::versionNotSetValue);
71}
72
73void ArduRoverFirmwarePlugin::guidedModeChangeAltitude(Vehicle* /*vehicle*/, double /*altitudeChange*/, bool /*pauseVehicle*/)
74{
75 QGC::showAppMessage(QStringLiteral("Change altitude not supported."));
76}
77
82
87
92
94{
95 for (FirmwareFlightMode &mode: modeList) {
96 mode.fixedWing = false;
97 mode.multiRotor = true;
98 }
99
100 _updateFlightModeList(modeList);
101}
102
104{
105 switch (val) {
107 return APMRoverMode::AUTO;
111 return APMRoverMode::RTL;
114 default:
115 return UINT32_MAX;
116 }
117}
QList< FirmwareFlightMode > FlightModeList
This is the base class for all stack specific APM firmware plugins.
QString followFlightMode() const override
Returns the flight mode which the vehicle will be for follow me.
void guidedModeChangeAltitude(Vehicle *vehicle, double altitudeChange, bool pauseVehicle) override
void updateAvailableFlightModes(FlightModeList &modeList) override
Update Available flight modes recieved from vehicle.
ArduRoverFirmwarePlugin(QObject *parent=nullptr)
QString pauseFlightMode() const override
Returns The flight mode which indicates the vehicle is paused.
int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const override
QString stabilizedFlightMode() const override
Returns the flight mode for Stabilized.
uint32_t _convertToCustomFlightModeEnum(uint32_t val) const override
void _setModeEnumToModeStringMapping(FlightModeCustomModeMap enumToString)
void _updateFlightModeList(FlightModeList &flightModeList)
QMap< QString, QString > remapParamNameMap_t
FlightModeCustomModeMap _modeEnumToString
QMap< int, remapParamNameMinorVersionRemapMap_t > remapParamNameMajorVersionMap_t
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
Definition AppMessages.cc:9
static const int versionNotSetValue