AC_AttitudeControl: remove unused variable

This commit is contained in:
Jonathan Challinger 2015-11-25 17:25:51 -08:00 committed by Randy Mackay
parent f8c709478a
commit 9208003aab
1 changed files with 0 additions and 5 deletions

View File

@ -64,7 +64,6 @@ public:
_pid_rate_yaw(pid_rate_yaw), _pid_rate_yaw(pid_rate_yaw),
_dt(AC_ATTITUDE_100HZ_DT), _dt(AC_ATTITUDE_100HZ_DT),
_angle_boost(0), _angle_boost(0),
_acro_angle_switch_rad(0),
_throttle_in_filt(AC_ATTITUDE_CONTROL_ALTHOLD_LEANANGLE_FILT_HZ) _throttle_in_filt(AC_ATTITUDE_CONTROL_ALTHOLD_LEANANGLE_FILT_HZ)
{ {
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);
@ -307,10 +306,6 @@ protected:
// Used only for logging. // Used only for logging.
int16_t _angle_boost; int16_t _angle_boost;
// This provides hysteresis on the attitude controller switching used to account
// for deficiencies in the euler angle based attitude control.
float _acro_angle_switch_rad;
// Specifies whether the attitude controller should use the acceleration limit // Specifies whether the attitude controller should use the acceleration limit
bool _att_ctrl_use_accel_limit; bool _att_ctrl_use_accel_limit;