ArduPPM: Redundancy mode

Fixed logic problem in the decoder (PPM channel increment)
This commit is contained in:
Olivier ADLER 2012-10-27 23:37:44 +02:00
parent 9c40c11e7b
commit 34151cbe91

View File

@ -13,6 +13,8 @@
// This mode Can be used as well if a PPM conversion is needed (Futaba 16 channels 760us mode to APM mode)
// -------------------------------------------------------------
// Not for production - Work in progress
#ifndef _PPM_ENCODER_H_
#define _PPM_ENCODER_H_
@ -641,10 +643,6 @@ ISR( SERVO_INT_VECTOR )
static bool sync_ch1 = false;
static bool sync_ch2 = false;
// Last channels flags
static bool last_channel_ch1 = false;
static bool last_channel_ch2 = false;
// Channel error flags
static bool channel_error_ch1 = true;
static bool channel_error_ch2 = true;
@ -685,7 +683,7 @@ ISR( SERVO_INT_VECTOR )
// PPM redundancy - decoder
// -----------------------------------
CHECK_START: // Start of PPM inputs check
CHECK_START: // Start of PPM inputs check
// Store current PPM inputs pins
servo_pins = SERVO_INPUT;
@ -697,7 +695,7 @@ CHECK_START: // Start of PPM inputs check
// PPM redundancy - Ch1 decoding
// -----------------------------------
CHECK_LOOP: // Input PPM pins check loop
CHECK_LOOP: // Input PPM pins check loop
// Check if we have a pin change on PPM channel 1
if( servo_change & 1 )
@ -711,6 +709,17 @@ CHECK_LOOP: // Input PPM pins check loop
if ( true ) //Todo optionnal: We could add a test here for channel pre pulse lenght check
{
//We have a valid pre pulse
if( ppm1_channel == channel_count_ch1 ) // Check for last channel
{
// We are at latest PPM channel
sync_ch1 = false; // Reset sync flag
ppm1_channel = 0; // Reset PPM channel counter
}
else // We do not have yet reached the last channel
{
// Increment channel counter
ppm1_channel++;
}
}
else
{
@ -718,7 +727,6 @@ CHECK_LOOP: // Input PPM pins check loop
sync_error_ch1 = true; // Set sync error flag
sync_ch1 = false; // Reset sync flag
ppm1_channel = 0; // Reset PPM channel counter
last_channel_ch1 = false; // Reset last channel flag
}
ppm1_start[ ppm1_channel ] = servo_time; // Store pulse start time for PPM1 input
}
@ -733,26 +741,13 @@ CHECK_LOOP: // Input PPM pins check loop
{
// Reset channel error flag
channel_error_ch1 = false;
if( ppm1_channel == channel_count_ch1 ) // Check for last channel
{
// We are at latest PPM channel
last_channel_ch1 = true; // Set last channel flag
sync_ch1 = false; // Reset sync flag
ppm1_channel = 0; // Reset PPM channel counter
}
else // We do not have yet reached the last channel
{
// Increment channel counter
ppm1_channel++;
}
}
else // We do not have a valid channel lenght
{
if( ppm1_width[ ppm1_channel ] > PPM_CH1_MIN_SYNC_LENGHT ) || ( ppm1_width[ ppm1_channel ] < PPM_CH1_MAX_SYNC_LENGHT ) //Check for sync symbol
{
// We have a valid sync symbol
if( channel_count_detected_ch1 == false ) // Check if do not have yet channel count detected
if( channel_count_detected_ch1 == false ) // Check if we do not have yet channel count detected
{
// We have detected channels count
channel_count_ch1 = ppm1_channel; // Store PPM1 channel count
@ -760,17 +755,14 @@ CHECK_LOOP: // Input PPM pins check loop
sync_error_ch1 = false; // Reset sync error flag
sync_ch1 = true; // Set sync flag
ppm1_channel = 0; // Reset PPM channel counter
last_channel_ch1 = false; // Reset last channel flag
}
else // Channel count had been detected before
{
//We should not have a sync symbol here
sync_error_ch1 = true; // Set sync error flag
last_channel_ch1 = false; // Reset last channel flag
sync_ch1 = false; // Reset sync flag
ppm1_channel = 0; // Reset PPM channel counter
}
ppm1_channel = 0; // Reset PPM channel counter
}
else // We do not have a valid sync symbol
{
@ -794,7 +786,6 @@ CHECK_LOOP: // Input PPM pins check loop
sync_ch1 = false; // Reset sync flag
}
ppm1_channel = 0; // Reset PPM channel counter
last_channel_ch1 = false; // Reset last channel flag
}
}
ppm1_prepulse_start = servo_time; // Store prepulse start time
@ -817,6 +808,17 @@ CHECK_LOOP: // Input PPM pins check loop
if ( true ) //Todo optionnal: We could add a test here for channel pre pulse lenght check
{
//We have a valid pre pulse
if( ppm2_channel == channel_count_ch2 ) // Check for last channel
{
// We are at latest PPM channel
sync_ch2 = false; // Reset sync flag
ppm2_channel = 0; // Reset PPM channel counter
}
else // We do not have yet reached the last channel
{
// Increment channel counter
ppm2_channel++;
}
}
else
{
@ -824,7 +826,6 @@ CHECK_LOOP: // Input PPM pins check loop
sync_error_ch2 = true; // Set sync error flag
sync_ch2 = false; // Reset sync flag
ppm2_channel = 0; // Reset PPM channel counter
last_channel_ch2 = false; // Reset last channel flag
}
ppm2_start[ ppm2_channel ] = servo_time; // Store pulse start time for PPM2 input
}
@ -839,26 +840,13 @@ CHECK_LOOP: // Input PPM pins check loop
{
// Reset channel error flag
channel_error_ch2 = false;
if( ppm2_channel == channel_count_ch2 ) // Check for last channel
{
// We are at latest PPM channel
last_channel_ch2 = true; // Set last channel flag
sync_ch2 = false; // Reset sync flag
ppm2_channel = 0; // Reset PPM channel counter
}
else // We do not have yet reached the last channel
{
// Increment channel counter
ppm2_channel++;
}
}
else // We do not have a valid channel lenght
{
if( ppm2_width[ ppm2_channel ] > PPM_CH2_MIN_SYNC_LENGHT ) || ( ppm2_width[ ppm2_channel ] < PPM_CH2_MAX_SYNC_LENGHT ) //Check for sync symbol
{
// We have a valid sync symbol
if( channel_count_detected_ch2 == false ) // Check if do not have yet channel count detected
if( channel_count_detected_ch2 == false ) // Check if we do not have yet channel count detected
{
// We have detected channels count
channel_count_ch2 = ppm2_channel; // Store PPM2 channel count
@ -866,17 +854,14 @@ CHECK_LOOP: // Input PPM pins check loop
sync_error_ch2 = false; // Reset sync error flag
sync_ch2 = true; // Set sync flag
ppm2_channel = 0; // Reset PPM channel counter
last_channel_ch2 = false; // Reset last channel flag
}
else // Channel count had been detected before
{
//We should not have a sync symbol here
sync_error_ch2 = true; // Set sync error flag
last_channel_ch2 = false; // Reset last channel flag
sync_ch2 = false; // Reset sync flag
ppm2_channel = 0; // Reset PPM channel counter
}
ppm2_channel = 0; // Reset PPM channel counter
}
else // We do not have a valid sync symbol
{
@ -900,7 +885,6 @@ CHECK_LOOP: // Input PPM pins check loop
sync_ch2 = false; // Reset sync flag
}
ppm2_channel = 0; // Reset PPM channel counter
last_channel_ch2 = false; // Reset last channel flag
}
}
ppm2_prepulse_start = servo_time; // Store prepulse start time
@ -1051,7 +1035,7 @@ CHECK_LOOP: // Input PPM pins check loop
//Reset throttle failsafe timeout
if( ppm1_channel == 5 ) throttle_timeout = 0;
CHECK_ERROR:
CHECK_ERROR:
#if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__)
// Delay LED toggle
@ -1060,7 +1044,7 @@ CHECK_ERROR:
*/
CHECK_DONE:
CHECK_DONE:
// Reset Watchdog Timer
wdt_reset();
@ -1105,7 +1089,6 @@ CHECK_DONE:
// Leave interrupt
return;
}
// -------------------------
// PPM redundancy mode END