mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_RCProtocol: added update() method for use by SITL
This commit is contained in:
parent
4b48e80c26
commit
c8de2ec9c7
@ -202,6 +202,11 @@ void AP_RCProtocol::check_added_uart(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void AP_RCProtocol::update()
|
||||||
|
{
|
||||||
|
check_added_uart();
|
||||||
|
}
|
||||||
|
|
||||||
bool AP_RCProtocol::new_input()
|
bool AP_RCProtocol::new_input()
|
||||||
{
|
{
|
||||||
bool ret = _new_input;
|
bool ret = _new_input;
|
||||||
|
@ -47,6 +47,7 @@ public:
|
|||||||
void process_pulse(uint32_t width_s0, uint32_t width_s1);
|
void process_pulse(uint32_t width_s0, uint32_t width_s1);
|
||||||
void process_pulse_list(const uint32_t *widths, uint16_t n, bool need_swap);
|
void process_pulse_list(const uint32_t *widths, uint16_t n, bool need_swap);
|
||||||
void process_byte(uint8_t byte, uint32_t baudrate);
|
void process_byte(uint8_t byte, uint32_t baudrate);
|
||||||
|
void update(void);
|
||||||
|
|
||||||
void disable_for_pulses(enum rcprotocol_t protocol) {
|
void disable_for_pulses(enum rcprotocol_t protocol) {
|
||||||
_disabled_for_pulses |= (1U<<(uint8_t)protocol);
|
_disabled_for_pulses |= (1U<<(uint8_t)protocol);
|
||||||
|
Loading…
Reference in New Issue
Block a user