diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index abc806a0f2..498d1086ed 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -139,7 +139,7 @@ public: k_param_optflow_enabled, k_param_low_voltage, k_param_ch7_option, - k_param_auto_slew_rate, + k_param_auto_slew_rate, // deprecated - can be deleted k_param_sonar_type, k_param_super_simple = 155, k_param_axis_enabled = 157, @@ -339,7 +339,6 @@ public: AP_Int8 frame_orientation; AP_Int8 ch7_option; AP_Int8 ch8_option; - AP_Int16 auto_slew_rate; #if FRAME_CONFIG == HELI_FRAME // Heli diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 70b30c2114..da5bf66e53 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -419,15 +419,6 @@ const AP_Param::Info var_info[] PROGMEM = { // @User: Standard GSCALAR(ch8_option, "CH8_OPT", CH8_OPTION), - // @Param: AUTO_SLEW - // @DisplayName: Auto Slew Rate - // @Description: This restricts the rate of change of the roll and pitch attitude commanded by the auto pilot - // @Units: Degrees/Second - // @Range: 1 90 - // @Increment: 1 - // @User: Advanced - GSCALAR(auto_slew_rate, "AUTO_SLEW", AUTO_SLEW_RATE), - #if FRAME_CONFIG == HELI_FRAME GGROUP(heli_servo_1, "HS1_", RC_Channel), GGROUP(heli_servo_2, "HS2_", RC_Channel), diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 4a4dd8961f..8f83916152 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -882,10 +882,6 @@ ////////////////////////////////////////////////////////////////////////////// // Autopilot rotate rate limits // -#ifndef AUTO_SLEW_RATE - # define AUTO_SLEW_RATE 45 // degrees/sec -#endif - #ifndef AUTO_YAW_SLEW_RATE # define AUTO_YAW_SLEW_RATE 60 // degrees/sec #endif