1 #include "AP_RCProtocol_config.h"
3 #if AP_RCPROTOCOL_RADIO_ENABLED
5 #include "AP_RCProtocol_Radio.h"
6 #include <AP_Radio/AP_Radio.h>
8 void AP_RCProtocol_Radio::update()
10 auto *radio
= AP_Radio::get_singleton();
11 if (radio
== nullptr) {
19 // allow the radio to handle mavlink on the main thread:
22 const uint32_t last_recv_us
= radio
->last_recv_us();
23 if (last_recv_us
== last_input_us
) {
27 last_input_us
= last_recv_us
;
29 const auto num_channels
= radio
->num_channels();
30 uint16_t rcin_values
[MAX_RCIN_CHANNELS
];
31 for (uint8_t i
=0; i
<num_channels
; i
++) {
32 rcin_values
[i
] = radio
->read(i
);
44 void AP_RCProtocol_Radio::start_bind()
46 auto *radio
= AP_Radio::get_singleton();
47 if (radio
== nullptr) {
50 radio
->start_recv_bind();
53 #endif // AP_RCPROTOCOL_RADIO_ENABLED