mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: send RC_CHANNELS_RAW if using MAVLink1
this fixes issue #5010
This commit is contained in:
parent
350ed20460
commit
a847520da8
|
@ -1102,11 +1102,32 @@ void GCS_MAVLINK::send_system_time(AP_GPS &gps)
|
|||
void GCS_MAVLINK::send_radio_in(uint8_t receiver_rssi)
|
||||
{
|
||||
uint32_t now = AP_HAL::millis();
|
||||
mavlink_status_t *status = mavlink_get_channel_status(chan);
|
||||
|
||||
uint16_t values[18];
|
||||
memset(values, 0, sizeof(values));
|
||||
hal.rcin->read(values, 18);
|
||||
|
||||
if (status && (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) {
|
||||
// for mavlink1 send RC_CHANNELS_RAW, for compatibility with OSD implementations
|
||||
mavlink_msg_rc_channels_raw_send(
|
||||
chan,
|
||||
now,
|
||||
0,
|
||||
values[0],
|
||||
values[1],
|
||||
values[2],
|
||||
values[3],
|
||||
values[4],
|
||||
values[5],
|
||||
values[6],
|
||||
values[7],
|
||||
receiver_rssi);
|
||||
if (!HAVE_PAYLOAD_SPACE(chan, RC_CHANNELS)) {
|
||||
// can't fit RC_CHANNELS
|
||||
return;
|
||||
}
|
||||
}
|
||||
mavlink_msg_rc_channels_send(
|
||||
chan,
|
||||
now,
|
||||
|
|
Loading…
Reference in New Issue