Plane: mode: add run and init methods
This commit is contained in:
parent
03d17437c3
commit
a808d5c688
@ -54,6 +54,12 @@ public:
|
||||
// perform any cleanups required:
|
||||
void exit();
|
||||
|
||||
// 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;
|
||||
|
||||
@ -446,6 +452,10 @@ public:
|
||||
// used as a base class for all Q modes
|
||||
bool _enter() override;
|
||||
|
||||
void run() override;
|
||||
|
||||
void init() override;
|
||||
|
||||
protected:
|
||||
private:
|
||||
|
||||
@ -468,6 +478,10 @@ public:
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
||||
void run() override;
|
||||
|
||||
void init() override;
|
||||
|
||||
protected:
|
||||
|
||||
bool _enter() override;
|
||||
@ -475,6 +489,8 @@ protected:
|
||||
|
||||
class ModeQLoiter : public Mode
|
||||
{
|
||||
friend class QuadPlane;
|
||||
friend class ModeQLand;
|
||||
public:
|
||||
|
||||
Number mode_number() const override { return Number::QLOITER; }
|
||||
@ -487,6 +503,10 @@ public:
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
||||
void run() override;
|
||||
|
||||
void init() override;
|
||||
|
||||
protected:
|
||||
|
||||
bool _enter() override;
|
||||
@ -505,6 +525,10 @@ public:
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
||||
void run() override;
|
||||
|
||||
void init() override;
|
||||
|
||||
bool allows_arming() const override { return false; }
|
||||
|
||||
protected:
|
||||
@ -525,6 +549,10 @@ public:
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
||||
void run() override;
|
||||
|
||||
void init() override;
|
||||
|
||||
bool allows_arming() const override { return false; }
|
||||
|
||||
bool does_auto_throttle() const override { return true; }
|
||||
@ -551,6 +579,10 @@ public:
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
||||
void run() override;
|
||||
|
||||
void init() override;
|
||||
|
||||
protected:
|
||||
|
||||
bool _enter() override;
|
||||
@ -567,6 +599,8 @@ public:
|
||||
bool is_vtol_mode() const override { return true; }
|
||||
virtual bool is_vtol_man_mode() const override { return true; }
|
||||
|
||||
void run() override;
|
||||
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user