mirror of https://github.com/ArduPilot/ardupilot
PID: Change from division to multiplication
This commit is contained in:
parent
82afaf70f6
commit
8f1369f065
|
@ -52,7 +52,7 @@ float PID::get_pid(float error, float scaler)
|
||||||
}
|
}
|
||||||
_last_t = tnow;
|
_last_t = tnow;
|
||||||
|
|
||||||
delta_time = (float)dt / 1000.0f;
|
delta_time = (float)dt * 0.001f;
|
||||||
|
|
||||||
// Compute proportional component
|
// Compute proportional component
|
||||||
_pid_info.P = error * _kp;
|
_pid_info.P = error * _kp;
|
||||||
|
|
Loading…
Reference in New Issue