From 631d8f542355a533a21136d915bae09651b30d73 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 9 Jun 2018 10:23:46 +0900 Subject: [PATCH] Rover: accept do-change-speed commands with high speeds --- APMrover2/commands_logic.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/APMrover2/commands_logic.cpp b/APMrover2/commands_logic.cpp index 7aee6bdd4d..f5ac3bada9 100644 --- a/APMrover2/commands_logic.cpp +++ b/APMrover2/commands_logic.cpp @@ -375,8 +375,7 @@ bool Rover::verify_within_distance() void Rover::do_change_speed(const AP_Mission::Mission_Command& cmd) { // set speed for active mode - if ((cmd.content.speed.target_ms >= 0.0f) && (cmd.content.speed.target_ms <= rover.control_mode->get_speed_default())) { - control_mode->set_desired_speed(cmd.content.speed.target_ms); + if (control_mode->set_desired_speed(cmd.content.speed.target_ms)) { gcs().send_text(MAV_SEVERITY_INFO, "speed: %.1f m/s", static_cast(cmd.content.speed.target_ms)); } }