From 19a5b38ff57f315b96f9c1052a67305b7f30903d Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Sun, 20 Aug 2017 13:42:31 -0400 Subject: [PATCH] Sub: Default FS_PILOT_TIMEOUT to 3 seconds --- ArduSub/Parameters.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 3e9dbbbdaf..cae27da139 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -179,7 +179,7 @@ const AP_Param::Info Sub::var_info[] = { // @Units: s // @Range: 0.1 3.0 // @User: Standard - GSCALAR(failsafe_pilot_input_timeout, "FS_PILOT_TIMEOUT", 1.0f), + GSCALAR(failsafe_pilot_input_timeout, "FS_PILOT_TIMEOUT", 3.0f), // @Param: XTRACK_ANG_LIM // @DisplayName: Crosstrack correction angle limit