ArduPPM V2.3.13
- New interrupt system that handles certain Futaba receivers better (simultaneous changes on groups of R/C channels in fast intervals) - Improved active channel detection requering 100 valid pulses before channel is marked active - Removed forced throttle fail-safe after channel loss - Lost channel detection signal for APM by setting channel output to 800us (not activated yet, need APM code to handle signals)
This commit is contained in:
parent
0419dc8dfd
commit
d5364571a8
@ -1,5 +1,5 @@
|
||||
// -------------------------------------------------------------
|
||||
// ArduPPM (PPM Encoder) V2.3.12
|
||||
// ArduPPM (PPM Encoder) V2.3.13
|
||||
// -------------------------------------------------------------
|
||||
// Improved servo to ppm for ArduPilot MEGA v1.x (ATmega328p),
|
||||
// PhoneDrone and APM2.x (ATmega32u2)
|
||||
@ -27,11 +27,10 @@
|
||||
// -----------------------
|
||||
// - PPM output will not be enabled unless a input signal has been detected and verified
|
||||
// - Verified inputs are lost during operaton (lose servo wire or receiver malfunction):
|
||||
// + The PPM output channel for the lost input will be set to the default fail-safe value
|
||||
// + PPM throttle output (ch3) will be permanently set to fail-safe (900us)
|
||||
// + The last known value of the lost input channel is keept for ~1 second
|
||||
// + If the lost input channel is not restored within ~1 second, it will be set to the default fail-safe value
|
||||
// - Lost channel signal is restored:
|
||||
// + PPM output for the restored channel will be updated with the valid signal
|
||||
// + PPM throttle output (ch3) will not be restored, and will continue to output fail-safe (900us)
|
||||
// + Normal channel operation is restored using the valid input signal
|
||||
|
||||
// PPM PASS-THROUGH MODE (signal pin 2&3 shorted):
|
||||
// -----------------------------------------------
|
||||
@ -118,6 +117,16 @@
|
||||
// - Improved LED status for APM 2.x
|
||||
// - Improved jitter performance (PPM output using nested interrupts)
|
||||
|
||||
// 30-11-2012
|
||||
// V2.3.13pre - Internal dev only pre-release
|
||||
// - Improved active channel detection requering 100 valid pulses before channel is marked active
|
||||
// - Removed forced throttle fail-safe after channel loss
|
||||
// - Changed fail-safe values to 800us, this will be used by APM code to detect channel loss and decide fail safe actions
|
||||
|
||||
// 16-12-2012
|
||||
// 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)
|
||||
|
||||
// -------------------------------------------------------------
|
||||
|
||||
#ifndef _PPM_ENCODER_H_
|
||||
@ -159,7 +168,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.12";
|
||||
const char ver[15] = "ArduPPMv2.3.13";
|
||||
|
||||
// -------------------------------------------------------------
|
||||
// INPUT MODE
|
||||
@ -173,6 +182,15 @@ const char ver[15] = "ArduPPMv2.3.12";
|
||||
|
||||
// Servo input mode (jumper (default), pwm, ppm, jeti or spektrum)
|
||||
volatile uint8_t servo_input_mode = JUMPER_SELECT_MODE;
|
||||
|
||||
// -------------------------------------------------------------
|
||||
// FAILSAFE 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)
|
||||
|
||||
// -------------------------------------------------------------
|
||||
// SERVO LIMIT VALUES
|
||||
// -------------------------------------------------------------
|
||||
|
||||
// Number of Timer1 ticks in one microsecond
|
||||
@ -181,11 +199,6 @@ volatile uint8_t servo_input_mode = JUMPER_SELECT_MODE;
|
||||
// 400us PPM pre pulse
|
||||
#define PPM_PRE_PULSE ONE_US * 400
|
||||
|
||||
|
||||
// -------------------------------------------------------------
|
||||
// SERVO LIMIT VALUES
|
||||
// -------------------------------------------------------------
|
||||
|
||||
// Servo minimum position
|
||||
#define PPM_SERVO_MIN ONE_US * 900 - PPM_PRE_PULSE
|
||||
|
||||
@ -201,6 +214,9 @@ volatile uint8_t servo_input_mode = JUMPER_SELECT_MODE;
|
||||
// Throttle during failsafe
|
||||
#define PPM_THROTTLE_FAILSAFE ONE_US * 900 - PPM_PRE_PULSE
|
||||
|
||||
// Channel loss failsafe
|
||||
#define PPM_CHANNEL_LOSS ONE_US * 800 - PPM_PRE_PULSE
|
||||
|
||||
// CH5 power on values (mode selection channel)
|
||||
#define PPM_CH5_MODE_4 ONE_US * 1555 - PPM_PRE_PULSE
|
||||
|
||||
@ -219,6 +235,32 @@ volatile uint8_t servo_input_mode = JUMPER_SELECT_MODE;
|
||||
// Size of ppm[..] data array ( servo channels * 2 + 2)
|
||||
#define PPM_ARRAY_MAX 18
|
||||
|
||||
#ifdef _APM_FAILSAFE_
|
||||
// -------------------------------------------------------------
|
||||
// APM FAILSAFE VALUES
|
||||
// -------------------------------------------------------------
|
||||
volatile uint16_t failsafe_ppm[ PPM_ARRAY_MAX ] =
|
||||
{
|
||||
PPM_PRE_PULSE,
|
||||
PPM_CHANNEL_LOSS, // Channel 1
|
||||
PPM_PRE_PULSE,
|
||||
PPM_CHANNEL_LOSS, // Channel 2
|
||||
PPM_PRE_PULSE,
|
||||
PPM_CHANNEL_LOSS, // Channel 3 (throttle)
|
||||
PPM_PRE_PULSE,
|
||||
PPM_CHANNEL_LOSS, // Channel 4
|
||||
PPM_PRE_PULSE,
|
||||
PPM_CHANNEL_LOSS, // Channel 5
|
||||
PPM_PRE_PULSE,
|
||||
PPM_CHANNEL_LOSS, // Channel 6
|
||||
PPM_PRE_PULSE,
|
||||
PPM_CHANNEL_LOSS, // Channel 7
|
||||
PPM_PRE_PULSE,
|
||||
PPM_CHANNEL_LOSS, // Channel 8
|
||||
PPM_PRE_PULSE,
|
||||
PPM_PERIOD
|
||||
};
|
||||
#else
|
||||
// -------------------------------------------------------------
|
||||
// SERVO FAILSAFE VALUES
|
||||
// -------------------------------------------------------------
|
||||
@ -243,6 +285,7 @@ volatile uint16_t failsafe_ppm[ PPM_ARRAY_MAX ] =
|
||||
PPM_PRE_PULSE,
|
||||
PPM_PERIOD
|
||||
};
|
||||
#endif
|
||||
|
||||
// -------------------------------------------------------------
|
||||
// Data array for storing ppm (8 channels) pulse widths.
|
||||
@ -275,8 +318,9 @@ volatile uint16_t ppm[ PPM_ARRAY_MAX ] =
|
||||
#define PPM_TIMEOUT_VALUE 40 // ~1sec before triggering missing channel detection
|
||||
volatile uint8_t ppm_timeout[ PPM_ARRAY_MAX ];
|
||||
|
||||
// Servo input channel connected flag
|
||||
volatile bool servo_input_connected[ PPM_ARRAY_MAX ];
|
||||
// Servo input channel connected status
|
||||
#define SERVO_INPUT_CONNECTED_VALUE 100
|
||||
volatile uint8_t servo_input_connected[ PPM_ARRAY_MAX ];
|
||||
|
||||
// AVR parameters for PhoneDrone and APM2 boards using ATmega32u2
|
||||
#if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__)
|
||||
@ -300,7 +344,7 @@ volatile bool servo_input_connected[ PPM_ARRAY_MAX ];
|
||||
#define PPM_COMPARE_FORCE_MATCH FOC1A
|
||||
|
||||
#define USB_DDR DDRC
|
||||
#define USB_PORT PORTC
|
||||
#define USB_PORT PORTC
|
||||
#define USB_PIN PC2
|
||||
|
||||
// true if we have received a USB device connect event
|
||||
@ -356,10 +400,7 @@ void EVENT_USB_Device_Disconnect(void)
|
||||
#else
|
||||
#error NO SUPPORTED DEVICE FOUND! (ATmega16u2 / ATmega32u2 / ATmega328p)
|
||||
#endif
|
||||
|
||||
// Used to force throttle fail-safe mode (RTL)
|
||||
volatile bool throttle_failsafe_force = false;
|
||||
|
||||
|
||||
// Used to indicate invalid SERVO input signals
|
||||
volatile uint8_t servo_input_errors = 0;
|
||||
|
||||
@ -462,9 +503,9 @@ ISR( WDT_vect ) // If watchdog is triggered then enable missing signal flag and
|
||||
if ( ppm_generator_active || brownout_reset )
|
||||
{
|
||||
// Copy failsafe values to ppm[..]
|
||||
for( volatile uint8_t i = 0; i < PPM_ARRAY_MAX; i++ )
|
||||
for( uint8_t i = 0; i < PPM_ARRAY_MAX; i++ )
|
||||
{
|
||||
ppm[ i ] = failsafe_ppm[ i ];
|
||||
ppm[ i ] = failsafe_ppm[ i ];
|
||||
}
|
||||
}
|
||||
|
||||
@ -568,7 +609,7 @@ ISR( SERVO_INT_VECTOR )
|
||||
// SERVO PWM MODE
|
||||
// ------------------------------------------------------------------------------
|
||||
|
||||
CHECK_PINS_START: // Start of servo input check
|
||||
//CHECK_PINS_START: // Start of servo input check
|
||||
|
||||
// Store current servo input pins
|
||||
servo_pins = SERVO_INPUT;
|
||||
@ -608,27 +649,15 @@ CHECK_PINS_LOOP: // Input servo pin check loop
|
||||
// Set servo input missing flag false to indicate that we have received servo input signals
|
||||
servo_input_missing = false;
|
||||
|
||||
// Channel has received a valid signal, so it must be connected
|
||||
servo_input_connected [ ppm_channel ] = true;
|
||||
// Count valid signals to mark channel active
|
||||
if( servo_input_connected[ ppm_channel ] < SERVO_INPUT_CONNECTED_VALUE )
|
||||
{
|
||||
servo_input_connected[ ppm_channel ]++;
|
||||
}
|
||||
|
||||
//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;
|
||||
}
|
||||
|
||||
#if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__)
|
||||
// Turn on RX LED if throttle fail-safe is forced
|
||||
PORTD &= ~(1 << PD4);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
#ifdef _AVERAGE_FILTER_
|
||||
// Average filter to smooth input jitter
|
||||
servo_width += ppm[ ppm_channel ];
|
||||
@ -724,25 +753,26 @@ ISR( PPM_INT_VECTOR, ISR_NOBLOCK )
|
||||
cli();
|
||||
PPM_COMPARE += failsafe_ppm[ ppm_out_channel ];
|
||||
sei();
|
||||
|
||||
// Did we lose an active servo input channel? If so force throttle fail-safe (RTL)
|
||||
if( servo_input_connected[ ppm_out_channel ] )
|
||||
{
|
||||
throttle_failsafe_force = true;
|
||||
}
|
||||
|
||||
#if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__)
|
||||
// Turn on RX LED to indicate a fail-safe condition
|
||||
PORTD &= ~(1 << PD4);
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
// Use latest ppm input value
|
||||
cli();
|
||||
PPM_COMPARE += ppm[ ppm_out_channel ];
|
||||
sei();
|
||||
sei();
|
||||
|
||||
// Increment channel timeout (reset to zero in input interrupt each time a valid signal is detected)
|
||||
ppm_timeout[ ppm_out_channel ] ++;
|
||||
// Increment active channel timeout (reset to zero in input interrupt each time a valid signal is detected)
|
||||
if( servo_input_connected[ ppm_out_channel ] >= SERVO_INPUT_CONNECTED_VALUE )
|
||||
{
|
||||
ppm_timeout[ ppm_out_channel ]++;
|
||||
}
|
||||
}
|
||||
|
||||
// Select the next ppm channel
|
||||
|
||||
if( ++ppm_out_channel >= PPM_ARRAY_MAX )
|
||||
{
|
||||
ppm_out_channel = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user