mirror of https://github.com/ArduPilot/ardupilot
AP_IOMCU: use AP::RC() for AP_RCProtocol
This commit is contained in:
parent
cbdb23afb5
commit
672d09c965
|
@ -305,7 +305,7 @@ void AP_IOMCU_FW::rcin_update()
|
|||
rc_input.pwm[i] = hal.rcin->read(i);
|
||||
}
|
||||
rc_last_input_ms = last_ms;
|
||||
rc_input.rc_protocol = (uint16_t)rcprotocol->protocol_detected();
|
||||
rc_input.rc_protocol = (uint16_t)AP::RC().protocol_detected();
|
||||
} else if (last_ms - rc_last_input_ms > 200U) {
|
||||
rc_input.flags_rc_ok = false;
|
||||
}
|
||||
|
|
|
@ -117,8 +117,6 @@ public:
|
|||
uint32_t sbus_last_ms;
|
||||
uint32_t sbus_interval_ms;
|
||||
|
||||
AP_RCProtocol *rcprotocol;
|
||||
|
||||
uint32_t fmu_data_received_time;
|
||||
uint32_t last_heater_ms;
|
||||
uint32_t reboot_time;
|
||||
|
|
|
@ -68,12 +68,10 @@ void AP_IOMCU_FW::rcin_serial_init(void)
|
|||
&sd3_listener,
|
||||
EVENT_MASK(1),
|
||||
SD_PARITY_ERROR);
|
||||
rcprotocol = AP_RCProtocol::get_singleton();
|
||||
|
||||
// disable input for SBUS with pulses, we will use the UART for
|
||||
// SBUS.
|
||||
rcprotocol->disable_for_pulses(AP_RCProtocol::SBUS);
|
||||
rcprotocol->disable_for_pulses(AP_RCProtocol::SBUS_NI);
|
||||
AP::RC().disable_for_pulses(AP_RCProtocol::SBUS);
|
||||
AP::RC().disable_for_pulses(AP_RCProtocol::SBUS_NI);
|
||||
}
|
||||
|
||||
static struct {
|
||||
|
@ -96,7 +94,7 @@ void AP_IOMCU_FW::rcin_serial_update(void)
|
|||
n = MIN(n, sizeof(b));
|
||||
rc_stats.num_dsm_bytes += n;
|
||||
for (uint8_t i=0; i<n; i++) {
|
||||
rcprotocol->process_byte(b[i], 115200);
|
||||
AP::RC().process_byte(b[i], 115200);
|
||||
}
|
||||
//BLUE_TOGGLE();
|
||||
}
|
||||
|
@ -111,7 +109,7 @@ void AP_IOMCU_FW::rcin_serial_update(void)
|
|||
n = MIN(n, sizeof(b));
|
||||
rc_stats.num_sbus_bytes += n;
|
||||
for (uint8_t i=0; i<n; i++) {
|
||||
rcprotocol->process_byte(b[i], 100000);
|
||||
AP::RC().process_byte(b[i], 100000);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue