From f4eed612d76b6098c2d19745ef18eb488071298c Mon Sep 17 00:00:00 2001 From: Tatsuya Yamaguchi Date: Tue, 11 Feb 2020 11:06:57 +0900 Subject: [PATCH] Copter: add allows_autotune function to Mode class --- ArduCopter/mode.h | 5 +++++ ArduCopter/mode_autotune.cpp | 7 ++----- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index debb32d9ea..03c530abd2 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -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: diff --git a/ArduCopter/mode_autotune.cpp b/ArduCopter/mode_autotune.cpp index 3de56f970f..4f5dbcc1d3 100644 --- a/ArduCopter/mode_autotune.cpp +++ b/ArduCopter/mode_autotune.cpp @@ -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; }