From bdb9f062ae78f59da68a5efd625ed567c931cb89 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 20 Jan 2018 10:05:19 +1100 Subject: [PATCH] AP_Motors: removed unused pwm parameters for heli --- libraries/AP_Motors/AP_MotorsHeli_Dual.cpp | 22 ---------------------- libraries/AP_Motors/AP_MotorsHeli_Quad.cpp | 21 --------------------- libraries/AP_Motors/AP_MotorsHeli_RSC.h | 4 ---- 3 files changed, 47 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp index 837f7d442e..514186cdf6 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp @@ -123,28 +123,6 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = { // @Increment: 0.1 AP_GROUPINFO("YAW_SCALER", 12, AP_MotorsHeli_Dual, _yaw_scaler, 1.0f), - // @Param: RSC_PWM_MIN - // @DisplayName: RSC PWM output miniumum - // @Description: This sets the PWM output on RSC channel for maximum rotor speed - // @Range: 0 2000 - // @User: Standard - AP_GROUPINFO("RSC_PWM_MIN", 13, AP_MotorsHeli_Dual, _rotor._pwm_min, 1000), - - // @Param: RSC_PWM_MAX - // @DisplayName: RSC PWM output maxiumum - // @Description: This sets the PWM output on RSC channel for miniumum rotor speed - // @Range: 0 2000 - // @User: Standard - AP_GROUPINFO("RSC_PWM_MAX", 14, AP_MotorsHeli_Dual, _rotor._pwm_max, 2000), - - // @Param: RSC_PWM_REV - // @DisplayName: RSC PWM reversal - // @Description: This controls reversal of the RSC channel output - // @Values: -1:Reversed,1:Normal - // @User: Standard - AP_GROUPINFO("RSC_PWM_REV", 15, AP_MotorsHeli_Dual, _rotor._pwm_rev, 1), - - // @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 e7062221fc..ccb36db913 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp @@ -23,27 +23,6 @@ extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_MotorsHeli_Quad::var_info[] = { AP_NESTEDGROUPINFO(AP_MotorsHeli, 0), - // @Param: RSC_PWM_MIN - // @DisplayName: RSC PWM output miniumum - // @Description: This sets the PWM output on RSC channel for maximum rotor speed - // @Range: 0 2000 - // @User: Standard - AP_GROUPINFO("RSC_PWM_MIN", 1, AP_MotorsHeli_Quad, _rotor._pwm_min, 1000), - - // @Param: RSC_PWM_MAX - // @DisplayName: RSC PWM output maxiumum - // @Description: This sets the PWM output on RSC channel for miniumum rotor speed - // @Range: 0 2000 - // @User: Standard - AP_GROUPINFO("RSC_PWM_MAX", 2, AP_MotorsHeli_Quad, _rotor._pwm_max, 2000), - - // @Param: RSC_PWM_REV - // @DisplayName: RSC PWM reversal - // @Description: This controls reversal of the RSC channel output - // @Values: -1:Reversed,1:Normal - // @User: Standard - AP_GROUPINFO("RSC_PWM_REV", 3, AP_MotorsHeli_Quad, _rotor._pwm_rev, 1), - AP_GROUPEND }; diff --git a/libraries/AP_Motors/AP_MotorsHeli_RSC.h b/libraries/AP_Motors/AP_MotorsHeli_RSC.h index b7a0280f22..0013535d92 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_RSC.h +++ b/libraries/AP_Motors/AP_MotorsHeli_RSC.h @@ -103,10 +103,6 @@ private: uint16_t _power_slewrate = 0; // slewrate for throttle (percentage per second) float _load_feedforward = 0.0f; // estimate of motor load, range 0-1.0f - AP_Int16 _pwm_min; - AP_Int16 _pwm_max; - AP_Int8 _pwm_rev; - // update_rotor_ramp - slews rotor output scalar between 0 and 1, outputs float scalar to _rotor_ramp_output void update_rotor_ramp(float rotor_ramp_input, float dt);