HAL_Linux: fixed a bug in RCInput::new_input
when a library called read() it would clear the new input flag, which would cause new_input() in the main loop to return false. This could trigger a false RC failsafe.
This commit is contained in:
parent
9b7f0f7957
commit
0a18f5e7b2
@ -25,8 +25,7 @@ extern const AP_HAL::HAL& hal;
|
|||||||
|
|
||||||
using namespace Linux;
|
using namespace Linux;
|
||||||
|
|
||||||
RCInput::RCInput() :
|
RCInput::RCInput()
|
||||||
new_rc_input(false)
|
|
||||||
{
|
{
|
||||||
ppm_state._channel_counter = -1;
|
ppm_state._channel_counter = -1;
|
||||||
}
|
}
|
||||||
@ -37,7 +36,11 @@ void RCInput::init()
|
|||||||
|
|
||||||
bool RCInput::new_input()
|
bool RCInput::new_input()
|
||||||
{
|
{
|
||||||
return new_rc_input;
|
bool ret = rc_input_count != last_rc_input_count;
|
||||||
|
if (ret) {
|
||||||
|
last_rc_input_count = rc_input_count;
|
||||||
|
}
|
||||||
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t RCInput::num_channels()
|
uint8_t RCInput::num_channels()
|
||||||
@ -47,7 +50,6 @@ uint8_t RCInput::num_channels()
|
|||||||
|
|
||||||
uint16_t RCInput::read(uint8_t ch)
|
uint16_t RCInput::read(uint8_t ch)
|
||||||
{
|
{
|
||||||
new_rc_input = false;
|
|
||||||
if (_override[ch]) {
|
if (_override[ch]) {
|
||||||
return _override[ch];
|
return _override[ch];
|
||||||
}
|
}
|
||||||
@ -84,7 +86,7 @@ bool RCInput::set_override(uint8_t channel, int16_t override)
|
|||||||
if (channel < LINUX_RC_INPUT_NUM_CHANNELS) {
|
if (channel < LINUX_RC_INPUT_NUM_CHANNELS) {
|
||||||
_override[channel] = override;
|
_override[channel] = override;
|
||||||
if (override != 0) {
|
if (override != 0) {
|
||||||
new_rc_input = true;
|
rc_input_count++;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -112,7 +114,7 @@ void RCInput::_process_ppmsum_pulse(uint16_t width_usec)
|
|||||||
_pwm_values[i] = ppm_state._pulse_capt[i];
|
_pwm_values[i] = ppm_state._pulse_capt[i];
|
||||||
}
|
}
|
||||||
_num_channels = ppm_state._channel_counter;
|
_num_channels = ppm_state._channel_counter;
|
||||||
new_rc_input = true;
|
rc_input_count++;
|
||||||
}
|
}
|
||||||
ppm_state._channel_counter = 0;
|
ppm_state._channel_counter = 0;
|
||||||
return;
|
return;
|
||||||
@ -143,7 +145,7 @@ void RCInput::_process_ppmsum_pulse(uint16_t width_usec)
|
|||||||
_pwm_values[i] = ppm_state._pulse_capt[i];
|
_pwm_values[i] = ppm_state._pulse_capt[i];
|
||||||
}
|
}
|
||||||
_num_channels = ppm_state._channel_counter;
|
_num_channels = ppm_state._channel_counter;
|
||||||
new_rc_input = true;
|
rc_input_count++;
|
||||||
ppm_state._channel_counter = -1;
|
ppm_state._channel_counter = -1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -221,7 +223,7 @@ void RCInput::_process_sbus_pulse(uint16_t width_s0, uint16_t width_s1)
|
|||||||
}
|
}
|
||||||
_num_channels = num_values;
|
_num_channels = num_values;
|
||||||
if (!sbus_failsafe) {
|
if (!sbus_failsafe) {
|
||||||
new_rc_input = true;
|
rc_input_count++;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
goto reset;
|
goto reset;
|
||||||
@ -291,7 +293,7 @@ void RCInput::_process_dsm_pulse(uint16_t width_s0, uint16_t width_s1)
|
|||||||
_pwm_values[i] = values[i];
|
_pwm_values[i] = values[i];
|
||||||
}
|
}
|
||||||
_num_channels = num_values;
|
_num_channels = num_values;
|
||||||
new_rc_input = true;
|
rc_input_count++;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
memset(&dsm_state, 0, sizeof(dsm_state));
|
memset(&dsm_state, 0, sizeof(dsm_state));
|
||||||
@ -349,7 +351,7 @@ void RCInput::_update_periods(uint16_t *periods, uint8_t len)
|
|||||||
_pwm_values[i] = periods[i];
|
_pwm_values[i] = periods[i];
|
||||||
}
|
}
|
||||||
_num_channels = len;
|
_num_channels = len;
|
||||||
new_rc_input = true;
|
rc_input_count++;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -408,7 +410,7 @@ bool RCInput::add_dsm_input(const uint8_t *bytes, size_t nbytes)
|
|||||||
if (num_values > _num_channels) {
|
if (num_values > _num_channels) {
|
||||||
_num_channels = num_values;
|
_num_channels = num_values;
|
||||||
}
|
}
|
||||||
new_rc_input = true;
|
rc_input_count++;
|
||||||
#if 0
|
#if 0
|
||||||
printf("Decoded DSM %u channels %u %u %u %u %u %u %u %u\n",
|
printf("Decoded DSM %u channels %u %u %u %u %u %u %u %u\n",
|
||||||
(unsigned)num_values,
|
(unsigned)num_values,
|
||||||
@ -444,7 +446,7 @@ bool RCInput::add_sumd_input(const uint8_t *bytes, size_t nbytes)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
_num_channels = channel_count;
|
_num_channels = channel_count;
|
||||||
new_rc_input = true;
|
rc_input_count++;
|
||||||
ret = true;
|
ret = true;
|
||||||
}
|
}
|
||||||
nbytes--;
|
nbytes--;
|
||||||
@ -474,7 +476,7 @@ bool RCInput::add_st24_input(const uint8_t *bytes, size_t nbytes)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
_num_channels = channel_count;
|
_num_channels = channel_count;
|
||||||
new_rc_input = true;
|
rc_input_count++;
|
||||||
ret = true;
|
ret = true;
|
||||||
}
|
}
|
||||||
nbytes--;
|
nbytes--;
|
||||||
@ -503,7 +505,7 @@ bool RCInput::add_srxl_input(const uint8_t *bytes, size_t nbytes)
|
|||||||
}
|
}
|
||||||
_num_channels = channel_count;
|
_num_channels = channel_count;
|
||||||
if (failsafe_state == false) {
|
if (failsafe_state == false) {
|
||||||
new_rc_input = true;
|
rc_input_count++;
|
||||||
}
|
}
|
||||||
ret = true;
|
ret = true;
|
||||||
}
|
}
|
||||||
@ -564,7 +566,7 @@ void RCInput::add_sbus_input(const uint8_t *bytes, size_t nbytes)
|
|||||||
_num_channels = num_values;
|
_num_channels = num_values;
|
||||||
}
|
}
|
||||||
if (!sbus_failsafe) {
|
if (!sbus_failsafe) {
|
||||||
new_rc_input = true;
|
rc_input_count++;
|
||||||
}
|
}
|
||||||
#if 0
|
#if 0
|
||||||
printf("Decoded SBUS %u channels %u %u %u %u %u %u %u %u %s\n",
|
printf("Decoded SBUS %u channels %u %u %u %u %u %u %u %u %s\n",
|
||||||
|
@ -47,7 +47,8 @@ protected:
|
|||||||
void _process_rc_pulse(uint16_t width_s0, uint16_t width_s1);
|
void _process_rc_pulse(uint16_t width_s0, uint16_t width_s1);
|
||||||
void _update_periods(uint16_t *periods, uint8_t len);
|
void _update_periods(uint16_t *periods, uint8_t len);
|
||||||
|
|
||||||
volatile bool new_rc_input;
|
volatile uint32_t rc_input_count;
|
||||||
|
uint32_t last_rc_input_count;
|
||||||
|
|
||||||
uint16_t _pwm_values[LINUX_RC_INPUT_NUM_CHANNELS];
|
uint16_t _pwm_values[LINUX_RC_INPUT_NUM_CHANNELS];
|
||||||
uint8_t _num_channels;
|
uint8_t _num_channels;
|
||||||
|
@ -58,7 +58,7 @@ void RCInput_Multi::_timer_tick(void)
|
|||||||
if (inputs[i]->new_input()) {
|
if (inputs[i]->new_input()) {
|
||||||
inputs[i]->read(_pwm_values, inputs[i]->num_channels());
|
inputs[i]->read(_pwm_values, inputs[i]->num_channels());
|
||||||
_num_channels = inputs[i]->num_channels();
|
_num_channels = inputs[i]->num_channels();
|
||||||
new_rc_input = true;
|
rc_input_count++;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user