mirror of https://github.com/ArduPilot/ardupilot
APM_Control: fixed yaw PID reset
This commit is contained in:
parent
90900adf53
commit
bcf6601e4e
|
@ -164,6 +164,7 @@ int32_t AP_YawController::get_servo_out(float scaler, bool disable_integrator)
|
||||||
uint32_t dt = tnow - _last_t;
|
uint32_t dt = tnow - _last_t;
|
||||||
if (_last_t == 0 || dt > 1000) {
|
if (_last_t == 0 || dt > 1000) {
|
||||||
dt = 0;
|
dt = 0;
|
||||||
|
_pid_info.I = 0;
|
||||||
}
|
}
|
||||||
_last_t = tnow;
|
_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()
|
void AP_YawController::reset_I()
|
||||||
{
|
{
|
||||||
_integrator = 0.0;
|
_pid_info.I = 0;
|
||||||
_pid_info.I = 0.0;
|
rate_pid.reset_I();
|
||||||
|
_integrator = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void AP_YawController::reset_rate_PID()
|
||||||
|
{
|
||||||
|
rate_pid.reset_I();
|
||||||
|
rate_pid.reset_filter();
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -26,6 +26,8 @@ public:
|
||||||
|
|
||||||
void reset_I();
|
void reset_I();
|
||||||
|
|
||||||
|
void reset_rate_PID();
|
||||||
|
|
||||||
/*
|
/*
|
||||||
reduce the integrator, used when we have a low scale factor in a quadplane hover
|
reduce the integrator, used when we have a low scale factor in a quadplane hover
|
||||||
*/
|
*/
|
||||||
|
@ -43,6 +45,7 @@ public:
|
||||||
// start/stop auto tuner
|
// start/stop auto tuner
|
||||||
void autotune_start(void);
|
void autotune_start(void);
|
||||||
void autotune_restore(void);
|
void autotune_restore(void);
|
||||||
|
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue