|
|
|
@ -45,6 +45,9 @@ public:
@@ -45,6 +45,9 @@ public:
|
|
|
|
|
Mode(const Mode &other) = delete; |
|
|
|
|
Mode &operator=(const Mode&) = delete; |
|
|
|
|
|
|
|
|
|
// returns a unique number specific to this mode
|
|
|
|
|
virtual Number mode_number() const = 0; |
|
|
|
|
|
|
|
|
|
// child classes should override these methods
|
|
|
|
|
virtual bool init(bool ignore_checks) { |
|
|
|
|
return true; |
|
|
|
@ -249,6 +252,7 @@ class ModeAcro : public Mode {
@@ -249,6 +252,7 @@ class ModeAcro : public Mode {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::ACRO; } |
|
|
|
|
|
|
|
|
|
enum class Trainer { |
|
|
|
|
OFF = 0, |
|
|
|
@ -308,6 +312,7 @@ class ModeAltHold : public Mode {
@@ -308,6 +312,7 @@ class ModeAltHold : public Mode {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::ALT_HOLD; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
@ -335,6 +340,7 @@ class ModeAuto : public Mode {
@@ -335,6 +340,7 @@ class ModeAuto : public Mode {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::AUTO; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
@ -538,6 +544,7 @@ class ModeAutoTune : public Mode {
@@ -538,6 +544,7 @@ class ModeAutoTune : public Mode {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::AUTOTUNE; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
@ -564,6 +571,7 @@ class ModeBrake : public Mode {
@@ -564,6 +571,7 @@ class ModeBrake : public Mode {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::BRAKE; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
@ -595,6 +603,7 @@ class ModeCircle : public Mode {
@@ -595,6 +603,7 @@ class ModeCircle : public Mode {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::CIRCLE; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
@ -625,6 +634,7 @@ class ModeDrift : public Mode {
@@ -625,6 +634,7 @@ class ModeDrift : public Mode {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::DRIFT; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
@ -651,6 +661,7 @@ class ModeFlip : public Mode {
@@ -651,6 +661,7 @@ class ModeFlip : public Mode {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::FLIP; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
@ -696,6 +707,7 @@ class ModeFlowHold : public Mode {
@@ -696,6 +707,7 @@ class ModeFlowHold : public Mode {
|
|
|
|
|
public: |
|
|
|
|
// need a constructor for parameters
|
|
|
|
|
ModeFlowHold(void); |
|
|
|
|
Number mode_number() const override { return Number::FLOWHOLD; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run(void) override; |
|
|
|
@ -778,6 +790,7 @@ class ModeGuided : public Mode {
@@ -778,6 +790,7 @@ class ModeGuided : public Mode {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::GUIDED; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
@ -853,6 +866,7 @@ class ModeGuidedNoGPS : public ModeGuided {
@@ -853,6 +866,7 @@ class ModeGuidedNoGPS : public ModeGuided {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using ModeGuided::Mode; |
|
|
|
|
Number mode_number() const override { return Number::GUIDED_NOGPS; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
@ -876,6 +890,7 @@ class ModeLand : public Mode {
@@ -876,6 +890,7 @@ class ModeLand : public Mode {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::LAND; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
@ -906,6 +921,7 @@ class ModeLoiter : public Mode {
@@ -906,6 +921,7 @@ class ModeLoiter : public Mode {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::LOITER; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
@ -947,6 +963,7 @@ class ModePosHold : public Mode {
@@ -947,6 +963,7 @@ class ModePosHold : public Mode {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::POSHOLD; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
@ -1027,6 +1044,7 @@ class ModeRTL : public Mode {
@@ -1027,6 +1044,7 @@ class ModeRTL : public Mode {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::RTL; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override { |
|
|
|
@ -1136,6 +1154,7 @@ class ModeSmartRTL : public ModeRTL {
@@ -1136,6 +1154,7 @@ class ModeSmartRTL : public ModeRTL {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using ModeRTL::Mode; |
|
|
|
|
Number mode_number() const override { return Number::SMART_RTL; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
@ -1181,6 +1200,7 @@ class ModeSport : public Mode {
@@ -1181,6 +1200,7 @@ class ModeSport : public Mode {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::SPORT; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
@ -1208,6 +1228,7 @@ class ModeStabilize : public Mode {
@@ -1208,6 +1228,7 @@ class ModeStabilize : public Mode {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::STABILIZE; } |
|
|
|
|
|
|
|
|
|
virtual void run() override; |
|
|
|
|
|
|
|
|
@ -1246,6 +1267,7 @@ class ModeSystemId : public Mode {
@@ -1246,6 +1267,7 @@ class ModeSystemId : public Mode {
|
|
|
|
|
|
|
|
|
|
public: |
|
|
|
|
ModeSystemId(void); |
|
|
|
|
Number mode_number() const override { return Number::SYSTEMID; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
@ -1313,6 +1335,7 @@ class ModeThrow : public Mode {
@@ -1313,6 +1335,7 @@ class ModeThrow : public Mode {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::THROW; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
@ -1369,6 +1392,7 @@ class ModeAvoidADSB : public ModeGuided {
@@ -1369,6 +1392,7 @@ class ModeAvoidADSB : public ModeGuided {
|
|
|
|
|
public: |
|
|
|
|
// inherit constructor
|
|
|
|
|
using ModeGuided::Mode; |
|
|
|
|
Number mode_number() const override { return Number::AVOID_ADSB; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
@ -1395,6 +1419,7 @@ public:
@@ -1395,6 +1419,7 @@ public:
|
|
|
|
|
|
|
|
|
|
// inherit constructor
|
|
|
|
|
using ModeGuided::Mode; |
|
|
|
|
Number mode_number() const override { return Number::FOLLOW; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void exit(); |
|
|
|
@ -1425,6 +1450,7 @@ public:
@@ -1425,6 +1450,7 @@ public:
|
|
|
|
|
|
|
|
|
|
// Inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::ZIGZAG; } |
|
|
|
|
|
|
|
|
|
enum class Destination : uint8_t { |
|
|
|
|
A, // Destination A
|
|
|
|
@ -1517,6 +1543,7 @@ public:
@@ -1517,6 +1543,7 @@ public:
|
|
|
|
|
|
|
|
|
|
// inherit constructor
|
|
|
|
|
using Mode::Mode; |
|
|
|
|
Number mode_number() const override { return Number::AUTOROTATE; } |
|
|
|
|
|
|
|
|
|
bool init(bool ignore_checks) override; |
|
|
|
|
void run() override; |
|
|
|
|