From ecad165f862eab5c300ecd41b3b969012463564b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 25 May 2022 21:23:06 +0900 Subject: [PATCH] Copter: remove Auto mode's rare use of mode() method --- ArduCopter/mode.h | 4 +--- ArduCopter/mode_auto.cpp | 2 +- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 266f9b6e2c..15259b009d 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -404,7 +404,7 @@ public: bool has_manual_throttle() const override { return false; } bool allows_arming(AP_Arming::Method method) const override; bool is_autopilot() const override { return true; } - bool in_guided_mode() const override { return mode() == SubMode::NAVGUIDED || mode() == SubMode::NAV_SCRIPT_TIME; } + bool in_guided_mode() const override { return _mode == SubMode::NAVGUIDED || _mode == SubMode::NAV_SCRIPT_TIME; } // Auto modes enum class SubMode : uint8_t { @@ -422,8 +422,6 @@ public: NAV_ATTITUDE_TIME, }; - // Auto - SubMode mode() const { return _mode; } // pause continue in auto mode bool pause() override; diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index a500672543..b6008962c1 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -695,7 +695,7 @@ void ModeAuto::exit_mission() bool ModeAuto::do_guided(const AP_Mission::Mission_Command& cmd) { // only process guided waypoint if we are in guided mode - if (copter.flightmode->mode_number() != Mode::Number::GUIDED && !(copter.flightmode->mode_number() == Mode::Number::AUTO && mode() == SubMode::NAVGUIDED)) { + if (copter.flightmode->mode_number() != Mode::Number::GUIDED && !(copter.flightmode->mode_number() == Mode::Number::AUTO && _mode == SubMode::NAVGUIDED)) { return false; }