From b682f3f6d9109431f35b66977bdfd1b7a3588ede Mon Sep 17 00:00:00 2001 From: mirkix Date: Mon, 18 Sep 2017 20:05:45 +0200 Subject: [PATCH] Plane: fix parameter units --- ArduPlane/quadplane.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 58dea0b194..189813553f 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -146,7 +146,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Param: THR_MIN_PWM // @DisplayName: Minimum PWM output // @Description: This is the minimum PWM output for the quad motors - // @Units: Hz + // @Units: PWM // @Range: 800 2200 // @Increment: 1 // @User: Standard @@ -155,7 +155,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Param: THR_MAX_PWM // @DisplayName: Maximum PWM output // @Description: This is the maximum PWM output for the quad motors - // @Units: Hz + // @Units: PWM // @Range: 800 2200 // @Increment: 1 // @User: Standard