Plane: return success or failure of get home position

This commit is contained in:
DonLakeFlyer 2015-12-07 11:31:11 +09:00 committed by Randy Mackay
parent a697d34b98
commit 7479bc5734
1 changed files with 4 additions and 1 deletions

View File

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