mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-03 06:28:32 -04:00
Merge pull request #6 from julianoes/ppm_encoder_fixes
ArduPPM Two new defines added: _THROTTLE_LOW_FAILSAFE_INDICATION: Throttle low indication and thus APM fail-safe triggering when a single channel error is detected. _THROTTLE_LOW_RECOVERY_POSSIBLE: Throttle low is reset when a disconnected channel comes back and full control regained.
This commit is contained in:
commit
3e5330efc9
@ -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
|
// ARDUCOPTER 2 : PPM ENCODER for AT Mega 328p and APM v1.4 Boards
|
||||||
// By:John Arne Birkeland - 2011
|
// By:John Arne Birkeland - 2011
|
||||||
@ -35,11 +35,13 @@
|
|||||||
// 0.9.85 : Added brownout reset detection flag
|
// 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.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.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
|
// PREPROCESSOR DIRECTIVES
|
||||||
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
|
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||||
|
|
||||||
#include "..\Libraries\PPM_Encoder.h"
|
#include "../Libraries/PPM_Encoder.h"
|
||||||
#include <util/delay.h>
|
#include <util/delay.h>
|
||||||
|
|
||||||
|
|
||||||
@ -283,7 +285,11 @@ int main(void)
|
|||||||
// ------------------------------------------------------------------------------
|
// ------------------------------------------------------------------------------
|
||||||
while( 1 )
|
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
|
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
|
blink_led ( 6 * LOOP_TIMER_10MS ); // Status LED very fast blink if invalid servo input or missing signal
|
||||||
}
|
}
|
||||||
@ -368,7 +374,11 @@ int main(void)
|
|||||||
// ------------------------------------------------------------------------------
|
// ------------------------------------------------------------------------------
|
||||||
// Status LED control
|
// 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
|
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
|
blink_led ( 6 * LOOP_TIMER_10MS ); // Status LED very fast blink if invalid servo input or missing signal
|
||||||
}
|
}
|
||||||
|
@ -54,7 +54,7 @@
|
|||||||
* number of device configurations. The descriptor is read out by the USB host when the enumeration
|
* number of device configurations. The descriptor is read out by the USB host when the enumeration
|
||||||
* process begins.
|
* process begins.
|
||||||
*/
|
*/
|
||||||
USB_Descriptor_Device_t PROGMEM DeviceDescriptor =
|
const USB_Descriptor_Device_t PROGMEM DeviceDescriptor =
|
||||||
{
|
{
|
||||||
.Header = {.Size = sizeof(USB_Descriptor_Device_t), .Type = DTYPE_Device},
|
.Header = {.Size = sizeof(USB_Descriptor_Device_t), .Type = DTYPE_Device},
|
||||||
|
|
||||||
@ -91,7 +91,7 @@ USB_Descriptor_Device_t PROGMEM DeviceDescriptor =
|
|||||||
* and endpoints. The descriptor is read out by the USB host during the enumeration process when selecting
|
* and endpoints. The descriptor is read out by the USB host during the enumeration process when selecting
|
||||||
* a configuration so that the host may correctly communicate with the USB device.
|
* a configuration so that the host may correctly communicate with the USB device.
|
||||||
*/
|
*/
|
||||||
USB_Descriptor_Configuration_t PROGMEM ConfigurationDescriptor =
|
const USB_Descriptor_Configuration_t PROGMEM ConfigurationDescriptor =
|
||||||
{
|
{
|
||||||
.Config =
|
.Config =
|
||||||
{
|
{
|
||||||
@ -199,7 +199,7 @@ USB_Descriptor_Configuration_t PROGMEM ConfigurationDescriptor =
|
|||||||
* the string descriptor with index 0 (the first index). It is actually an array of 16-bit integers, which indicate
|
* the string descriptor with index 0 (the first index). It is actually an array of 16-bit integers, which indicate
|
||||||
* via the language ID table available at USB.org what languages the device supports for its string descriptors.
|
* via the language ID table available at USB.org what languages the device supports for its string descriptors.
|
||||||
*/
|
*/
|
||||||
USB_Descriptor_String_t PROGMEM LanguageString =
|
const USB_Descriptor_String_t PROGMEM LanguageString =
|
||||||
{
|
{
|
||||||
.Header = {.Size = USB_STRING_LEN(1), .Type = DTYPE_String},
|
.Header = {.Size = USB_STRING_LEN(1), .Type = DTYPE_String},
|
||||||
|
|
||||||
@ -210,7 +210,7 @@ USB_Descriptor_String_t PROGMEM LanguageString =
|
|||||||
* form, and is read out upon request by the host when the appropriate string ID is requested, listed in the Device
|
* form, and is read out upon request by the host when the appropriate string ID is requested, listed in the Device
|
||||||
* Descriptor.
|
* Descriptor.
|
||||||
*/
|
*/
|
||||||
USB_Descriptor_String_t PROGMEM ManufacturerString =
|
const USB_Descriptor_String_t PROGMEM ManufacturerString =
|
||||||
{
|
{
|
||||||
.Header = {.Size = USB_STRING_LEN(24), .Type = DTYPE_String},
|
.Header = {.Size = USB_STRING_LEN(24), .Type = DTYPE_String},
|
||||||
|
|
||||||
@ -221,7 +221,7 @@ USB_Descriptor_String_t PROGMEM ManufacturerString =
|
|||||||
* and is read out upon request by the host when the appropriate string ID is requested, listed in the Device
|
* and is read out upon request by the host when the appropriate string ID is requested, listed in the Device
|
||||||
* Descriptor.
|
* Descriptor.
|
||||||
*/
|
*/
|
||||||
USB_Descriptor_String_t PROGMEM ProductString =
|
const USB_Descriptor_String_t PROGMEM ProductString =
|
||||||
{
|
{
|
||||||
#if (ARDUINO_MODEL_PID == ARDUINO_UNO_PID)
|
#if (ARDUINO_MODEL_PID == ARDUINO_UNO_PID)
|
||||||
.Header = {.Size = USB_STRING_LEN(11), .Type = DTYPE_String},
|
.Header = {.Size = USB_STRING_LEN(11), .Type = DTYPE_String},
|
||||||
|
@ -1,5 +1,5 @@
|
|||||||
// -------------------------------------------------------------
|
// -------------------------------------------------------------
|
||||||
// ArduPPM (PPM Encoder) V2.3.13
|
// ArduPPM (PPM Encoder) V2.3.14
|
||||||
// -------------------------------------------------------------
|
// -------------------------------------------------------------
|
||||||
// Improved servo to ppm for ArduPilot MEGA v1.x (ATmega328p),
|
// Improved servo to ppm for ArduPilot MEGA v1.x (ATmega328p),
|
||||||
// PhoneDrone and APM2.x (ATmega32u2)
|
// PhoneDrone and APM2.x (ATmega32u2)
|
||||||
@ -127,6 +127,16 @@
|
|||||||
// V2.3.13 - Official release
|
// 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)
|
// - Fail-safe vales changed back to normal fail-safe values. Use until APM code knows how to handle lost channel signal (800us)
|
||||||
|
|
||||||
|
// 10-01-2013
|
||||||
|
// 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
|
||||||
|
|
||||||
|
// 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
|
||||||
|
|
||||||
// -------------------------------------------------------------
|
// -------------------------------------------------------------
|
||||||
|
|
||||||
#ifndef _PPM_ENCODER_H_
|
#ifndef _PPM_ENCODER_H_
|
||||||
@ -168,7 +178,7 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Version stamp for firmware hex file ( decode hex file using <avr-objdump -s file.hex> and look for "ArduPPM" string )
|
// 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.14";
|
||||||
|
|
||||||
// -------------------------------------------------------------
|
// -------------------------------------------------------------
|
||||||
// INPUT MODE
|
// INPUT MODE
|
||||||
@ -189,6 +199,13 @@ 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 _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 when a single channel is lost
|
||||||
|
//#define _THROTTLE_LOW_RECOVERY_POSSIBLE //if set, throttle low recovers from being low when the single channel comes back, 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
|
// SERVO LIMIT VALUES
|
||||||
// -------------------------------------------------------------
|
// -------------------------------------------------------------
|
||||||
@ -322,6 +339,11 @@ volatile uint8_t ppm_timeout[ PPM_ARRAY_MAX ];
|
|||||||
#define SERVO_INPUT_CONNECTED_VALUE 100
|
#define SERVO_INPUT_CONNECTED_VALUE 100
|
||||||
volatile uint8_t servo_input_connected[ PPM_ARRAY_MAX ];
|
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
|
// AVR parameters for PhoneDrone and APM2 boards using ATmega32u2
|
||||||
#if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__)
|
#if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__)
|
||||||
|
|
||||||
@ -413,6 +435,10 @@ volatile bool ppm_generator_active = false;
|
|||||||
// Used to indicate a brownout restart
|
// Used to indicate a brownout restart
|
||||||
volatile bool brownout_reset = false;
|
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
|
// PPM GENERATOR START - TOGGLE ON COMPARE INTERRUPT ENABLE
|
||||||
@ -655,9 +681,21 @@ CHECK_PINS_LOOP: // Input servo pin check loop
|
|||||||
servo_input_connected[ ppm_channel ]++;
|
servo_input_connected[ ppm_channel ]++;
|
||||||
}
|
}
|
||||||
|
|
||||||
//Reset ppm single channel fail-safe timeout
|
//Reset ppm single channel fail-safe timeout
|
||||||
ppm_timeout[ ppm_channel ] = 0;
|
ppm_timeout[ ppm_channel ] = 0;
|
||||||
|
|
||||||
|
#ifdef _THROTTLE_LOW_FAILSAFE_INDICATION
|
||||||
|
// Check for forced throttle fail-safe
|
||||||
|
if( throttle_failsafe_force )
|
||||||
|
{
|
||||||
|
if( ppm_channel == 5 )
|
||||||
|
{
|
||||||
|
// Force throttle fail-safe
|
||||||
|
servo_width = PPM_THROTTLE_FAILSAFE;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef _AVERAGE_FILTER_
|
#ifdef _AVERAGE_FILTER_
|
||||||
// Average filter to smooth input jitter
|
// Average filter to smooth input jitter
|
||||||
servo_width += ppm[ ppm_channel ];
|
servo_width += ppm[ ppm_channel ];
|
||||||
@ -754,6 +792,16 @@ ISR( PPM_INT_VECTOR, ISR_NOBLOCK )
|
|||||||
PPM_COMPARE += failsafe_ppm[ ppm_out_channel ];
|
PPM_COMPARE += failsafe_ppm[ ppm_out_channel ];
|
||||||
sei();
|
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__)
|
#if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__)
|
||||||
// Turn on RX LED to indicate a fail-safe condition
|
// Turn on RX LED to indicate a fail-safe condition
|
||||||
PORTD &= ~(1 << PD4);
|
PORTD &= ~(1 << PD4);
|
||||||
@ -777,6 +825,20 @@ ISR( PPM_INT_VECTOR, ISR_NOBLOCK )
|
|||||||
{
|
{
|
||||||
ppm_out_channel = 0;
|
ppm_out_channel = 0;
|
||||||
|
|
||||||
|
#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;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
throttle_failsafe_force = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
disconnected_channels = 0;
|
||||||
|
#endif
|
||||||
|
|
||||||
#if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__)
|
#if defined (__AVR_ATmega16U2__) || defined (__AVR_ATmega32U2__)
|
||||||
// Blink TX LED when PPM generator has finished a pulse train
|
// Blink TX LED when PPM generator has finished a pulse train
|
||||||
PIND |= ( 1<< PD5 );
|
PIND |= ( 1<< PD5 );
|
||||||
|
Loading…
Reference in New Issue
Block a user