From f1f8233220e336598f4148955e259c4121dfb2fb Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Fri, 2 Sep 2016 21:18:28 -0700 Subject: [PATCH] Rover: Return RESULT_FAILED for GET_CMD_HOME if home is unset --- APMrover2/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 48f308d6b7..3ffdaaf346 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -1105,6 +1105,8 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) if (rover.home_is_set != HOME_UNSET) { send_home(rover.ahrs.get_home()); result = MAV_RESULT_ACCEPTED; + } else { + result = MAV_RESULT_FAILED; } break;