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