Copter: Return RESULT_FAILED for GET_CMD_HOME if home is unset

This commit is contained in:
Michael du Breuil 2016-09-02 21:17:42 -07:00 committed by Randy Mackay
parent 2843e266b5
commit bec4bfa2ba

View File

@ -1425,6 +1425,8 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
if (copter.ap.home_state != HOME_UNSET) {
send_home(copter.ahrs.get_home());
result = MAV_RESULT_ACCEPTED;
} else {
result = MAV_RESULT_FAILED;
}
break;