mirror of https://github.com/ArduPilot/ardupilot
AntennaTracker: added LOCAL_POSITION message
This commit is contained in:
parent
5284211c96
commit
2f8764d31a
|
@ -183,6 +183,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:
|
||||
CHECK_PAYLOAD_SIZE(NAV_CONTROLLER_OUTPUT);
|
||||
send_nav_controller_output(chan);
|
||||
|
@ -422,6 +427,7 @@ GCS_MAVLINK::data_stream_send(void)
|
|||
|
||||
if (stream_trigger(STREAM_POSITION)) {
|
||||
send_message(MSG_LOCATION);
|
||||
send_message(MSG_LOCAL_POSITION);
|
||||
}
|
||||
|
||||
if (stream_trigger(STREAM_RAW_CONTROLLER)) {
|
||||
|
|
Loading…
Reference in New Issue