QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
ArduRoverFirmwarePlugin.cc
Go to the documentation of this file.
2#include "QGCApplication.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 _remapParamNameIntialized = true;
51 }
52}
53
58
60{
61 // Remapping not supported
63}
64
65void ArduRoverFirmwarePlugin::guidedModeChangeAltitude(Vehicle* /*vehicle*/, double /*altitudeChange*/, bool /*pauseVehicle*/)
66{
67 qgcApp()->showAppMessage(QStringLiteral("Change altitude not supported."));
68}
69
74
79
84
86{
87 for (FirmwareFlightMode &mode: modeList) {
88 mode.fixedWing = false;
89 mode.multiRotor = true;
90 }
91
92 _updateFlightModeList(modeList);
93}
94
96{
97 switch (val) {
99 return APMRoverMode::AUTO;
103 return APMRoverMode::RTL;
106 default:
107 return UINT32_MAX;
108 }
109}
QList< FirmwareFlightMode > FlightModeList
#define qgcApp()
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
Returns the highest major version number that is known to the remap for this specified major version.
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)
FlightModeCustomModeMap _modeEnumToString
QMap< int, remapParamNameMinorVersionRemapMap_t > remapParamNameMajorVersionMap_t
static const int versionNotSetValue
Definition Vehicle.h:702