mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
ArduCopter: increase CONTROL_SWITCH_COUNTER so that flight mode switch must be changed for at least 1/10th of a second
This commit is contained in:
parent
072ffec493
commit
6da07ef1d2
@ -1,6 +1,6 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#define CONTROL_SWITCH_COUNTER 5 // 5 iterations (1/10th of a second) at a new switch position will cause flight mode change
|
||||
#define CONTROL_SWITCH_COUNTER 10 // 10 iterations at 100hz (i.e. 1/10th of a second) at a new switch position will cause flight mode change
|
||||
static void read_control_switch()
|
||||
{
|
||||
static uint8_t switch_counter = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user