ArduPPM: changes for throttle low indication and also recovery after a throttle low indication are now set with defines

This commit is contained in:
Julian Oes 2013-01-11 15:08:13 -08:00
parent 70ce94ee88
commit ef6268f62a
2 changed files with 30 additions and 6 deletions

View File

@ -1,5 +1,5 @@
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
// ArduPPM Version v0.9.87
// ArduPPM Version v0.9.89
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
// ARDUCOPTER 2 : PPM ENCODER for AT Mega 328p and APM v1.4 Boards
// By:John Arne Birkeland - 2011
@ -36,6 +36,7 @@
// 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
// 0.9.89 : LED fail-safe change can be reverted with a define
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
// PREPROCESSOR DIRECTIVES
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
@ -48,7 +49,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
@ -284,7 +285,11 @@ int main(void)
// ------------------------------------------------------------------------------
while( 1 )
{
#if defined _THROTTLE_LOW_RECOVERY_POSSIBLE
if ( throttle_failsafe_force ) // We have an error
#else
if ( servo_error_condition || servo_input_missing ) // We have an error
#endif
{
blink_led ( 6 * LOOP_TIMER_10MS ); // Status LED very fast blink if invalid servo input or missing signal
}
@ -369,8 +374,11 @@ int main(void)
// ------------------------------------------------------------------------------
// Status LED control
// ------------------------------------------------------------------------------
#ifdef _THROTTLE_LOW_FAILSAFE_INDICATION
if ( throttle_failsafe_force ) // We have an error
#else
if ( servo_error_condition || servo_input_missing ) // We have an error
#endif
{
blink_led ( 6 * LOOP_TIMER_10MS ); // Status LED very fast blink if invalid servo input or missing signal
}
@ -456,7 +464,7 @@ int main(void)
// Status LED control
// ------------------------------------------------------------------------------
if ( throttle_failsafe_force ) // We have an error
if ( servo_input_missing ) // We have an error
{
blink_led ( 6 * LOOP_TIMER_10MS ); // Status LED very fast blink if invalid servo input or missing signal
}

View File

@ -1,5 +1,5 @@
// -------------------------------------------------------------
// ArduPPM (PPM Encoder) V2.3.14pre
// ArduPPM (PPM Encoder) V2.3.14
// -------------------------------------------------------------
// Improved servo to ppm for ArduPilot MEGA v1.x (ATmega328p),
// PhoneDrone and APM2.x (ATmega32u2)
@ -135,6 +135,7 @@
// 11-01-2013
// V2.3.14 - temporary release for ArduCopter 2.9
// - fail-safe throttle low can be set with a define
// - recovery from error condition can also be set with a define
// -------------------------------------------------------------
@ -199,6 +200,11 @@ volatile uint8_t servo_input_mode = JUMPER_SELECT_MODE;
//#define _APM_FAILSAFE_ // Used to spesify APM 800us channel loss fail safe values, remove to use normal fail safe values (stand alone encoder board)
#define _THROTTLE_LOW_FAILSAFE_INDICATION //if set, throttle is set to low in an error condition
#define _THROTTLE_LOW_RECOVERY_POSSIBLE //if set, a channel can be regained when the error disappears, only makes sense together with _THROTTLE_LOW_FAILSAFE_INDICATION
#if defined _THROTTLE_LOW_RECOVERY_POSSIBLE && !defined _THROTTLE_LOW_FAILSAFE_INDICATION
#error failsafe recovery is only possible with throttle_low_failsafe_indication defined as well
#endif
// -------------------------------------------------------------
// SERVO LIMIT VALUES
@ -333,8 +339,10 @@ volatile uint8_t ppm_timeout[ PPM_ARRAY_MAX ];
#define SERVO_INPUT_CONNECTED_VALUE 100
volatile uint8_t servo_input_connected[ PPM_ARRAY_MAX ];
#ifdef _THROTTLE_LOW_RECOVERY_POSSIBLE
// count the channels which have been once connected but then got disconnected
volatile uint8_t disconnected_channels;
#endif
// AVR parameters for PhoneDrone and APM2 boards using ATmega32u2
#if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__)
@ -427,8 +435,10 @@ volatile bool ppm_generator_active = false;
// Used to indicate a brownout restart
volatile bool brownout_reset = false;
#ifdef _THROTTLE_LOW_FAILSAFE_INDICATION
// Used to force throttle fail-safe mode (RTL)
volatile bool throttle_failsafe_force = false;
#endif
// ------------------------------------------------------------------------------
// PPM GENERATOR START - TOGGLE ON COMPARE INTERRUPT ENABLE
@ -782,11 +792,15 @@ ISR( PPM_INT_VECTOR, ISR_NOBLOCK )
PPM_COMPARE += failsafe_ppm[ ppm_out_channel ];
sei();
#if defined _THROTTLE_LOW_RECOVERY_POSSIBLE && defined _THROTTLE_LOW_FAILSAFE_INDICATION
// Count the channel that we have lost
if( servo_input_connected[ ppm_out_channel ] )
{
disconnected_channels++;
}
#elif defined _THROTTLE_LOW_FAILSAFE_INDICATION
throttle_failsafe_force = true;
#endif
#if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__)
// Turn on RX LED to indicate a fail-safe condition
@ -811,7 +825,8 @@ 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)
#ifdef _THROTTLE_LOW_RECOVERY_POSSIBLE
// 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;
@ -822,6 +837,7 @@ ISR( PPM_INT_VECTOR, ISR_NOBLOCK )
}
disconnected_channels = 0;
#endif
#if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__)
// Blink TX LED when PPM generator has finished a pulse train