RCInput: allow ppmsum of less than 8 channels
This commit is contained in:
parent
c067fa2660
commit
a28c6df611
@ -6,6 +6,7 @@
|
|||||||
#include "AP_HAL_AVR_Namespace.h"
|
#include "AP_HAL_AVR_Namespace.h"
|
||||||
|
|
||||||
#define AVR_RC_INPUT_NUM_CHANNELS 8
|
#define AVR_RC_INPUT_NUM_CHANNELS 8
|
||||||
|
#define AVR_RC_INPUT_MIN_CHANNELS 5 // for ppm sum we allow less than 8 channels to make up a valid packet
|
||||||
|
|
||||||
class AP_HAL_AVR::APM1RCInput : public AP_HAL::RCInput {
|
class AP_HAL_AVR::APM1RCInput : public AP_HAL::RCInput {
|
||||||
public:
|
public:
|
||||||
|
@ -32,7 +32,10 @@ void APM1RCInput::_timer4_capt_cb(void) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (pulse_width > 8000) {
|
if (pulse_width > 8000) {
|
||||||
/* sync pulse detected */
|
// sync pulse detected. Pass through values if at least a minimum number of channels received
|
||||||
|
if( channel_ctr >= AVR_RC_INPUT_MIN_CHANNELS ) {
|
||||||
|
_valid = channel_ctr;
|
||||||
|
}
|
||||||
channel_ctr = 0;
|
channel_ctr = 0;
|
||||||
} else {
|
} else {
|
||||||
if (channel_ctr < AVR_RC_INPUT_NUM_CHANNELS) {
|
if (channel_ctr < AVR_RC_INPUT_NUM_CHANNELS) {
|
||||||
|
@ -32,7 +32,10 @@ void APM2RCInput::_timer5_capt_cb(void) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (pulse_width > 8000) {
|
if (pulse_width > 8000) {
|
||||||
/* sync pulse detected */
|
// sync pulse detected. Pass through values if at least a minimum number of channels received
|
||||||
|
if( channel_ctr >= AVR_RC_INPUT_MIN_CHANNELS ) {
|
||||||
|
_valid = channel_ctr;
|
||||||
|
}
|
||||||
channel_ctr = 0;
|
channel_ctr = 0;
|
||||||
} else {
|
} else {
|
||||||
if (channel_ctr < AVR_RC_INPUT_NUM_CHANNELS) {
|
if (channel_ctr < AVR_RC_INPUT_NUM_CHANNELS) {
|
||||||
|
Loading…
Reference in New Issue
Block a user