mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
ArduPPM(experimental): Active input channel detection during init
This commit is contained in:
parent
12e19617f5
commit
e077814e77
@ -73,6 +73,7 @@
|
||||
|
||||
// 22-11-2012
|
||||
// V2.3.11 - Very experimental test forcing throttle fail-safe (RTL) on single channel loss. !DO NOT RELEASE TO PUBLIC!
|
||||
// - Test for active input channels during init
|
||||
|
||||
// -------------------------------------------------------------
|
||||
|
||||
@ -562,7 +563,7 @@ CHECK_PINS_LOOP: // Input servo pin check loop
|
||||
wdt_reset();
|
||||
|
||||
// Channel has received a valid signal, so it must be connected
|
||||
servo_input_connected [ ppm_channel ] = true;
|
||||
// servo_input_connected [ ppm_channel ] = true; // Removed - Check performed during init
|
||||
|
||||
// Check for forced throttle fail-safe
|
||||
if( throttle_failsafe_force && ppm_channel == 5 )
|
||||
@ -607,7 +608,7 @@ CHECK_PINS_NEXT:
|
||||
|
||||
// Check channel and process if needed
|
||||
//if( servo_channel < SERVO_CHANNELS ) goto CHECK_PINS_LOOP;
|
||||
if( servo_pin ) goto CHECK_PINS_LOOP; // Bitshift wraps to zero (false)
|
||||
if( servo_pin ) goto CHECK_PINS_LOOP; // Bit shifts to zero when all pins have been checked
|
||||
|
||||
goto CHECK_PINS_DONE;
|
||||
|
||||
@ -823,28 +824,119 @@ void ppm_encoder_init( void )
|
||||
}
|
||||
#endif
|
||||
|
||||
// SERVO/PPM INPUT - PIN CHANGE INTERRUPT
|
||||
// ------------------------------------------------------------------------------
|
||||
if( servo_input_mode == SERVO_PWM_MODE )
|
||||
{
|
||||
// Set servo input interrupt pin mask to all 8 servo input channels
|
||||
SERVO_INT_MASK = 0xFF;
|
||||
}
|
||||
|
||||
// PPM PASS-THROUGH MODE
|
||||
if( servo_input_mode == PPM_PASSTROUGH_MODE )
|
||||
{
|
||||
// Set servo input interrupt pin mask to servo input channel 1
|
||||
SERVO_INT_MASK = 0x01;
|
||||
}
|
||||
|
||||
// SERVO PWM INPUT MODE
|
||||
// ------------------------------------------------------------------------------
|
||||
if( servo_input_mode == SERVO_PWM_MODE )
|
||||
{
|
||||
// CHECK FOR ACTIVE INPUT CHANNELS
|
||||
// ------------------------------------------------------------------------------
|
||||
// This will poll the input pins looking for pin level changes, and mark the inputs with active signal connections
|
||||
|
||||
uint16_t input_channel_count[ SERVO_CHANNELS ];
|
||||
uint8_t input_current; // Input pin level mask
|
||||
uint8_t input_previous; // Input pin level mask
|
||||
uint8_t input_int_mask; // Active input pin interupt mask
|
||||
|
||||
INPUT_ACTIVE_CHANNEL_CHECK:
|
||||
|
||||
// ~100khz timed polling of input pins for ~0.5sec duration (1us = 16 clocks)
|
||||
for( uint16_t t = 0; t < 50000; t++ ) // 10us * 1000ms * 0.5sec = 50000 delayed loops at 10us
|
||||
{
|
||||
// Get current input pin levels
|
||||
input_current = SERVO_INPUT;
|
||||
|
||||
// Check input pins against previous levels
|
||||
uint8_t input_change = input_current ^ input_previous;
|
||||
|
||||
// Do we need to check for changes?
|
||||
if( input_change )
|
||||
{
|
||||
// Check for change on all input pins
|
||||
uint8_t input_pin = 1;
|
||||
uint8_t input_channel = 0;
|
||||
|
||||
do
|
||||
{
|
||||
// Check for change on current input pin
|
||||
if( input_change & input_pin )
|
||||
{
|
||||
// Pin has changed, count it
|
||||
input_channel_count[ input_channel ]++;
|
||||
}
|
||||
|
||||
// Select next pin
|
||||
input_pin <<= 1;
|
||||
|
||||
// Select next channel
|
||||
input_channel++;
|
||||
|
||||
} while ( input_channel < SERVO_CHANNELS );
|
||||
|
||||
// Store checked input pin levels
|
||||
input_previous = input_current;
|
||||
}
|
||||
|
||||
// Delay the next input level check
|
||||
_delay_us( 10 );
|
||||
|
||||
}
|
||||
|
||||
// Check input_channel_count[..] to see if channels are active.
|
||||
for( uint8_t input_channel = 0; input_channel < SERVO_CHANNELS; input_channel++ )
|
||||
{
|
||||
// Is current channel active?
|
||||
if( input_channel_count[ input_channel ] > 20 ) // 0.5sec * 40hz * 2 = 40 pulse edges - 50% margin = 20 level changes
|
||||
{
|
||||
// Set active channel in servo_input_connected[..]
|
||||
servo_input_connected[ (input_channel << 1) + 1 ] = true;
|
||||
|
||||
// Set interupt pin mask for active channel
|
||||
input_int_mask |= 1 << input_channel;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
// if no active input channels are found, then re-check until found (might be caused by delayed receiver startup)
|
||||
// Do not perform re-check if there was a brown-out reset
|
||||
if( input_int_mask > 0 && !brownout_reset )
|
||||
{
|
||||
// Re-check active input channels
|
||||
goto INPUT_ACTIVE_CHANNEL_CHECK;
|
||||
}
|
||||
|
||||
// Set servo input interrupt pin mask
|
||||
// Set to all input channel for safety in case of brown-out reset
|
||||
if( brownout_reset)
|
||||
{
|
||||
// Interrupt on all input pins
|
||||
SERVO_INT_MASK = 0xFF;
|
||||
}
|
||||
else
|
||||
{
|
||||
// Interrupt only on active input pins
|
||||
SERVO_INT_MASK = input_int_mask;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Enable servo input interrupt
|
||||
PCICR |= (1 << SERVO_INT_ENABLE);
|
||||
|
||||
// PPM OUTPUT PIN
|
||||
// PPM OUTPUT
|
||||
// ------------------------------------------------------------------------------
|
||||
// PPM generator (PWM output timer/counter) is started either by pin change interrupt or by watchdog interrupt
|
||||
|
||||
// Set PPM pin to output
|
||||
PPM_DDR |= (1 << PPM_OUTPUT_PIN);
|
||||
|
||||
|
||||
// ------------------------------------------------------------------------------
|
||||
// Enable watchdog interrupt mode
|
||||
// ------------------------------------------------------------------------------
|
||||
|
Loading…
Reference in New Issue
Block a user