1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#ifndef ArduCopterFirmwarePlugin_H
#define ArduCopterFirmwarePlugin_H
#include "APMFirmwarePlugin.h"
class APMCopterMode : public APMCustomMode
{
public:
enum Mode {
STABILIZE = 0, // hold level position
ACRO = 1, // rate control
ALT_HOLD = 2, // AUTO control
AUTO = 3, // AUTO control
GUIDED = 4, // AUTO control
LOITER = 5, // Hold a single location
RTL = 6, // AUTO control
CIRCLE = 7, // AUTO control
POSITION = 8, // AUTO control
LAND = 9, // AUTO control
OF_LOITER = 10, // Hold a single location using optical flow
// sensor
DRIFT = 11, // Drift 'Car Like' mode
RESERVED_12 = 12, // RESERVED FOR FUTURE USE
SPORT = 13, // [TODO] Verify this is correct.
FLIP = 14,
AUTOTUNE = 15,
POS_HOLD = 16, // HYBRID LOITER.
BRAKE = 17
};
static const int modeCount = 18;
APMCopterMode(uint32_t mode, bool settable);
};
class ArduCopterFirmwarePlugin : public APMFirmwarePlugin
{
Q_OBJECT
public:
ArduCopterFirmwarePlugin(void);
// Overrides from FirmwarePlugin
bool isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) final;
bool isPaused(const Vehicle* vehicle) const final;
void setGuidedMode(Vehicle* vehicle, bool guidedMode) final;
void pauseVehicle(Vehicle* vehicle) final;
void guidedModeRTL(Vehicle* vehicle) final;
void guidedModeLand(Vehicle* vehicle) final;
void guidedModeTakeoff(Vehicle* vehicle, double altitudeRel) final;
void guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord) final;
void guidedModeChangeAltitude(Vehicle* vehicle, double altitudeRel) final;
const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const final { return _remapParamName; }
int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const final;
bool multiRotorCoaxialMotors(Vehicle* vehicle) final;
bool multiRotorXConfig(Vehicle* vehicle) final;
QString geoFenceRadiusParam(Vehicle* vehicle) final;
QString offlineEditingParamFile(Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Copter.OfflineEditing.params"); }
private:
static bool _remapParamNameIntialized;
static FirmwarePlugin::remapParamNameMajorVersionMap_t _remapParamName;
};
#endif