diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index 8a707e0f97..ef9c75e1ad 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -152,7 +152,7 @@ const AP_Param::Info Rover::var_info[] = { // @Param: FS_ACTION // @DisplayName: Failsafe Action // @Description: What to do on a failsafe event - // @Values: 0:Nothing,1:RTL,2:HOLD + // @Values: 0:Nothing,1:RTL,2:Hold // @User: Standard GSCALAR(fs_action, "FS_ACTION", 2), @@ -188,7 +188,7 @@ const AP_Param::Info Rover::var_info[] = { // @Param: FS_CRASH_CHECK // @DisplayName: Crash check action // @Description: What to do on a crash event. When enabled the rover will go to hold if a crash is detected. - // @Values: 0:Disabled,1:HOLD,2:HoldAndDisarm + // @Values: 0:Disabled,1:Hold,2:HoldAndDisarm // @User: Standard GSCALAR(fs_crash_check, "FS_CRASH_CHECK", FS_CRASH_DISABLE), diff --git a/APMrover2/crash_check.cpp b/APMrover2/crash_check.cpp index 69a94f6d59..6fe39b3e8d 100644 --- a/APMrover2/crash_check.cpp +++ b/APMrover2/crash_check.cpp @@ -12,7 +12,7 @@ void Rover::crash_check() { static uint16_t crash_counter; // number of iterations vehicle may have been crashed - // return immediately if disarmed, or crash checking disabled or in HOLD mode + // return immediately if disarmed, crash checking is disabled or vehicle is Hold, Manual or Acro mode if (!arming.is_armed() || g.fs_crash_check == FS_CRASH_DISABLE || (!control_mode->is_autopilot_mode())) { crash_counter = 0; return;