AP_Math: revert AP_Math class change

This commit is contained in:
Andrew Tridgell 2015-05-05 12:35:31 +10:00
parent e6a8a6da07
commit 0b897e04bb
3 changed files with 6 additions and 6 deletions

View File

@ -128,7 +128,7 @@ void location_update(struct Location &loc, float bearing, float distance)
*/
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
{
if (!AP_Math::is_zero(ofs_north) || !AP_Math::is_zero(ofs_east)) {
if (!is_zero(ofs_north) || !is_zero(ofs_east)) {
int32_t dlat = ofs_north * LOCATION_SCALING_FACTOR_INV;
int32_t dlng = (ofs_east * LOCATION_SCALING_FACTOR_INV) / longitude_scale(loc);
loc.lat += dlat;
@ -254,7 +254,7 @@ void wgsecef2llh(const Vector3d &ecef, Vector3d &llh) {
const double p = sqrt(ecef[0]*ecef[0] + ecef[1]*ecef[1]);
/* Compute longitude first, this can be done exactly. */
if (!AP_Math::is_zero(p))
if (!is_zero(p))
llh[1] = atan2(ecef[1], ecef[0]);
else
llh[1] = 0;

View File

@ -113,13 +113,13 @@ Vector2<T> Vector2<T>::operator -(void) const
template <typename T>
bool Vector2<T>::operator ==(const Vector2<T> &v) const
{
return (AP_Math::is_equal(x,v.x) && AP_Math::is_equal(y,v.y));
return (is_equal(x,v.x) && is_equal(y,v.y));
}
template <typename T>
bool Vector2<T>::operator !=(const Vector2<T> &v) const
{
return (!AP_Math::is_equal(x,v.x) || !AP_Math::is_equal(y,v.y));
return (!is_equal(x,v.x) || !is_equal(y,v.y));
}
template <typename T>

View File

@ -327,13 +327,13 @@ Vector3<T> Vector3<T>::operator -(void) const
template <typename T>
bool Vector3<T>::operator ==(const Vector3<T> &v) const
{
return (AP_Math::is_equal(x,v.x) && AP_Math::is_equal(y,v.y) && AP_Math::is_equal(z,v.z));
return (is_equal(x,v.x) && is_equal(y,v.y) && is_equal(z,v.z));
}
template <typename T>
bool Vector3<T>::operator !=(const Vector3<T> &v) const
{
return (!AP_Math::is_equal(x,v.x) || !AP_Math::is_equal(y,v.y) || !AP_Math::is_equal(z,v.z));
return (!is_equal(x,v.x) || !is_equal(y,v.y) || !is_equal(z,v.z));
}
template <typename T>