mirror of https://github.com/ArduPilot/ardupilot
AC_PID: replace is_equal with is_zero
This commit is contained in:
parent
3514177314
commit
67b0c6f5c4
|
@ -132,7 +132,7 @@ float AC_PID::get_p() const
|
|||
|
||||
float AC_PID::get_i()
|
||||
{
|
||||
if(!is_equal(_ki, 0.0f) && !is_equal(_dt, 0.0f)) {
|
||||
if(!is_zero(_ki) && !is_zero(_dt)) {
|
||||
_integrator += ((float)_input * _ki) * _dt;
|
||||
if (_integrator < -_imax) {
|
||||
_integrator = -_imax;
|
||||
|
@ -199,7 +199,7 @@ void AC_PID::operator() (float p, float i, float d, float imaxval, float input_f
|
|||
// calc_filt_alpha - recalculate the input filter alpha
|
||||
float AC_PID::get_filt_alpha() const
|
||||
{
|
||||
if (is_equal(_filt_hz, 0.0f)) {
|
||||
if (is_zero(_filt_hz)) {
|
||||
return 1.0f;
|
||||
}
|
||||
|
||||
|
|
|
@ -95,7 +95,7 @@ Vector2f AC_PI_2D::get_p() const
|
|||
|
||||
Vector2f AC_PI_2D::get_i()
|
||||
{
|
||||
if(!is_equal(_ki, 0.0f) && !is_equal(_dt, 0.0f)) {
|
||||
if(!is_zero(_ki) && !is_zero(_dt)) {
|
||||
_integrator += (_input * _ki) * _dt;
|
||||
float integrator_length = _integrator.length();
|
||||
if ((integrator_length > _imax) && (integrator_length > 0)) {
|
||||
|
@ -109,7 +109,7 @@ Vector2f AC_PI_2D::get_i()
|
|||
// get_i_shrink - get_i but do not allow integrator to grow in length (it may shrink)
|
||||
Vector2f AC_PI_2D::get_i_shrink()
|
||||
{
|
||||
if (!is_equal(_ki, 0.0f) && !is_equal(_dt, 0.0f)) {
|
||||
if (!is_zero(_ki) && !is_zero(_dt)) {
|
||||
float integrator_length_orig = min(_integrator.length(),_imax);
|
||||
_integrator += (_input * _ki) * _dt;
|
||||
float integrator_length_new = _integrator.length();
|
||||
|
@ -167,7 +167,7 @@ void AC_PI_2D::operator() (float p, float i, float imaxval, float input_filt_hz,
|
|||
// calc_filt_alpha - recalculate the input filter alpha
|
||||
void AC_PI_2D::calc_filt_alpha()
|
||||
{
|
||||
if (is_equal(_filt_hz, 0.0f)) {
|
||||
if (is_zero(_filt_hz)) {
|
||||
_filt_alpha = 1.0f;
|
||||
return;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue