mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_HAL_AVR: accept a much shorted sync pulse width on RCInput
this should fix issues with OpenLRSng default settings
This commit is contained in:
parent
f2a919c55e
commit
7fb114752c
@ -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:
|
||||||
/**
|
/**
|
||||||
|
@ -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;
|
||||||
|
@ -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…
Reference in New Issue
Block a user