Browse Source

Copter: add allows_flip function to Mode class

zr-v5.1
Tatsuya Yamaguchi 5 years ago committed by Peter Barker
parent
commit
069b7142b7
  1. 5
      ArduCopter/mode.h
  2. 7
      ArduCopter/mode_flip.cpp

5
ArduCopter/mode.h

@ -62,6 +62,7 @@ public: @@ -62,6 +62,7 @@ public:
virtual bool logs_attitude() const { return false; }
virtual bool allows_save_trim() const { return false; }
virtual bool allows_autotune() const { return false; }
virtual bool allows_flip() const { return false; }
// return a string for this flightmode
virtual const char *name() const = 0;
@ -278,6 +279,7 @@ public: @@ -278,6 +279,7 @@ public:
// whether an air-mode aux switch has been toggled
void air_mode_aux_changed();
bool allows_save_trim() const override { return true; }
bool allows_flip() const override { return true; }
protected:
@ -328,6 +330,7 @@ public: @@ -328,6 +330,7 @@ public:
return !must_navigate;
}
bool allows_autotune() const override { return true; }
bool allows_flip() const override { return true; }
protected:
@ -723,6 +726,7 @@ public: @@ -723,6 +726,7 @@ public:
bool has_user_takeoff(bool must_navigate) const override {
return !must_navigate;
}
bool allows_flip() const override { return true; }
static const struct AP_Param::GroupInfo var_info[];
@ -1244,6 +1248,7 @@ public: @@ -1244,6 +1248,7 @@ public:
bool is_autopilot() const override { return false; }
bool allows_save_trim() const override { return true; }
bool allows_autotune() const override { return true; }
bool allows_flip() const override { return true; }
protected:

7
ArduCopter/mode_flip.cpp

@ -35,11 +35,8 @@ @@ -35,11 +35,8 @@
// flip_init - initialise flip controller
bool ModeFlip::init(bool ignore_checks)
{
// only allow flip from ACRO, Stabilize, AltHold or Drift flight modes
if (copter.flightmode != &copter.mode_acro &&
copter.flightmode != &copter.mode_stabilize &&
copter.flightmode != &copter.mode_althold &&
copter.flightmode != &copter.mode_flowhold) {
// only allow flip from some flight modes, for example ACRO, Stabilize, AltHold or FlowHold flight modes
if (!copter.flightmode->allows_flip()) {
return false;
}

Loading…
Cancel
Save