mirror of https://github.com/ArduPilot/ardupilot
attempt to change from 1/10th second to 2/10th second on flight mode switch
This commit is contained in:
parent
53bff2b63e
commit
07ca8ef87a
|
@ -1,6 +1,6 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
|
||||||
#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
|
#define CONTROL_SWITCH_COUNTER 20 // 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 void read_control_switch()
|
||||||
{
|
{
|
||||||
static uint8_t switch_counter = 0;
|
static uint8_t switch_counter = 0;
|
||||||
|
|
Loading…
Reference in New Issue