From 8decb9d43fc3bff252e3fd8264df85548f9594af Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 23 Aug 2023 22:17:25 +1000 Subject: [PATCH] Rover: rely on magic long-to-int conversion to handle MAV_CMD_DO_CHANGE_SPEED --- Rover/GCS_Mavlink.cpp | 8 -------- 1 file changed, 8 deletions(-) diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index 2eef43bd6f2b1..dc419cfcd3909 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -678,14 +678,6 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_l } return MAV_RESULT_FAILED; - case MAV_CMD_DO_CHANGE_SPEED: - // param1 : unused - // param2 : new speed in m/s - if (!rover.control_mode->set_desired_speed(packet.param2)) { - return MAV_RESULT_FAILED; - } - return MAV_RESULT_ACCEPTED; - case MAV_CMD_NAV_SET_YAW_SPEED: { // param1 : yaw angle to adjust direction by in centidegress