Copter: return success or failure of get home position

This commit is contained in:
DonLakeFlyer 2015-12-07 11:29:49 +09:00 committed by Randy Mackay
parent 78e9b0a4e3
commit c8cc83505b

View File

@ -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: