mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-11 10:23:59 -04:00
APM_Control: fill in Act field of PID logs for plane
This commit is contained in:
parent
557a20eaa7
commit
d7f90963ea
@ -187,6 +187,7 @@ int32_t AP_PitchController::_get_rate_out(float desired_rate, float scaler, bool
|
|||||||
_pid_info.D = rate_error * gains.D * scaler;
|
_pid_info.D = rate_error * gains.D * scaler;
|
||||||
_last_out = _pid_info.D + _pid_info.FF + _pid_info.P;
|
_last_out = _pid_info.D + _pid_info.FF + _pid_info.P;
|
||||||
_pid_info.desired = desired_rate;
|
_pid_info.desired = desired_rate;
|
||||||
|
_pid_info.actual = achieved_rate;
|
||||||
|
|
||||||
if (autotune.running && aspeed > aparm.airspeed_min) {
|
if (autotune.running && aspeed > aparm.airspeed_min) {
|
||||||
// let autotune have a go at the values
|
// let autotune have a go at the values
|
||||||
@ -336,4 +337,4 @@ int32_t AP_PitchController::get_servo_out(int32_t angle_err, float scaler, bool
|
|||||||
void AP_PitchController::reset_I()
|
void AP_PitchController::reset_I()
|
||||||
{
|
{
|
||||||
_pid_info.I = 0;
|
_pid_info.I = 0;
|
||||||
}
|
}
|
||||||
|
@ -161,6 +161,7 @@ int32_t AP_RollController::_get_rate_out(float desired_rate, float scaler, bool
|
|||||||
_pid_info.P = desired_rate * kp_ff * scaler;
|
_pid_info.P = desired_rate * kp_ff * scaler;
|
||||||
_pid_info.FF = desired_rate * k_ff * scaler;
|
_pid_info.FF = desired_rate * k_ff * scaler;
|
||||||
_pid_info.desired = desired_rate;
|
_pid_info.desired = desired_rate;
|
||||||
|
_pid_info.actual = achieved_rate;
|
||||||
|
|
||||||
_last_out = _pid_info.FF + _pid_info.P + _pid_info.D;
|
_last_out = _pid_info.FF + _pid_info.P + _pid_info.D;
|
||||||
|
|
||||||
|
@ -147,6 +147,8 @@ int32_t AP_SteerController::get_steering_out_rate(float desired_rate)
|
|||||||
if (_reverse) {
|
if (_reverse) {
|
||||||
yaw_rate_earth *= -1.0f;
|
yaw_rate_earth *= -1.0f;
|
||||||
}
|
}
|
||||||
|
_pid_info.actual = yaw_rate_earth;
|
||||||
|
|
||||||
float rate_error = (desired_rate - yaw_rate_earth) * scaler;
|
float rate_error = (desired_rate - yaw_rate_earth) * scaler;
|
||||||
|
|
||||||
// Calculate equivalent gains so that values for K_P and K_I can be taken across from the old PID law
|
// Calculate equivalent gains so that values for K_P and K_I can be taken across from the old PID law
|
||||||
|
Loading…
Reference in New Issue
Block a user