mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Math: compiler warnings: apply is_equal(float)
This commit is contained in:
parent
c93c773de2
commit
ac4e7b2b03
@ -113,13 +113,13 @@ Vector2<T> Vector2<T>::operator -(void) const
|
||||
template <typename T>
|
||||
bool Vector2<T>::operator ==(const Vector2<T> &v) const
|
||||
{
|
||||
return (x==v.x && y==v.y);
|
||||
return (AP_Math::is_equal(x,v.x) && AP_Math::is_equal(y,v.y));
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
bool Vector2<T>::operator !=(const Vector2<T> &v) const
|
||||
{
|
||||
return (x!=v.x || y!=v.y);
|
||||
return (!AP_Math::is_equal(x,v.x) || !AP_Math::is_equal(y,v.y));
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
|
@ -327,13 +327,13 @@ Vector3<T> Vector3<T>::operator -(void) const
|
||||
template <typename T>
|
||||
bool Vector3<T>::operator ==(const Vector3<T> &v) const
|
||||
{
|
||||
return (x==v.x && y==v.y && z==v.z);
|
||||
return (AP_Math::is_equal(x,v.x) && AP_Math::is_equal(y,v.y) && AP_Math::is_equal(z,v.z));
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
bool Vector3<T>::operator !=(const Vector3<T> &v) const
|
||||
{
|
||||
return (x!=v.x || y!=v.y || z!=v.z);
|
||||
return (!AP_Math::is_equal(x,v.x) || !AP_Math::is_equal(y,v.y) || !AP_Math::is_equal(z,v.z));
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
|
Loading…
Reference in New Issue
Block a user