From ded334016fa0371c5e21d3cd661f7355f9ae7b77 Mon Sep 17 00:00:00 2001 From: bnsgeyer Date: Sun, 17 Nov 2019 22:33:44 -0500 Subject: [PATCH] AP_Motors: tradheli- fix metadata --- libraries/AP_Motors/AP_MotorsHeli.cpp | 2 +- libraries/AP_Motors/AP_MotorsHeli_Dual.cpp | 2 ++ libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 2 +- 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index c342a19014..0473cd8f0d 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -81,7 +81,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = { // @Range: 0 18000 // @Units: cdeg // @Increment: 100 - // @User: Advanced + // @User: Standard AP_GROUPINFO("CYC_MAX", 16, AP_MotorsHeli, _cyclic_max, AP_MOTORS_HELI_SWASH_CYCLIC_MAX), // @Param: SV_TEST diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp index 38a8da1844..e6ce52841f 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp @@ -46,6 +46,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = { // @Description: Feed-forward compensation to automatically add yaw input when differential collective pitch is applied. // @Range: -10 10 // @Increment: 0.1 + // @User: Standard AP_GROUPINFO("DCP_YAW", 11, AP_MotorsHeli_Dual, _dcp_yaw_effect, 0), // @Param: YAW_SCALER @@ -53,6 +54,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = { // @Description: Scaler for mixing yaw into roll or pitch. // @Range: -10 10 // @Increment: 0.1 + // @User: Standard AP_GROUPINFO("YAW_SCALER", 12, AP_MotorsHeli_Dual, _yaw_scaler, 1.0f), // Indices 13-15 were used by RSC_PWM_MIN, RSC_PWM_MAX and RSC_PWM_REV and should not be used diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index b75df63809..24989d2f10 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -51,7 +51,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = { // @Description: Feed-forward compensation to automatically add rudder input when collective pitch is increased. Can be positive or negative depending on mechanics. // @Range: -10 10 // @Increment: 0.1 - // @User: Advanced + // @User: Standard AP_GROUPINFO("COLYAW", 8, AP_MotorsHeli_Single, _collective_yaw_effect, 0), // @Param: FLYBAR_MODE