From 8043c0f6383fe6a688a543a9fc2da06a44bb6e0e Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 1 Dec 2017 10:54:45 +0900 Subject: [PATCH] Rover: reduce arming delay to 2 sec --- APMrover2/config.h | 3 +++ APMrover2/radio.cpp | 4 ++-- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/APMrover2/config.h b/APMrover2/config.h index 00b99e8e6c..0eba1fe193 100644 --- a/APMrover2/config.h +++ b/APMrover2/config.h @@ -60,6 +60,9 @@ #define MAV_SYSTEM_ID 1 #endif +#ifndef ARM_DELAY_MS + #define ARM_DELAY_MS 2000 +#endif ////////////////////////////////////////////////////////////////////////////// // FrSky telemetry support diff --git a/APMrover2/radio.cpp b/APMrover2/radio.cpp index 1e34b57e59..95ea17a71a 100644 --- a/APMrover2/radio.cpp +++ b/APMrover2/radio.cpp @@ -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; }