|
|
|
@ -1,5 +1,5 @@
@@ -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 @@
@@ -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 @@
@@ -168,7 +174,7 @@
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
// Version stamp for firmware hex file ( decode hex file using <avr-objdump -s file.hex> 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 ];
@@ -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;
@@ -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
@@ -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 )
@@ -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 )
@@ -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 ); |
|
|
|
|