mirror of https://github.com/ArduPilot/ardupilot
Tracker: send RADIO_IN msg to GCS
This commit is contained in:
parent
1b7ca684ee
commit
4f5f253656
|
@ -193,6 +193,11 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
|||
gcs[chan-MAVLINK_COMM_0].send_gps_raw(gps);
|
||||
break;
|
||||
|
||||
case MSG_RADIO_IN:
|
||||
CHECK_PAYLOAD_SIZE(RC_CHANNELS_RAW);
|
||||
gcs[chan-MAVLINK_COMM_0].send_radio_in(0);
|
||||
break;
|
||||
|
||||
case MSG_RADIO_OUT:
|
||||
CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW);
|
||||
send_radio_out(chan);
|
||||
|
@ -249,7 +254,6 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
|||
case MSG_RETRY_DEFERRED:
|
||||
case MSG_CURRENT_WAYPOINT:
|
||||
case MSG_VFR_HUD:
|
||||
case MSG_RADIO_IN:
|
||||
case MSG_SYSTEM_TIME:
|
||||
case MSG_LIMITS_STATUS:
|
||||
case MSG_FENCE_STATUS:
|
||||
|
@ -418,6 +422,7 @@ GCS_MAVLINK::data_stream_send(void)
|
|||
}
|
||||
|
||||
if (stream_trigger(STREAM_RC_CHANNELS)) {
|
||||
send_message(MSG_RADIO_IN);
|
||||
send_message(MSG_RADIO_OUT);
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue