Sub: Remove (unused) PHLD parameters

This commit is contained in:
Jacob Walser 2016-11-25 20:12:10 -05:00 committed by Andrew Tridgell
parent ae4e53fc3f
commit 9aa05e1195
3 changed files with 0 additions and 29 deletions

View File

@ -495,24 +495,6 @@ const AP_Param::Info Sub::var_info[] = {
// @Values: 0:Very Soft, 25:Soft, 50:Medium, 75:Crisp, 100:Very Crisp // @Values: 0:Very Soft, 25:Soft, 50:Medium, 75:Crisp, 100:Very Crisp
GSCALAR(rc_feel_rp, "RC_FEEL_RP", RC_FEEL_RP_MEDIUM), GSCALAR(rc_feel_rp, "RC_FEEL_RP", RC_FEEL_RP_MEDIUM),
#if POSHOLD_ENABLED == ENABLED
// @Param: PHLD_BRAKE_RATE
// @DisplayName: PosHold braking rate
// @Description: PosHold flight mode's rotation rate during braking in deg/sec
// @Units: deg/sec
// @Range: 4 12
// @User: Advanced
GSCALAR(poshold_brake_rate, "PHLD_BRAKE_RATE", POSHOLD_BRAKE_RATE_DEFAULT),
// @Param: PHLD_BRAKE_ANGLE
// @DisplayName: PosHold braking angle max
// @Description: PosHold flight mode's max lean angle during braking in centi-degrees
// @Units: Centi-degrees
// @Range: 2000 4500
// @User: Advanced
GSCALAR(poshold_brake_angle_max, "PHLD_BRAKE_ANGLE", POSHOLD_BRAKE_ANGLE_DEFAULT),
#endif
// @Param: LAND_REPOSITION // @Param: LAND_REPOSITION
// @DisplayName: Land repositioning // @DisplayName: Land repositioning
// @Description: Enables user input during LAND mode, the landing phase of RTL, and auto mode landings. // @Description: Enables user input during LAND mode, the landing phase of RTL, and auto mode landings.

View File

@ -94,8 +94,6 @@ public:
k_param_rc_13, k_param_rc_13,
k_param_rc_14, k_param_rc_14,
k_param_rally, k_param_rally,
k_param_poshold_brake_rate,
k_param_poshold_brake_angle_max,
k_param_pilot_accel_z, k_param_pilot_accel_z,
k_param_land_repositioning, k_param_land_repositioning,
k_param_rangefinder, // rangefinder object k_param_rangefinder, // rangefinder object
@ -329,9 +327,6 @@ public:
AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions
AP_Int8 rc_feel_rp; // controls vehicle response to user input with 0 being extremely soft and 100 begin extremely crisp AP_Int8 rc_feel_rp; // controls vehicle response to user input with 0 being extremely soft and 100 begin extremely crisp
AP_Int16 poshold_brake_rate; // PosHold flight mode's rotation rate during braking in deg/sec
AP_Int16 poshold_brake_angle_max; // PosHold flight mode's max lean angle during braking in centi-degrees
// Waypoints // Waypoints
// //

View File

@ -516,12 +516,6 @@
#ifndef POSHOLD_ENABLED #ifndef POSHOLD_ENABLED
# define POSHOLD_ENABLED ENABLED // PosHold flight mode enabled by default # define POSHOLD_ENABLED ENABLED // PosHold flight mode enabled by default
#endif #endif
#ifndef POSHOLD_BRAKE_RATE_DEFAULT
# define POSHOLD_BRAKE_RATE_DEFAULT 8 // default POSHOLD_BRAKE_RATE param value. Rotation rate during braking in deg/sec
#endif
#ifndef POSHOLD_BRAKE_ANGLE_DEFAULT
# define POSHOLD_BRAKE_ANGLE_DEFAULT 3000 // default POSHOLD_BRAKE_ANGLE param value. Max lean angle during braking in centi-degrees
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Throttle control gains // Throttle control gains