Browse Source

APM: added control switch debouncer

this adds a switch debouncer, similar to the one used in
ArduCopter. I'm adding this after a flight on the weekend where noise
on the control mode channel caused a mode change away from auto.

To prevent this change adding excessive mode switch latency, it also
moves the reading of the control switch to the 10Hz loop, away from
the 3.3Hz loop. That gives us 0.2s delay in mode switch changes and
allows for spikes in the control mode for 0.1 seconds without changing
mode.
master
Andrew Tridgell 13 years ago
parent
commit
301ab00c5b
  1. 7
      ArduPlane/ArduPlane.pde
  2. 14
      ArduPlane/control_modes.pde

7
ArduPlane/ArduPlane.pde

@ -807,6 +807,9 @@ Serial.println(tempaccel.z, DEC); @@ -807,6 +807,9 @@ Serial.println(tempaccel.z, DEC);
case 1:
medium_loopCounter++;
// Read 6-position switch on radio
// -------------------------------
read_control_switch();
if(g_gps->new_data){
g_gps->new_data = false;
@ -896,10 +899,6 @@ static void slow_loop() @@ -896,10 +899,6 @@ static void slow_loop()
case 1:
slow_loopCounter++;
// Read 3-position switch on radio
// -------------------------------
read_control_switch();
// Read Control Surfaces/Mix switches
// ----------------------------------
update_servo_switches();

14
ArduPlane/control_modes.pde

@ -1,8 +1,9 @@ @@ -1,8 +1,9 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static void read_control_switch()
{
static bool switch_debouncer;
byte switchPosition = readSwitch();
// If switchPosition = 255 this indicates that the mode control channel input was out of range
@ -19,6 +20,15 @@ static void read_control_switch() @@ -19,6 +20,15 @@ static void read_control_switch()
(g.reset_switch_chan != 0 &&
APM_RC.InputCh(g.reset_switch_chan-1) > RESET_SWITCH_CHAN_PWM)) {
if (switch_debouncer == false) {
// this ensures that mode switches only happen if the
// switch changes for 2 reads. This prevents momentary
// spikes in the mode control channel from causing a mode
// switch
switch_debouncer = true;
return;
}
set_mode(flight_modes[switchPosition]);
oldSwitchPosition = switchPosition;
@ -29,6 +39,8 @@ static void read_control_switch() @@ -29,6 +39,8 @@ static void read_control_switch()
reset_I();
}
switch_debouncer = false;
if (g.inverted_flight_ch != 0) {
// if the user has configured an inverted flight channel, then
// fly upside down when that channel goes above INVERTED_FLIGHT_PWM

Loading…
Cancel
Save