Browse Source

AP_HAL_AVR: accept a much shorted sync pulse width on RCInput

this should fix issues with OpenLRSng default settings
master
Andrew Tridgell 10 years ago
parent
commit
7fb114752c
  1. 8
      libraries/AP_HAL_AVR/RCInput.h
  2. 2
      libraries/AP_HAL_AVR/RCInput_APM1.cpp
  3. 2
      libraries/AP_HAL_AVR/RCInput_APM2.cpp

8
libraries/AP_HAL_AVR/RCInput.h

@ -8,6 +8,14 @@
#define AVR_RC_INPUT_NUM_CHANNELS 11 #define AVR_RC_INPUT_NUM_CHANNELS 11
#define AVR_RC_INPUT_MIN_CHANNELS 5 // for ppm sum we allow less than 8 channels to make up a valid packet #define AVR_RC_INPUT_MIN_CHANNELS 5 // for ppm sum we allow less than 8 channels to make up a valid packet
/*
mininum pulse width in microseconds to signal end of a PPM-SUM
frame. This value is chosen to be smaller than the default 3000 sync
pulse width for OpenLRSng. Note that this is the total pulse with
(typically 300us low followed by a long high pulse)
*/
#define AVR_RC_INPUT_MIN_SYNC_PULSE_WIDTH 2700
class AP_HAL_AVR::APM1RCInput : public AP_HAL::RCInput { class AP_HAL_AVR::APM1RCInput : public AP_HAL::RCInput {
public: public:
/** /**

2
libraries/AP_HAL_AVR/RCInput_APM1.cpp

@ -32,7 +32,7 @@ void APM1RCInput::_timer4_capt_cb(void) {
pulse_width = icr4_current - icr4_prev; pulse_width = icr4_current - icr4_prev;
} }
if (pulse_width > 8000) { if (pulse_width > AVR_RC_INPUT_MIN_SYNC_PULSE_WIDTH*2) {
// sync pulse detected. Pass through values if at least a minimum number of channels received // sync pulse detected. Pass through values if at least a minimum number of channels received
if( channel_ctr >= AVR_RC_INPUT_MIN_CHANNELS ) { if( channel_ctr >= AVR_RC_INPUT_MIN_CHANNELS ) {
_num_channels = channel_ctr; _num_channels = channel_ctr;

2
libraries/AP_HAL_AVR/RCInput_APM2.cpp

@ -32,7 +32,7 @@ void APM2RCInput::_timer5_capt_cb(void) {
pulse_width = icr5_current - icr5_prev; pulse_width = icr5_current - icr5_prev;
} }
if (pulse_width > 8000) { if (pulse_width > AVR_RC_INPUT_MIN_SYNC_PULSE_WIDTH*2) {
// sync pulse detected. Pass through values if at least a minimum number of channels received // sync pulse detected. Pass through values if at least a minimum number of channels received
if( channel_ctr >= AVR_RC_INPUT_MIN_CHANNELS ) { if( channel_ctr >= AVR_RC_INPUT_MIN_CHANNELS ) {
_num_channels = channel_ctr; _num_channels = channel_ctr;

Loading…
Cancel
Save