AC_PosControl: Add MAX(bla,0) because safe_sqrt isn't safe

This commit is contained in:
Leonard Hall 2021-07-21 14:23:47 +09:30 committed by Andrew Tridgell
parent 6606ab4996
commit 730ac9cb20

View File

@ -1187,7 +1187,9 @@ float AC_PosControl::crosstrack_error() const
// crosstrack is the horizontal distance to the closest point to the current track
const Vector2f vel_unit = _vel_desired.xy().normalized();
const float dot_error = pos_error * vel_unit;
return safe_sqrt(pos_error.length_squared() - sq(dot_error));
// todo: remove MAX of zero when safe_sqrt fixed
return safe_sqrt(MAX(pos_error.length_squared() - sq(dot_error), 0.0));
}
}