Plane: move handling of get_home_position up

This commit is contained in:
Peter Barker 2018-03-16 15:02:43 +11:00 committed by Randy Mackay
parent bb7bed0614
commit 5572d83ce9

View File

@ -1193,19 +1193,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
}
break;
case MAV_CMD_GET_HOME_POSITION:
if (AP::ahrs().home_is_set()) {
send_home(plane.ahrs.get_home());
Location ekf_origin;
if (plane.ahrs.get_origin(ekf_origin)) {
send_ekf_origin(ekf_origin);
}
result = MAV_RESULT_ACCEPTED;
} else {
result = MAV_RESULT_FAILED;
}
break;
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
result = handle_preflight_reboot(packet, plane.quadplane.enable != 0);
break;