APM_RC: allow ppm sum for as few as 5 channels

This commit is contained in:
rmackay9 2012-11-16 11:07:11 +09:00
parent 47b1bc30d3
commit 01dc9fbe3e
3 changed files with 11 additions and 10 deletions

View File

@ -23,6 +23,7 @@
#define NUM_CHANNELS 8
#define MIN_CHANNELS 5 // for ppm sum we allow less than 8 channels to make up a valid packet

View File

@ -55,16 +55,16 @@ void APM_RC_APM1::_timer4_capt_cb(void)
}
if (Pulse_Width>8000) { // SYNC pulse?
// pass through values if at least a minimum number of channels received
if( PPM_Counter >= MIN_CHANNELS ) {
_radio_status = 1;
_last_update = millis();
}
PPM_Counter=0;
}
else {
if (PPM_Counter < NUM_CHANNELS) { // Valid pulse channel?
_PWM_RAW[PPM_Counter++]=Pulse_Width; // Saving pulse.
if (PPM_Counter >= NUM_CHANNELS) {
_radio_status = 1;
_last_update = millis();
}
}
}
ICR4_old = Pulse;

View File

@ -55,16 +55,16 @@ void APM_RC_APM2::_timer5_capt_cb(void)
// Was it a sync pulse? If so, reset frame.
if ( pwidth > 8000 ) {
// pass through values if at least a minimum number of channels received
if( frame_idx >= MIN_CHANNELS ) {
_radio_status = 1;
_last_update = millis();
}
frame_idx=0;
} else {
// Save pulse into _PWM_RAW array.
if ( frame_idx < NUM_CHANNELS ) {
_PWM_RAW[ frame_idx++ ] = pwidth;
// If this is the last pulse in a frame, set _radio_status.
if (frame_idx >= NUM_CHANNELS) {
_radio_status = 1;
_last_update = millis();
}
}
}
// Save icr for next call.