From f3237b9e5da302d120bcc54cdda84ac5c52c0057 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 2 Jul 2013 14:50:04 +1000 Subject: [PATCH] Plane: update FS_LONG_ACTN and FS_SHORT_ACTN docs thanks to Craig for noticing this --- ArduPlane/Parameters.pde | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde index fd68540211..1aa3c8ec44 100644 --- a/ArduPlane/Parameters.pde +++ b/ArduPlane/Parameters.pde @@ -347,15 +347,15 @@ const AP_Param::Info var_info[] PROGMEM = { // @Param: FS_SHORT_ACTN // @DisplayName: Short failsafe action - // @Description: The action to take on a short (1 second) failsafe event - // @Values: 0:None,1:ReturnToLaunch + // @Description: The action to take on a short (1.5 seconds) failsafe event in AUTO, GUIDED or LOITER modes. A short failsafe event in stabilization modes will always cause a change to CIRCLE mode. In AUTO mode you can choose whether it will RTL (ReturnToLaunch) or continue with the mission. If FS_SHORT_ACTN is 0 then it will continue with the mission, if it is 1 then it will enter CIRCLE mode, and then enter RTL if the failsafe condition persists for 20 seconds. + // @Values: 0:Continue,1:Circle/ReturnToLaunch // @User: Standard GSCALAR(short_fs_action, "FS_SHORT_ACTN", SHORT_FAILSAFE_ACTION), // @Param: FS_LONG_ACTN // @DisplayName: Long failsafe action - // @Description: The action to take on a long (20 second) failsafe event - // @Values: 0:None,1:ReturnToLaunch + // @Description: The action to take on a long (20 second) failsafe event in AUTO, GUIDED or LOITER modes. A long failsafe event in stabilization modes will always cause an RTL (ReturnToLaunch). In AUTO modes you can choose whether it will RTL or continue with the mission. If FS_LONG_ACTN is 0 then it will continue with the mission, if it is 1 then it will enter RTL mode. Note that if FS_SHORT_ACTN is 1, then the aircraft will enter CIRCLE mode after 1.5 seconds of failsafe, and will always enter RTL after 20 seconds of failsafe, regardless of the FS_LONG_ACTN setting. + // @Values: 0:Continue,1:ReturnToLaunch // @User: Standard GSCALAR(long_fs_action, "FS_LONG_ACTN", LONG_FAILSAFE_ACTION),