mirror of https://github.com/ArduPilot/ardupilot
APM_Control: fixed yaw PID reset
This commit is contained in:
parent
dabd9fbddc
commit
822c26f811
|
@ -164,6 +164,7 @@ int32_t AP_YawController::get_servo_out(float scaler, bool disable_integrator)
|
|||
uint32_t dt = tnow - _last_t;
|
||||
if (_last_t == 0 || dt > 1000) {
|
||||
dt = 0;
|
||||
_pid_info.I = 0;
|
||||
}
|
||||
_last_t = tnow;
|
||||
|
||||
|
@ -343,8 +344,15 @@ float AP_YawController::get_rate_out(float desired_rate, float scaler, bool disa
|
|||
|
||||
void AP_YawController::reset_I()
|
||||
{
|
||||
_integrator = 0.0;
|
||||
_pid_info.I = 0.0;
|
||||
_pid_info.I = 0;
|
||||
rate_pid.reset_I();
|
||||
_integrator = 0;
|
||||
}
|
||||
|
||||
void AP_YawController::reset_rate_PID()
|
||||
{
|
||||
rate_pid.reset_I();
|
||||
rate_pid.reset_filter();
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -29,6 +29,8 @@ public:
|
|||
|
||||
void reset_I();
|
||||
|
||||
void reset_rate_PID();
|
||||
|
||||
/*
|
||||
reduce the integrator, used when we have a low scale factor in a quadplane hover
|
||||
*/
|
||||
|
@ -47,6 +49,7 @@ public:
|
|||
void autotune_start(void);
|
||||
void autotune_restore(void);
|
||||
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
|
|
Loading…
Reference in New Issue