mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AC_CustomControl_PID: set false to avoid hitting limits
This commit is contained in:
parent
bd30f3ede9
commit
1ab985fff8
@ -290,9 +290,9 @@ Vector3f AC_CustomControl_PID::update()
|
|||||||
// run rate controller
|
// run rate controller
|
||||||
Vector3f gyro_latest = _ahrs->get_gyro_latest();
|
Vector3f gyro_latest = _ahrs->get_gyro_latest();
|
||||||
Vector3f motor_out;
|
Vector3f motor_out;
|
||||||
motor_out.x = _pid_atti_rate_roll.update_all(target_rate[0], gyro_latest[0], _dt, true);
|
motor_out.x = _pid_atti_rate_roll.update_all(target_rate[0], gyro_latest[0], _dt, false);
|
||||||
motor_out.y = _pid_atti_rate_pitch.update_all(target_rate[1], gyro_latest[1], _dt, true);
|
motor_out.y = _pid_atti_rate_pitch.update_all(target_rate[1], gyro_latest[1], _dt, false);
|
||||||
motor_out.z = _pid_atti_rate_yaw.update_all(target_rate[2], gyro_latest[2], _dt, true);
|
motor_out.z = _pid_atti_rate_yaw.update_all(target_rate[2], gyro_latest[2], _dt, false);
|
||||||
|
|
||||||
return motor_out;
|
return motor_out;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user