5 #pragma GCC optimize ("O2")    10 #ifdef BOARD_SBUS_UART    32     memset((
void *)&
_val[0],    0, 
sizeof(_val));
    33     memset((
void *)&
sbus,       0, 
sizeof(sbus));
    45         if(hal_param_helper->_uart_sbus) {
    46 #ifdef BOARD_SBUS_INVERTER    62             } 
else printf(
"\nWrong HAL_SBUS_UART selected!");
    80         const uint8_t frame_size = 
sizeof(sbus.frame);
    84         if (now - sbus.last_input_uS > 5000) { 
    86             sbus.partial_frame_count = 0;
    88         sbus.last_input_uS = now;
    90         if (sbus.partial_frame_count + 1 > frame_size) {
    96         sbus.partial_frame_count += 1;
    98     if (sbus.partial_frame_count == frame_size) {
    99             sbus.partial_frame_count = 0;
   100             uint16_t values[18] {};
   101             uint16_t num_values=0;
   102             bool sbus_failsafe=
false, sbus_frame_drop=
false;    
   105                         &sbus_failsafe, &sbus_frame_drop,
   110                 for (uint8_t i=0; i<num_values; i++) {
   116                 if (!sbus_failsafe) {
   121             sbus.partial_frame_count = 0; 
 int printf(const char *fmt,...)
 
static UARTDriver * uartSDriver
 
static void _pinMode(uint8_t pin, uint8_t output)
 
#define BOARD_SBUS_INVERTER
 
Simple circular buffer for PEM input. 
 
static void _write(uint8_t pin, uint8_t value)
 
static uint64_t systick_uptime(void)
Returns the system uptime, in milliseconds. 
 
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- 
 
void setCallback(Handler cb)
 
const usart_dev *const UARTS[]
 
struct F4Light::SBUS_parser::SBUS sbus
 
void late_init(uint8_t ch)
 
bool sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values)
 
#define F4Light_RC_INPUT_MIN_CHANNELS
 
static void do_io_completion(uint8_t id)
 
uint32_t available() override
 
volatile uint8_t _channels
 
static uint32_t _micros()
 
volatile uint16_t _val[F4Light_RC_INPUT_NUM_CHANNELS]
 
volatile uint64_t _last_signal
 
#define F4Light_RC_INPUT_NUM_CHANNELS
 
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
 
static uint8_t register_io_completion(Handler handle)