Plane: added LOCAL_POSITION_NED message

This commit is contained in:
Andrew Tridgell 2015-04-05 09:25:41 -07:00
parent 4b5a36cc3f
commit 36796fb810

View File

@ -560,6 +560,11 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
send_location(chan);
break;
case MSG_LOCAL_POSITION:
CHECK_PAYLOAD_SIZE(LOCAL_POSITION_NED);
send_local_position(ahrs);
break;
case MSG_NAV_CONTROLLER_OUTPUT:
if (control_mode != MANUAL) {
CHECK_PAYLOAD_SIZE(NAV_CONTROLLER_OUTPUT);
@ -901,6 +906,7 @@ GCS_MAVLINK::data_stream_send(void)
if (stream_trigger(STREAM_POSITION)) {
// sent with GPS read
send_message(MSG_LOCATION);
send_message(MSG_LOCAL_POSITION);
}
if (gcs_out_of_time) return;