mirror of https://github.com/ArduPilot/ardupilot
Rover: reduce arming delay to 2 sec
This commit is contained in:
parent
e38cefea8a
commit
8043c0f638
|
@ -60,6 +60,9 @@
|
|||
#define MAV_SYSTEM_ID 1
|
||||
#endif
|
||||
|
||||
#ifndef ARM_DELAY_MS
|
||||
#define ARM_DELAY_MS 2000
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// FrSky telemetry support
|
||||
|
|
|
@ -64,7 +64,7 @@ void Rover::rudder_arm_disarm_check()
|
|||
const uint32_t now = millis();
|
||||
|
||||
if (rudder_arm_timer == 0 ||
|
||||
now - rudder_arm_timer < 3000) {
|
||||
now - rudder_arm_timer < ARM_DELAY_MS) {
|
||||
if (rudder_arm_timer == 0) {
|
||||
rudder_arm_timer = now;
|
||||
}
|
||||
|
@ -83,7 +83,7 @@ void Rover::rudder_arm_disarm_check()
|
|||
const uint32_t now = millis();
|
||||
|
||||
if (rudder_arm_timer == 0 ||
|
||||
now - rudder_arm_timer < 3000) {
|
||||
now - rudder_arm_timer < ARM_DELAY_MS) {
|
||||
if (rudder_arm_timer == 0) {
|
||||
rudder_arm_timer = now;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue