HAL_Linux: make 115200 R/C decoders return a bool

This commit is contained in:
Andrew Tridgell 2016-10-14 16:22:47 +11:00
parent 710d08da6d
commit 513156a4cc
2 changed files with 27 additions and 15 deletions

View File

@ -354,12 +354,13 @@ void RCInput::_update_periods(uint16_t *periods, uint8_t len)
/*
add some bytes of input in DSM serial stream format, coping with partial packets
*/
void RCInput::add_dsm_input(const uint8_t *bytes, size_t nbytes)
bool RCInput::add_dsm_input(const uint8_t *bytes, size_t nbytes)
{
if (nbytes == 0) {
return;
return false;
}
const uint8_t dsm_frame_size = sizeof(dsm.frame);
bool ret = false;
uint32_t now = AP_HAL::millis();
if (now - dsm.last_input_ms > 5) {
@ -405,26 +406,29 @@ void RCInput::add_dsm_input(const uint8_t *bytes, size_t nbytes)
(unsigned)num_values,
values[0], values[1], values[2], values[3], values[4], values[5], values[6], values[7]);
#endif
ret = true;
}
}
}
return ret;
}
/*
add some bytes of input in SUMD serial stream format, coping with partial packets
*/
void RCInput::add_sumd_input(const uint8_t *bytes, size_t nbytes)
bool RCInput::add_sumd_input(const uint8_t *bytes, size_t nbytes)
{
uint16_t values[LINUX_RC_INPUT_NUM_CHANNELS];
uint8_t rssi;
uint8_t rx_count;
uint16_t channel_count;
bool ret = false;
while (nbytes > 0) {
if (sumd_decode(*bytes++, &rssi, &rx_count, &channel_count, values, LINUX_RC_INPUT_NUM_CHANNELS) == 0) {
if (channel_count > LINUX_RC_INPUT_NUM_CHANNELS) {
return;
continue;
}
for (uint8_t i=0; i<channel_count; i++) {
if (values[i] != 0) {
@ -433,25 +437,28 @@ void RCInput::add_sumd_input(const uint8_t *bytes, size_t nbytes)
}
_num_channels = channel_count;
new_rc_input = true;
ret = true;
}
nbytes--;
}
return ret;
}
/*
add some bytes of input in ST24 serial stream format, coping with partial packets
*/
void RCInput::add_st24_input(const uint8_t *bytes, size_t nbytes)
bool RCInput::add_st24_input(const uint8_t *bytes, size_t nbytes)
{
uint16_t values[LINUX_RC_INPUT_NUM_CHANNELS];
uint8_t rssi;
uint8_t rx_count;
uint16_t channel_count;
bool ret = false;
while (nbytes > 0) {
if (st24_decode(*bytes++, &rssi, &rx_count, &channel_count, values, LINUX_RC_INPUT_NUM_CHANNELS) == 0) {
if (channel_count > LINUX_RC_INPUT_NUM_CHANNELS) {
return;
continue;
}
for (uint8_t i=0; i<channel_count; i++) {
if (values[i] != 0) {
@ -460,33 +467,38 @@ void RCInput::add_st24_input(const uint8_t *bytes, size_t nbytes)
}
_num_channels = channel_count;
new_rc_input = true;
ret = true;
}
nbytes--;
}
return ret;
}
/*
add some bytes of input in SRXL serial stream format, coping with partial packets
*/
void RCInput::add_srxl_input(const uint8_t *bytes, size_t nbytes)
bool RCInput::add_srxl_input(const uint8_t *bytes, size_t nbytes)
{
uint16_t values[LINUX_RC_INPUT_NUM_CHANNELS];
uint8_t channel_count;
uint64_t now = AP_HAL::micros64();
bool ret = false;
while (nbytes > 0) {
if (srxl_decode(now, *bytes++, &channel_count, values, LINUX_RC_INPUT_NUM_CHANNELS) == 0) {
if (channel_count > LINUX_RC_INPUT_NUM_CHANNELS) {
return;
continue;
}
for (uint8_t i=0; i<channel_count; i++) {
_pwm_values[i] = values[i];
}
_num_channels = channel_count;
new_rc_input = true;
ret = true;
}
nbytes--;
}
return ret;
}

View File

@ -29,19 +29,19 @@ public:
virtual void _timer_tick() {}
// add some DSM input bytes, for RCInput over a serial port
void add_dsm_input(const uint8_t *bytes, size_t nbytes);
bool add_dsm_input(const uint8_t *bytes, size_t nbytes);
// add some SBUS input bytes, for RCInput over a serial port
void add_sbus_input(const uint8_t *bytes, size_t nbytes);
// add some SUMD input bytes, for RCInput over a serial port
void add_sumd_input(const uint8_t *bytes, size_t nbytes);
bool add_sumd_input(const uint8_t *bytes, size_t nbytes);
// add some st24 input bytes, for RCInput over a serial port
void add_st24_input(const uint8_t *bytes, size_t nbytes);
bool add_st24_input(const uint8_t *bytes, size_t nbytes);
// add some srxl input bytes, for RCInput over a serial port
void add_srxl_input(const uint8_t *bytes, size_t nbytes);
bool add_srxl_input(const uint8_t *bytes, size_t nbytes);
protected:
void _process_rc_pulse(uint16_t width_s0, uint16_t width_s1);