From 7479bc57344935b760b81a142aa4145b583abbee Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Mon, 7 Dec 2015 11:31:11 +0900 Subject: [PATCH] Plane: return success or failure of get home position --- ArduPlane/GCS_Mavlink.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 9659a71449..94f3b96b13 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1305,7 +1305,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; case MAV_CMD_GET_HOME_POSITION: - send_home(plane.ahrs.get_home()); + if (plane.home_is_set != HOME_UNSET) { + send_home(plane.ahrs.get_home()); + result = MAV_RESULT_ACCEPTED; + } break; case MAV_CMD_DO_SET_MODE: