From e1408696dc2f255e91b522d4c0f3987b84d7b046 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 24 Jul 2017 09:54:00 +1000 Subject: [PATCH] Rover: move mavlink reboot code up to base class --- APMrover2/GCS_Mavlink.cpp | 8 -------- 1 file changed, 8 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 491df14e7e..665dc80caf 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -676,14 +676,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) result = MAV_RESULT_ACCEPTED; 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 - hal.scheduler->reboot(is_equal(packet.param1, 3.0f)); - result = MAV_RESULT_ACCEPTED; - } - break; - case MAV_CMD_COMPONENT_ARM_DISARM: if (is_equal(packet.param1, 1.0f)) { // run pre_arm_checks and arm_checks and display failures