Plane: mode.h remove init method

This commit is contained in:
Iampete1 2021-09-04 20:21:48 +01:00 committed by Andrew Tridgell
parent fae22b34b7
commit 2582159d1a

View File

@ -61,9 +61,6 @@ public:
// run controllers specific to this mode
virtual void run() {};
// init function, used only be quadplane modes, to be factored in to _enter() in the future
virtual void init() {};
// returns a unique number specific to this mode
virtual Number mode_number() const = 0;
@ -466,8 +463,6 @@ public:
void run() override;
void init() override;
protected:
private:
@ -492,8 +487,6 @@ public:
void run() override;
void init() override;
protected:
bool _enter() override;
@ -517,8 +510,6 @@ public:
void run() override;
void init() override;
protected:
bool _enter() override;
@ -539,8 +530,6 @@ public:
void run() override;
void init() override;
bool allows_arming() const override { return false; }
protected:
@ -563,8 +552,6 @@ public:
void run() override;
void init() override;
bool allows_arming() const override { return false; }
bool does_auto_throttle() const override { return true; }
@ -593,8 +580,6 @@ public:
void run() override;
void init() override;
protected:
bool _enter() override;