Copter: simplify get_target_location

Co-authored-by: Peter Hall <33176108+IamPete1@users.noreply.github.com>
This commit is contained in:
rtos-kawamura 2024-01-18 09:13:49 +09:00 committed by Randy Mackay
parent b9bf7acbf1
commit 34748e681f
1 changed files with 1 additions and 13 deletions

View File

@ -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);
}
/*