diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp index 514186cdf6..90f8257345 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp @@ -123,6 +123,8 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = { // @Increment: 0.1 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 + // @Param: COL2_MIN // @DisplayName: Collective Pitch Minimum for rear swashplate // @Description: Lowest possible servo position in PWM microseconds for the rear swashplate diff --git a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp index ccb36db913..8ab075ebdd 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp @@ -23,6 +23,8 @@ extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_MotorsHeli_Quad::var_info[] = { AP_NESTEDGROUPINFO(AP_MotorsHeli, 0), + // Indices 1-3 were used by RSC_PWM_MIN, RSC_PWM_MAX and RSC_PWM_REV and should not be used + AP_GROUPEND }; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index c111f437f2..37af8f4c53 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -116,6 +116,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = { // @User: Standard AP_GROUPINFO("GYR_GAIN_ACRO", 11, AP_MotorsHeli_Single, _ext_gyro_gain_acro, 0), + // Indices 16-18 were used by RSC_PWM_MIN, RSC_PWM_MAX and RSC_PWM_REV and should not be used // parameters up to and including 29 are reserved for tradheli AP_GROUPEND