diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 22a539f203..fb5b9a1f5b 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -354,7 +354,7 @@ const AP_Param::Info Copter::var_info[] = { // @Param: DISARM_DELAY // @DisplayName: Disarm delay - // @Description: Delay before automatic disarm in seconds. A value of zero disables auto disarm. + // @Description: Delay before automatic disarm in seconds after landing touchdown detection. A value of zero disables auto disarm. If Emergency Motor stop active, delay time is half this value. // @Units: s // @Range: 0 127 // @User: Advanced