Browse Source

Rover: reduce arming delay to 2 sec

mission-4.1.18
Randy Mackay 7 years ago
parent
commit
8043c0f638
  1. 3
      APMrover2/config.h
  2. 4
      APMrover2/radio.cpp

3
APMrover2/config.h

@ -60,6 +60,9 @@ @@ -60,6 +60,9 @@
#define MAV_SYSTEM_ID 1
#endif
#ifndef ARM_DELAY_MS
#define ARM_DELAY_MS 2000
#endif
//////////////////////////////////////////////////////////////////////////////
// FrSky telemetry support

4
APMrover2/radio.cpp

@ -64,7 +64,7 @@ void Rover::rudder_arm_disarm_check() @@ -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() @@ -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…
Cancel
Save