From edcfa7ffd4da78d14b694ecf587fda1298888345 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 16 Mar 2018 15:12:41 +1100 Subject: [PATCH] Copter: move handling of get_home_position up --- ArduCopter/GCS_Mavlink.cpp | 13 ------------- 1 file changed, 13 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index d96c6e2d0f..257689f951 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1125,19 +1125,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) } break; - case MAV_CMD_GET_HOME_POSITION: - if (AP::ahrs().home_is_set()) { - send_home(copter.ahrs.get_home()); - Location ekf_origin; - if (copter.ahrs.get_origin(ekf_origin)) { - send_ekf_origin(ekf_origin); - } - result = MAV_RESULT_ACCEPTED; - } else { - result = MAV_RESULT_FAILED; - } - break; - case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN: if (is_equal(packet.param1,1.0f) || is_equal(packet.param1,3.0f)) { AP_Notify::flags.firmware_update = 1;