From e347618210bec5554c8e648a6a974c12ee6a6ba6 Mon Sep 17 00:00:00 2001 From: Tatsuya Yamaguchi Date: Tue, 6 Oct 2020 08:54:38 +0900 Subject: [PATCH] Rover: support speed control of DO_REPOSITION --- Rover/GCS_Mavlink.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index c1b8cb2c8d..30b1ea062f 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -718,6 +718,12 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_do_reposition(const mavlink_com } } + if (is_positive(packet.param1)) { + if (!rover.control_mode->set_desired_speed(packet.param1)) { + return MAV_RESULT_FAILED; + } + } + // set the destination if (!rover.mode_guided.set_desired_location(request_location)) { return MAV_RESULT_FAILED;