From 0bcb3ece8518a20c35cef13fe649a660ef7d8173 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 23 Aug 2023 10:41:37 +1000 Subject: [PATCH] Rover: rely on magic conversion to handle DO_SET_REVERSE as both int/long --- Rover/GCS_Mavlink.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index 3a7d31ae12..88323f303a 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -686,11 +686,6 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_l } return MAV_RESULT_ACCEPTED; - case MAV_CMD_DO_SET_REVERSE: - // param1 : Direction (0=Forward, 1=Reverse) - rover.control_mode->set_reversed(is_equal(packet.param1,1.0f)); - return MAV_RESULT_ACCEPTED; - case MAV_CMD_NAV_SET_YAW_SPEED: { // param1 : yaw angle to adjust direction by in centidegress