From 069b7142b7bfc96ab9aa64f1e909fb2ec97875de Mon Sep 17 00:00:00 2001 From: Tatsuya Yamaguchi Date: Tue, 11 Feb 2020 11:17:19 +0900 Subject: [PATCH] Copter: add allows_flip function to Mode class --- ArduCopter/mode.h | 5 +++++ ArduCopter/mode_flip.cpp | 7 ++----- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 03c530abd2..2b4c0f8b90 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -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: // 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: return !must_navigate; } bool allows_autotune() const override { return true; } + bool allows_flip() const override { return true; } protected: @@ -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: 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: diff --git a/ArduCopter/mode_flip.cpp b/ArduCopter/mode_flip.cpp index 4a5909eb60..bade71e5e9 100644 --- a/ArduCopter/mode_flip.cpp +++ b/ArduCopter/mode_flip.cpp @@ -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; }