From 3e399fd830ddb510fbb928d0719eced433228c6e Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 3 Feb 2014 16:39:43 +0900 Subject: [PATCH] Copter: remove unused parameters --- ArduCopter/Parameters.h | 18 +++++--------- ArduCopter/Parameters.pde | 51 +-------------------------------------- 2 files changed, 7 insertions(+), 62 deletions(-) diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 2c2e31f995..bc459620c7 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -86,7 +86,7 @@ public: k_param_wp_yaw_behavior, k_param_acro_trainer, k_param_pilot_velocity_z_max, - k_param_circle_rate, + k_param_circle_rate, // deprecated - remove k_param_sonar_gain, k_param_ch8_option, k_param_arming_check, @@ -95,7 +95,7 @@ public: k_param_gps_hdop_good, k_param_battery, k_param_fs_batt_mah, - k_param_angle_rate_max, + k_param_angle_rate_max, // remove k_param_rssi_range, k_param_rc_feel_rp, // 40 @@ -122,9 +122,9 @@ public: k_param_heli_servo_2, k_param_heli_servo_3, k_param_heli_servo_4, - k_param_heli_pitch_ff, - k_param_heli_roll_ff, - k_param_heli_yaw_ff, + k_param_heli_pitch_ff, // remove + k_param_heli_roll_ff, // remove + k_param_heli_yaw_ff, // remove k_param_heli_stab_col_min, k_param_heli_stab_col_max, // 88 @@ -250,7 +250,7 @@ public: k_param_command_index, k_param_command_nav_index, // remove k_param_waypoint_radius, // remove - k_param_circle_radius, + k_param_circle_radius, // remove k_param_waypoint_speed_max, // remove k_param_land_speed, k_param_auto_velocity_z_min, // remove @@ -323,15 +323,12 @@ public: AP_Int8 rssi_pin; AP_Float rssi_range; // allows to set max voltage for rssi pin such as 5.0, 3.3 etc. AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions - AP_Int32 angle_rate_max; // maximum rotation rate in roll/pitch axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes AP_Int8 rc_feel_rp; // controls vehicle response to user input with 0 being extremely soft and 100 begin extremely crisp // Waypoints // AP_Int8 command_total; AP_Int8 command_index; - AP_Int16 circle_radius; - AP_Float circle_rate; // Circle mode's turn rate in deg/s. positive to rotate clockwise, negative for counter clockwise AP_Int32 rtl_loiter_time; AP_Int16 land_speed; AP_Int16 pilot_velocity_z_max; // maximum vertical velocity the pilot may request @@ -371,9 +368,6 @@ public: #if FRAME_CONFIG == HELI_FRAME // Heli RC_Channel heli_servo_1, heli_servo_2, heli_servo_3, heli_servo_4; // servos for swash plate and tail - AP_Float heli_pitch_ff; // pitch rate feed-forward - AP_Float heli_roll_ff; // roll rate feed-forward - AP_Float heli_yaw_ff; // yaw rate feed-forward AP_Int16 heli_stab_col_min; // min collective while pilot directly controls collective in stabilize mode AP_Int16 heli_stab_col_max; // min collective while pilot directly controls collective in stabilize mode #endif diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 00187d6db2..5ce92520a1 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -216,24 +216,6 @@ const AP_Param::Info var_info[] PROGMEM = { // @User: Advanced GSCALAR(command_index, "WP_INDEX", 0), - // @Param: CIRCLE_RADIUS - // @DisplayName: Circle radius - // @Description: Defines the radius of the circle the vehicle will fly when in Circle flight mode - // @Units: Meters - // @Range: 1 127 - // @Increment: 1 - // @User: Standard - GSCALAR(circle_radius, "CIRCLE_RADIUS", CIRCLE_RADIUS), - - // @Param: CIRCLE_RATE - // @DisplayName: Circle rate - // @Description: Circle mode's turn rate in degrees / second. Positive to turn clockwise, negative for counter clockwise - // @Units: deg/s - // @Range: -90 90 - // @Increment: 1 - // @User: Standard - GSCALAR(circle_rate, "CIRCLE_RATE", CIRCLE_RATE), - // @Param: RTL_LOIT_TIME // @DisplayName: RTL loiter time // @Description: Time (in milliseconds) to loiter above home before begining final descent @@ -430,13 +412,6 @@ const AP_Param::Info var_info[] PROGMEM = { // @User: Advanced ASCALAR(angle_max, "ANGLE_MAX", DEFAULT_ANGLE_MAX), - // @Param: ANGLE_RATE_MAX - // @DisplayName: Angle Rate max - // @Description: maximum rotation rate in roll/pitch axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes - // @Range 90000 250000 - // @User: Advanced - GSCALAR(angle_rate_max, "ANGLE_RATE_MAX", ANGLE_RATE_MAX), - // @Param: RC_FEEL_RP // @DisplayName: RC Feel Roll/Pitch // @Description: RC feel for roll/pitch which controls vehicle response to user input with 0 being extremely soft and 100 begin crisp @@ -458,30 +433,6 @@ const AP_Param::Info var_info[] PROGMEM = { // @Path: ../libraries/RC_Channel/RC_Channel.cpp GGROUP(heli_servo_4, "HS4_", RC_Channel), - // @Param: RATE_PIT_FF - // @DisplayName: Rate Pitch Feed Forward - // @Description: Rate Pitch Feed Forward (for TradHeli Only) - // @Range: 0 10 - // @Increment: 0.01 - // @User: Standard - GSCALAR(heli_pitch_ff, "RATE_PIT_FF", HELI_PITCH_FF), - - // @Param: RATE_RLL_FF - // @DisplayName: Rate Roll Feed Forward - // @Description: Rate Roll Feed Forward (for TradHeli Only) - // @Range: 0 10 - // @Increment: 0.01 - // @User: Standard - GSCALAR(heli_roll_ff, "RATE_RLL_FF", HELI_ROLL_FF), - - // @Param: RATE_YAW_FF - // @DisplayName: Rate Yaw Feed Forward - // @Description: Rate Yaw Feed Forward (for TradHeli Only) - // @Range: 0 10 - // @Increment: 0.01 - // @User: Standard - GSCALAR(heli_yaw_ff, "RATE_YAW_FF", HELI_YAW_FF), - // @Param: H_STAB_COL_MIN // @DisplayName: Heli Stabilize Throttle Collective Minimum // @Description: Helicopter's minimum collective position while pilot directly controls collective in stabilize mode @@ -1014,7 +965,7 @@ const AP_Param::Info var_info[] PROGMEM = { #if FRAME_CONFIG == HELI_FRAME // @Group: ATCON_ // @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp - GOBJECT(attitude_control, "ATTCON_", AC_AttitudeControl_Heli), + GOBJECT(attitude_control, "ATC_", AC_AttitudeControl_Heli), #else // @Group: ATCON_ // @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp