mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: use rc() method to get rc singleton
This commit is contained in:
parent
f4c93dc697
commit
dbccd6a399
@ -1002,8 +1002,8 @@ void GCS_MAVLINK::send_radio_in()
|
||||
uint32_t now = AP_HAL::millis();
|
||||
mavlink_status_t *status = mavlink_get_channel_status(chan);
|
||||
|
||||
uint16_t values[18];
|
||||
RC_Channels::get_radio_in(values, 18);
|
||||
uint16_t values[18] = {};
|
||||
rc().get_radio_in(values, 18);
|
||||
|
||||
if (status && (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) {
|
||||
// for mavlink1 send RC_CHANNELS_RAW, for compatibility with OSD implementations
|
||||
|
Loading…
Reference in New Issue
Block a user