Copter: add allows_autotune function to Mode class
This commit is contained in:
parent
2b89ac625f
commit
f4eed612d7
@ -61,6 +61,7 @@ public:
|
||||
virtual bool in_guided_mode() const { return false; }
|
||||
virtual bool logs_attitude() const { return false; }
|
||||
virtual bool allows_save_trim() const { return false; }
|
||||
virtual bool allows_autotune() const { return false; }
|
||||
|
||||
// return a string for this flightmode
|
||||
virtual const char *name() const = 0;
|
||||
@ -326,6 +327,7 @@ public:
|
||||
bool has_user_takeoff(bool must_navigate) const override {
|
||||
return !must_navigate;
|
||||
}
|
||||
bool allows_autotune() const override { return true; }
|
||||
|
||||
protected:
|
||||
|
||||
@ -933,6 +935,7 @@ public:
|
||||
bool allows_arming(bool from_gcs) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool has_user_takeoff(bool must_navigate) const override { return true; }
|
||||
bool allows_autotune() const override { return true; }
|
||||
|
||||
#if PRECISION_LANDING == ENABLED
|
||||
void set_precision_loiter_enabled(bool value) { _precision_loiter_enabled = value; }
|
||||
@ -975,6 +978,7 @@ public:
|
||||
bool allows_arming(bool from_gcs) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool has_user_takeoff(bool must_navigate) const override { return true; }
|
||||
bool allows_autotune() const override { return true; }
|
||||
|
||||
protected:
|
||||
|
||||
@ -1239,6 +1243,7 @@ public:
|
||||
bool allows_arming(bool from_gcs) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool allows_save_trim() const override { return true; }
|
||||
bool allows_autotune() const override { return true; }
|
||||
|
||||
protected:
|
||||
|
||||
|
@ -23,11 +23,8 @@ bool AutoTune::init()
|
||||
*/
|
||||
bool AutoTune::start()
|
||||
{
|
||||
// only allow flip from Stabilize, AltHold, PosHold or Loiter modes
|
||||
if (copter.flightmode != &copter.mode_stabilize &&
|
||||
copter.flightmode != &copter.mode_althold &&
|
||||
copter.flightmode != &copter.mode_loiter &&
|
||||
copter.flightmode != &copter.mode_poshold) {
|
||||
// only allow AutoTune from some flight modes, for example Stabilize, AltHold, PosHold or Loiter modes
|
||||
if (!copter.flightmode->allows_autotune()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user