From c8cc83505b40eefa3b4d6a91e145d837c2a399e3 Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Mon, 7 Dec 2015 11:29:49 +0900 Subject: [PATCH] Copter: return success or failure of get home position --- ArduCopter/GCS_Mavlink.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 9107da307e..0ddf4fae72 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1387,7 +1387,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; case MAV_CMD_GET_HOME_POSITION: - send_home(copter.ahrs.get_home()); + if (copter.ap.home_state != HOME_UNSET) { + send_home(copter.ahrs.get_home()); + result = MAV_RESULT_ACCEPTED; + } break; case MAV_CMD_DO_SET_SERVO: