From 34748e681fc4a4b5311a1212a75fd3cbb96c191c Mon Sep 17 00:00:00 2001 From: rtos-kawamura <150573421+robot-to-society@users.noreply.github.com> Date: Thu, 18 Jan 2024 09:13:49 +0900 Subject: [PATCH] Copter: simplify get_target_location Co-authored-by: Peter Hall <33176108+IamPete1@users.noreply.github.com> --- ArduCopter/Copter.cpp | 14 +------------- 1 file changed, 1 insertion(+), 13 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 3ec65c46b1..d8e1b684a7 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -449,19 +449,7 @@ bool Copter::has_ekf_failsafed() const // get target location (for use by scripting) bool Copter::get_target_location(Location& target_loc) { - switch (flightmode->mode_number()) { - case Mode::Number::RTL: - case Mode::Number::SMART_RTL: - case Mode::Number::AVOID_ADSB: - case Mode::Number::GUIDED: - case Mode::Number::AUTO: - case Mode::Number::FOLLOW: - return flightmode->get_wp(target_loc); - break; - default: - break; - } - return false; + return flightmode->get_wp(target_loc); } /*