From f8aa91681ed845a9c3ac46743c900547ad20be1a Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar Do Carmo Lucas" Date: Tue, 16 May 2017 01:16:12 +0200 Subject: [PATCH] Copter: Improve the PWM parameters descriptions --- ArduCopter/Parameters.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index a43fe97cad..6f783dbdcd 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -287,7 +287,7 @@ const AP_Param::Info Copter::var_info[] = { // @Param: FS_THR_VALUE // @DisplayName: Throttle Failsafe Value - // @Description: The PWM level on channel 3 below which throttle failsafe triggers + // @Description: The PWM level in microseconds on channel 3 below which throttle failsafe triggers // @Range: 925 1100 // @Units: PWM // @Increment: 1 @@ -296,7 +296,7 @@ const AP_Param::Info Copter::var_info[] = { // @Param: THR_DZ // @DisplayName: Throttle deadzone - // @Description: The deadzone above and below mid throttle. Used in AltHold, Loiter, PosHold flight modes + // @Description: The deadzone above and below mid throttle in PWM microseconds. Used in AltHold, Loiter, PosHold flight modes // @User: Standard // @Range: 0 300 // @Units: PWM