5 #pragma GCC optimize ("O2") 29 memset((
void *)&
_val[0], 0,
sizeof(_val));
60 #if 0 // [ statistics to tune memory usage 113 }
else if(value > 700 && value < 2300) {
143 uint16_t bits_s0 = (width_s0+4) / 10;
144 uint16_t bits_s1 = (width_s1+4) / 10;
146 uint8_t byte_ofs = state.
bit_ofs/12;
147 uint8_t bit_ofs = state.
bit_ofs%12;
150 if (bits_s1 == 0 || bits_s0 == 0) {
154 if (bits_s1+bit_ofs > 10) {
160 state.
bytes[byte_ofs] |= ((1U<<bits_s1)-1) << bit_ofs;
166 if (nlow + bit_ofs > 12) {
172 if (state.
bit_ofs == 25*12 && bits_s0 > 12) {
177 for (i=0; i<25; i++) {
179 uint16_t
v = ~state.
bytes[i];
185 if ((v & 0xC00) != 0xC00) {
189 uint8_t parity = 0, j;
190 for (j=1; j<=8; j++) {
191 parity ^= (v & (1U<<j))?1:0;
193 if (parity != (v&0x200)>>9) {
196 bytes[i] = ((v>>1) & 0xFF);
200 uint16_t num_values=0;
201 bool sbus_failsafe=
false, sbus_frame_drop=
false;
205 &sbus_failsafe, &sbus_frame_drop,
210 for (i=0; i<num_values; i++) {
218 if (!sbus_failsafe) {
224 }
else if (bits_s0 > 12) {
246 uint16_t bits_s0 = ((width_s0+4)*(uint32_t)115200) / 1000000;
247 uint16_t bits_s1 = ((width_s1+4)*(uint32_t)115200) / 1000000;
248 uint8_t bit_ofs, byte_ofs;
251 if (bits_s0 == 0 || bits_s1 == 0) {
266 if (nbits+bit_ofs > 10) {
267 nbits = 10 - bit_ofs;
274 if (bits_s0 - nbits > 10) {
279 for (i=0; i<16; i++) {
288 if ((v & 0x200) != 0x200) {
291 uint8_t bt= ((v>>1) & 0xFF);
299 uint16_t channel_count;
306 for (uint8_t j=0; j<channel_count; j++) {
307 if (values[j] != 0) {
324 uint16_t num_values=0;
330 for (i=0; i<num_values; i++) {
335 uint32_t nc=num_values+1;
350 if (bits_s1+bit_ofs > 10) {
Simple circular buffer for PEM input.
static uint64_t systick_uptime(void)
Returns the system uptime, in milliseconds.
static void pwm_setHandler(Handler handler, uint8_t ch)
int sumd_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channel_count, uint16_t *channels, uint16_t max_chan_count)
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
struct SbusState sbus_state[2]
static void putch(uint8_t c, uint8_t n)
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
bool _process_ppmsum_pulse(uint16_t value)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
bool getPPM_Pulse(Pulse *p, uint8_t ch)
bool dsm_decode(uint64_t frame_time, const uint8_t dsm_frame[16], uint16_t *values, uint16_t *num_values, uint16_t max_values)
static void do_io_completion(uint8_t id)
void _process_sbus_pulse(uint16_t width_s0, uint16_t width_s1, struct PPM_parser::SbusState &state)
volatile uint8_t _channels
volatile uint16_t _val[F4Light_RC_INPUT_NUM_CHANNELS]
volatile uint64_t _last_signal
void rxIntRC(uint16_t value0, uint16_t value1, bool state)
#define F4Light_RC_INPUT_NUM_CHANNELS
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
void _process_dsm_pulse(uint16_t width_s0, uint16_t width_s1)
enum BOARD_RC_MODE _rc_mode
struct F4Light::PPM_parser::DSM_State dsm_state
uint16_t getPPM_count(uint8_t ch)
static uint8_t register_io_completion(Handler handle)