From 71b2c3e13da8b9416259a16cdc24d640348dec76 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 10 Jan 2013 17:45:26 -0800 Subject: [PATCH] ArduPPM: throttle failsafe is now triggered on single channel loss but recovery from the throttle low is possible --- Tools/ArduPPM/ATMega328p/Encoder-PPM.c | 12 ++++--- Tools/ArduPPM/Libraries/PPM_Encoder.h | 45 ++++++++++++++++++++++++-- 2 files changed, 49 insertions(+), 8 deletions(-) diff --git a/Tools/ArduPPM/ATMega328p/Encoder-PPM.c b/Tools/ArduPPM/ATMega328p/Encoder-PPM.c index 3b7eb5f81b..32752d880e 100644 --- a/Tools/ArduPPM/ATMega328p/Encoder-PPM.c +++ b/Tools/ArduPPM/ATMega328p/Encoder-PPM.c @@ -35,11 +35,12 @@ // 0.9.85 : Added brownout reset detection flag // 0.9.86 : Added a #define to disable Radio Passthrough mode (hardware failsafe for Arduplane) // 0.9.87 : #define correction for radio passthrough (was screwed up). +// 0.9.88 : LED fail-safe indication is on whenever throttle is low // ------------------------------------------------------------------------------------------------------------------------------------------------------------ // PREPROCESSOR DIRECTIVES // ------------------------------------------------------------------------------------------------------------------------------------------------------------ -#include "..\Libraries\PPM_Encoder.h" +#include "../Libraries/PPM_Encoder.h" #include @@ -47,7 +48,7 @@ #define ERROR_DETECTION_WINDOW 3000 * LOOP_TIMER_10MS // Detection window for error detection (default to 30s) #define ERROR_CONDITION_DELAY 500 * LOOP_TIMER_10MS // Servo error condition LED delay (LED blinking duration) -#define PASSTHROUGH_MODE_ENABLED // Comment this line to remove CH8 radio passthrough mode support (hardware failsafe for Arduplane) +//#define PASSTHROUGH_MODE_ENABLED // Comment this line to remove CH8 radio passthrough mode support (hardware failsafe for Arduplane) #define PASSTHROUGH_CHANNEL 8 * 2 // Channel for passthrough mode selection #define PASSTHROUGH_CHANNEL_OFF_US ONE_US * 1600 - PPM_PRE_PULSE // Passthrough off threshold #define PASSTHROUGH_CHANNEL_ON_US ONE_US * 1800 - PPM_PRE_PULSE // Passthrough on threshold @@ -283,7 +284,7 @@ int main(void) // ------------------------------------------------------------------------------ while( 1 ) { - if ( servo_error_condition || servo_input_missing ) // We have an error + if ( throttle_failsafe_force ) // We have an error { blink_led ( 6 * LOOP_TIMER_10MS ); // Status LED very fast blink if invalid servo input or missing signal } @@ -368,7 +369,8 @@ int main(void) // ------------------------------------------------------------------------------ // Status LED control // ------------------------------------------------------------------------------ - if ( servo_error_condition || servo_input_missing ) // We have an error + + if ( throttle_failsafe_force ) // We have an error { blink_led ( 6 * LOOP_TIMER_10MS ); // Status LED very fast blink if invalid servo input or missing signal } @@ -454,7 +456,7 @@ int main(void) // Status LED control // ------------------------------------------------------------------------------ - if ( servo_input_missing ) // We have an error + if ( throttle_failsafe_force ) // We have an error { blink_led ( 6 * LOOP_TIMER_10MS ); // Status LED very fast blink if invalid servo input or missing signal } diff --git a/Tools/ArduPPM/Libraries/PPM_Encoder.h b/Tools/ArduPPM/Libraries/PPM_Encoder.h index 5e1dbd313e..f15c8537b6 100644 --- a/Tools/ArduPPM/Libraries/PPM_Encoder.h +++ b/Tools/ArduPPM/Libraries/PPM_Encoder.h @@ -1,5 +1,5 @@ // ------------------------------------------------------------- -// ArduPPM (PPM Encoder) V2.3.13 +// ArduPPM (PPM Encoder) V2.3.14pre // ------------------------------------------------------------- // Improved servo to ppm for ArduPilot MEGA v1.x (ATmega328p), // PhoneDrone and APM2.x (ATmega32u2) @@ -127,6 +127,12 @@ // V2.3.13 - Official release // - Fail-safe vales changed back to normal fail-safe values. Use until APM code knows how to handle lost channel signal (800us) +// 16-12-2012 +// V2.3.14pre - Internal test release +// - If one or more or all channel(s) are disconnected, throttle is set to fail-safe low (RTL) +// - If the misssing channel(s) are regained, throttle control is regained + + // ------------------------------------------------------------- #ifndef _PPM_ENCODER_H_ @@ -168,7 +174,7 @@ #endif // Version stamp for firmware hex file ( decode hex file using and look for "ArduPPM" string ) -const char ver[15] = "ArduPPMv2.3.13"; +const char ver[15] = "ArduPPMv2.3.14pre"; // ------------------------------------------------------------- // INPUT MODE @@ -322,6 +328,9 @@ volatile uint8_t ppm_timeout[ PPM_ARRAY_MAX ]; #define SERVO_INPUT_CONNECTED_VALUE 100 volatile uint8_t servo_input_connected[ PPM_ARRAY_MAX ]; +// count the channels which have been once connected but then got disconnected +volatile uint8_t disconnected_channels; + // AVR parameters for PhoneDrone and APM2 boards using ATmega32u2 #if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__) @@ -413,6 +422,8 @@ volatile bool ppm_generator_active = false; // Used to indicate a brownout restart volatile bool brownout_reset = false; +// Used to force throttle fail-safe mode (RTL) +volatile bool throttle_failsafe_force = false; // ------------------------------------------------------------------------------ // PPM GENERATOR START - TOGGLE ON COMPARE INTERRUPT ENABLE @@ -655,8 +666,18 @@ CHECK_PINS_LOOP: // Input servo pin check loop servo_input_connected[ ppm_channel ]++; } - //Reset ppm single channel fail-safe timeout + //Reset ppm single channel fail-safe timeout ppm_timeout[ ppm_channel ] = 0; + + // Check for forced throttle fail-safe + if( throttle_failsafe_force ) + { + if( ppm_channel == 5 ) + { + // Force throttle fail-safe + servo_width = PPM_THROTTLE_FAILSAFE; + } + } #ifdef _AVERAGE_FILTER_ // Average filter to smooth input jitter @@ -754,6 +775,12 @@ ISR( PPM_INT_VECTOR, ISR_NOBLOCK ) PPM_COMPARE += failsafe_ppm[ ppm_out_channel ]; sei(); + // Count the channel that we have lost + if( servo_input_connected[ ppm_out_channel ] ) + { + disconnected_channels++; + } + #if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__) // Turn on RX LED to indicate a fail-safe condition PORTD &= ~(1 << PD4); @@ -777,6 +804,18 @@ ISR( PPM_INT_VECTOR, ISR_NOBLOCK ) { ppm_out_channel = 0; + // Did we lose one or more active servo input channel? If so force throttle fail-safe (RTL) + if( disconnected_channels > 0 ) + { + throttle_failsafe_force = true; + } + else + { + throttle_failsafe_force = false; + } + + disconnected_channels = 0; + #if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__) // Blink TX LED when PPM generator has finished a pulse train PIND |= ( 1<< PD5 );