mirror of https://github.com/ArduPilot/ardupilot
APM_Control: add function to relax rover i terms
This commit is contained in:
parent
ba3d1bc6c7
commit
49ec059420
|
@ -748,3 +748,11 @@ float AR_AttitudeControl::get_stopping_distance(float speed) const
|
|||
// assume linear deceleration
|
||||
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();
|
||||
}
|
||||
|
|
|
@ -139,6 +139,9 @@ public:
|
|||
// parameter var table
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
// relax I terms of throttle and steering controllers
|
||||
void relax_I();
|
||||
|
||||
private:
|
||||
|
||||
// external references
|
||||
|
|
Loading…
Reference in New Issue