From fa36b563bc6bee811d9896f20b7b0b9b96a3a6ab Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 14 Oct 2016 14:00:59 +0900 Subject: [PATCH] Copter: add advanced failsafe enable to APM_Config No functional change --- ArduCopter/APM_Config.h | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 4965f3995c..173623fed3 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -42,6 +42,7 @@ // features below are disabled by default on all boards //#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes //#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE // disable mode changes from GCS during Radio failsafes. Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link +//#define ADVANCED_FAILSAFE ENABLED // enabled advanced failsafe which allows running a portion of the mission in failsafe events // other settings //#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000)