APM_Control: add function to relax rover i terms

This commit is contained in:
IamPete1 2019-01-25 18:58:13 +00:00 committed by Randy Mackay
parent ba3d1bc6c7
commit 49ec059420
2 changed files with 11 additions and 0 deletions

View File

@ -748,3 +748,11 @@ float AR_AttitudeControl::get_stopping_distance(float speed) const
// assume linear deceleration // assume linear deceleration
return 0.5f * sq(speed) / accel_max; return 0.5f * sq(speed) / accel_max;
} }
// relax I terms of throttle and steering controllers
void AR_AttitudeControl::relax_I()
{
_steer_rate_pid.reset_I();
_throttle_speed_pid.reset_I();
_pitch_to_throttle_pid.reset_I();
}

View File

@ -139,6 +139,9 @@ public:
// parameter var table // parameter var table
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];
// relax I terms of throttle and steering controllers
void relax_I();
private: private:
// external references // external references