From 5718c49928689f23c1cc284e80266cbeea6f3639 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 5 Dec 2023 08:52:52 +0900 Subject: [PATCH] Copter: set-desired-speed applied to flightmode --- ArduCopter/Copter.cpp | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index f5242feb0d..c121865134 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -404,13 +404,7 @@ bool Copter::set_circle_rate(float rate_dps) // set desired speed (m/s). Used for scripting. bool Copter::set_desired_speed(float speed) { - // exit if vehicle is not in auto mode - if (!flightmode->is_autopilot()) { - return false; - } - - wp_nav->set_speed_xy(speed * 100.0f); - return true; + return flightmode->set_speed_xy(speed * 100.0f); } #if MODE_AUTO_ENABLED == ENABLED