From add5eb69077924841a7c8279cedf6c229a4fb3fb Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 18 Sep 2017 14:34:12 +1000 Subject: [PATCH] Rover: remove old DO_SET_MODE support We no longer support setting modes except via custom-modes --- APMrover2/GCS_Mavlink.cpp | 25 ------------------------- 1 file changed, 25 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index dc1da0d141..c1346bf6f9 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -799,31 +799,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) } break; - case MAV_CMD_DO_SET_MODE: - switch (static_cast(packet.param1)) { - case MAV_MODE_MANUAL_ARMED: - case MAV_MODE_MANUAL_DISARMED: - rover.set_mode(rover.mode_manual, MODE_REASON_GCS_COMMAND); - result = MAV_RESULT_ACCEPTED; - break; - - case MAV_MODE_AUTO_ARMED: - case MAV_MODE_AUTO_DISARMED: - rover.set_mode(rover.mode_auto, MODE_REASON_GCS_COMMAND); - result = MAV_RESULT_ACCEPTED; - break; - - case MAV_MODE_STABILIZE_DISARMED: - case MAV_MODE_STABILIZE_ARMED: - rover.set_mode(rover.mode_steering, MODE_REASON_GCS_COMMAND); - result = MAV_RESULT_ACCEPTED; - break; - - default: - result = MAV_RESULT_UNSUPPORTED; - } - break; - case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN: if (is_equal(packet.param1, 1.0f) || is_equal(packet.param1, 3.0f)) { // when packet.param1 == 3 we reboot to hold in bootloader