|
|
|
@ -433,6 +433,11 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
@@ -433,6 +433,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); |
|
|
|
@ -743,6 +748,7 @@ GCS_MAVLINK::data_stream_send(void)
@@ -743,6 +748,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; |
|
|
|
|