From e2157d8b9f48aa4e784a856a4dadfe87e1d6f6f8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 5 Oct 2023 11:50:51 +1100 Subject: [PATCH] Copter: remove un-needed PayloadPlace::run_should_run make this look like the other handling, especially in terms of what we do if we shouldn't be running --- ArduCopter/mode.h | 1 - ArduCopter/mode_auto.cpp | 27 ++------------------------- 2 files changed, 2 insertions(+), 26 deletions(-) diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 06ec5f33af..58559ba532 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -52,7 +52,6 @@ public: float descent_max_cm; private: - bool run_should_run(); void run_hover(); void run_descent(); void run_release(); diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 2ba2ae7583..740b7cae70 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -1164,8 +1164,8 @@ void PayloadPlace::run() { const char* prefix_str = "PayloadPlace:"; - if (!run_should_run()) { - copter.flightmode->zero_throttle_and_relax_ac(); + if (copter.flightmode->is_disarmed_or_landed()) { + copter.flightmode->make_safe_ground_handling(); return; } @@ -1369,29 +1369,6 @@ void PayloadPlace::run() } } -bool PayloadPlace::run_should_run() -{ - // must be armed - if (!copter.motors->armed()) { - return false; - } - // must be auto-armed - if (!copter.ap.auto_armed) { - return false; - } - // must not be landed - if (copter.ap.land_complete && - (state == State::FlyToLocation || state == State::Descent_Start)) { - return false; - } - // interlock must be enabled (i.e. unsafe) - if (!copter.motors->get_interlock()) { - return false; - } - - return true; -} - void PayloadPlace::run_hover() { const auto &pos_control = copter.pos_control;