Skip to content

Commit

Permalink
Add Vector(2|3|4)<T>::NaN to easily create invalid vectors (#222)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
Signed-off-by: Arjo Chakravarty <[email protected]>
  • Loading branch information
chapulina authored and arjo129 committed Sep 20, 2021
1 parent e7eaad6 commit 9739419
Show file tree
Hide file tree
Showing 18 changed files with 261 additions and 8 deletions.
9 changes: 9 additions & 0 deletions include/ignition/math/Vector2.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#define IGNITION_MATH_VECTOR2_HH_

#include <algorithm>
#include <limits>

#include <ignition/math/Helpers.hh>
#include <ignition/math/config.hh>
Expand All @@ -40,6 +41,9 @@ namespace ignition
/// \brief math::Vector2(1, 1)
public: static const Vector2<T> One;

/// \brief math::Vector2(NaN, NaN, NaN)
public: static const Vector2 NaN;

/// \brief Default Constructor
public: Vector2()
{
Expand Down Expand Up @@ -579,6 +583,11 @@ namespace ignition
template<typename T>
const Vector2<T> Vector2<T>::One(1, 1);

template<typename T>
const Vector2<T> Vector2<T>::NaN(
std::numeric_limits<T>::quiet_NaN(),
std::numeric_limits<T>::quiet_NaN());

typedef Vector2<int> Vector2i;
typedef Vector2<double> Vector2d;
typedef Vector2<float> Vector2f;
Expand Down
14 changes: 11 additions & 3 deletions include/ignition/math/Vector3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,11 @@
#ifndef IGNITION_MATH_VECTOR3_HH_
#define IGNITION_MATH_VECTOR3_HH_

#include <iostream>
#include <fstream>
#include <cmath>
#include <algorithm>
#include <cmath>
#include <fstream>
#include <iostream>
#include <limits>

#include <ignition/math/Helpers.hh>
#include <ignition/math/config.hh>
Expand Down Expand Up @@ -54,6 +55,9 @@ namespace ignition
/// \brief math::Vector3(0, 0, 1)
public: static const Vector3 UnitZ;

/// \brief math::Vector3(NaN, NaN, NaN)
public: static const Vector3 NaN;

/// \brief Constructor
public: Vector3()
{
Expand Down Expand Up @@ -765,6 +769,10 @@ namespace ignition
template<typename T> const Vector3<T> Vector3<T>::UnitX(1, 0, 0);
template<typename T> const Vector3<T> Vector3<T>::UnitY(0, 1, 0);
template<typename T> const Vector3<T> Vector3<T>::UnitZ(0, 0, 1);
template<typename T> const Vector3<T> Vector3<T>::NaN(
std::numeric_limits<T>::quiet_NaN(),
std::numeric_limits<T>::quiet_NaN(),
std::numeric_limits<T>::quiet_NaN());

typedef Vector3<int> Vector3i;
typedef Vector3<double> Vector3d;
Expand Down
10 changes: 10 additions & 0 deletions include/ignition/math/Vector4.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#define IGNITION_MATH_VECTOR4_HH_

#include <algorithm>
#include <limits>

#include <ignition/math/Matrix4.hh>
#include <ignition/math/Helpers.hh>
Expand All @@ -41,6 +42,9 @@ namespace ignition
/// \brief math::Vector4(1, 1, 1, 1)
public: static const Vector4<T> One;

/// \brief math::Vector4(NaN, NaN, NaN, NaN)
public: static const Vector4 NaN;

/// \brief Constructor
public: Vector4()
{
Expand Down Expand Up @@ -735,6 +739,12 @@ namespace ignition
template<typename T>
const Vector4<T> Vector4<T>::One(1, 1, 1, 1);

template<typename T> const Vector4<T> Vector4<T>::NaN(
std::numeric_limits<T>::quiet_NaN(),
std::numeric_limits<T>::quiet_NaN(),
std::numeric_limits<T>::quiet_NaN(),
std::numeric_limits<T>::quiet_NaN());

typedef Vector4<int> Vector4i;
typedef Vector4<double> Vector4d;
typedef Vector4<float> Vector4f;
Expand Down
22 changes: 22 additions & 0 deletions src/Vector2_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -443,3 +443,25 @@ TEST(Vector2Test, Length)
EXPECT_EQ(vi.SquaredLength(), 25);
}

/////////////////////////////////////////////////
TEST(Vector2Test, NaN)
{
auto nanVec = math::Vector2d::NaN;
EXPECT_FALSE(nanVec.IsFinite());
EXPECT_TRUE(math::isnan(nanVec.X()));
EXPECT_TRUE(math::isnan(nanVec.Y()));

nanVec.Correct();
EXPECT_EQ(math::Vector2d::Zero, nanVec);
EXPECT_TRUE(nanVec.IsFinite());

auto nanVecF = math::Vector2f::NaN;
EXPECT_FALSE(nanVecF.IsFinite());
EXPECT_TRUE(math::isnan(nanVecF.X()));
EXPECT_TRUE(math::isnan(nanVecF.Y()));

nanVecF.Correct();
EXPECT_EQ(math::Vector2f::Zero, nanVecF);
EXPECT_TRUE(nanVecF.IsFinite());
}

47 changes: 42 additions & 5 deletions src/Vector3_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -125,11 +125,25 @@ TEST(Vector3dTest, Vector3d)
EXPECT_TRUE(v.Equal(math::Vector3d(2, 1, .4)));

// Test the static defines.
EXPECT_TRUE(math::Vector3d::Zero == math::Vector3d(0, 0, 0));
EXPECT_TRUE(math::Vector3d::One == math::Vector3d(1, 1, 1));
EXPECT_TRUE(math::Vector3d::UnitX == math::Vector3d(1, 0, 0));
EXPECT_TRUE(math::Vector3d::UnitY == math::Vector3d(0, 1, 0));
EXPECT_TRUE(math::Vector3d::UnitZ == math::Vector3d(0, 0, 1));
EXPECT_EQ(math::Vector3d::Zero, math::Vector3d(0, 0, 0));
EXPECT_EQ(math::Vector3f::Zero, math::Vector3f(0, 0, 0));
EXPECT_EQ(math::Vector3i::Zero, math::Vector3i(0, 0, 0));

EXPECT_EQ(math::Vector3d::One, math::Vector3d(1, 1, 1));
EXPECT_EQ(math::Vector3f::One, math::Vector3f(1, 1, 1));
EXPECT_EQ(math::Vector3i::One, math::Vector3i(1, 1, 1));

EXPECT_EQ(math::Vector3d::UnitX, math::Vector3d(1, 0, 0));
EXPECT_EQ(math::Vector3f::UnitX, math::Vector3f(1, 0, 0));
EXPECT_EQ(math::Vector3i::UnitX, math::Vector3i(1, 0, 0));

EXPECT_EQ(math::Vector3d::UnitY, math::Vector3d(0, 1, 0));
EXPECT_EQ(math::Vector3f::UnitY, math::Vector3f(0, 1, 0));
EXPECT_EQ(math::Vector3i::UnitY, math::Vector3i(0, 1, 0));

EXPECT_EQ(math::Vector3d::UnitZ, math::Vector3d(0, 0, 1));
EXPECT_EQ(math::Vector3f::UnitZ, math::Vector3f(0, 0, 1));
EXPECT_EQ(math::Vector3i::UnitZ, math::Vector3i(0, 0, 1));
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -479,3 +493,26 @@ TEST(Vector3dTest, NoException)
EXPECT_NO_THROW(ss << vInf);
}

/////////////////////////////////////////////////
TEST(Vector3dTest, NaN)
{
auto nanVec = math::Vector3d::NaN;
EXPECT_FALSE(nanVec.IsFinite());
EXPECT_TRUE(math::isnan(nanVec.X()));
EXPECT_TRUE(math::isnan(nanVec.Y()));
EXPECT_TRUE(math::isnan(nanVec.Z()));

nanVec.Correct();
EXPECT_EQ(math::Vector3d::Zero, nanVec);
EXPECT_TRUE(nanVec.IsFinite());

auto nanVecF = math::Vector3f::NaN;
EXPECT_FALSE(nanVecF.IsFinite());
EXPECT_TRUE(math::isnan(nanVecF.X()));
EXPECT_TRUE(math::isnan(nanVecF.Y()));
EXPECT_TRUE(math::isnan(nanVecF.Z()));

nanVecF.Correct();
EXPECT_EQ(math::Vector3f::Zero, nanVecF);
EXPECT_TRUE(nanVecF.IsFinite());
}
25 changes: 25 additions & 0 deletions src/Vector4_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -443,3 +443,28 @@ TEST(Vector4dTest, Length)
EXPECT_EQ(math::Vector4i::One.SquaredLength(), 4);
}

/////////////////////////////////////////////////
TEST(Vector4Test, NaN)
{
auto nanVec = math::Vector4d::NaN;
EXPECT_FALSE(nanVec.IsFinite());
EXPECT_TRUE(math::isnan(nanVec.X()));
EXPECT_TRUE(math::isnan(nanVec.Y()));
EXPECT_TRUE(math::isnan(nanVec.Z()));
EXPECT_TRUE(math::isnan(nanVec.W()));

nanVec.Correct();
EXPECT_EQ(math::Vector4d::Zero, nanVec);
EXPECT_TRUE(nanVec.IsFinite());

auto nanVecF = math::Vector4f::NaN;
EXPECT_FALSE(nanVecF.IsFinite());
EXPECT_TRUE(math::isnan(nanVecF.X()));
EXPECT_TRUE(math::isnan(nanVecF.Y()));
EXPECT_TRUE(math::isnan(nanVecF.Z()));
EXPECT_TRUE(math::isnan(nanVecF.W()));

nanVecF.Correct();
EXPECT_EQ(math::Vector4f::Zero, nanVecF);
EXPECT_TRUE(nanVecF.IsFinite());
}
1 change: 1 addition & 0 deletions src/python/Vector2.i
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ namespace ignition
%rename("%(uppercase)s", %$isstatic, %$isvariable) "";
public: static const Vector2 Zero;
public: static const Vector2 One;
public: static const Vector2 NaN;

public: Vector2();
public: Vector2(const T &_x, const T &_y);
Expand Down
19 changes: 19 additions & 0 deletions src/python/Vector2_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
import unittest
import math
from ignition.math import Vector2d
from ignition.math import Vector2f


class TestVector2(unittest.TestCase):
Expand Down Expand Up @@ -295,6 +296,24 @@ def test_lenght(self):
self.assertAlmostEqual(v.length(), 5)
self.assertAlmostEqual(v.squared_length(), 25)

def test_nan(self):
nanVec = Vector2d.NAN
self.assertFalse(nanVec.is_finite())
self.assertTrue(math.isnan(nanVec.x()))
self.assertTrue(math.isnan(nanVec.y()))

nanVec.correct()
self.assertEqual(Vector2d.ZERO, nanVec)
self.assertTrue(nanVec.is_finite())

nanVecF = Vector2f.NAN
self.assertFalse(nanVecF.is_finite())
self.assertTrue(math.isnan(nanVecF.x()))
self.assertTrue(math.isnan(nanVecF.y()))

nanVecF.correct()
self.assertEqual(Vector2f.ZERO, nanVecF)
self.assertTrue(nanVecF.is_finite())

if __name__ == '__main__':
unittest.main()
1 change: 1 addition & 0 deletions src/python/Vector3.i
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ namespace ignition
public: static const Vector3 UnitY;
%rename(UNIT_Z) UnitZ;
public: static const Vector3 UnitZ;
public: static const Vector3 NaN;
public: Vector3();
public: Vector3(const T &_x, const T &_y, const T &_z);
public: Vector3(const Vector3<T> &_v);
Expand Down
21 changes: 21 additions & 0 deletions src/python/Vector3_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
import unittest
import math
from ignition.math import Vector3d
from ignition.math import Vector3f


class TestVector3(unittest.TestCase):
Expand Down Expand Up @@ -350,6 +351,26 @@ def test_finite(self):

self.assertTrue(vec1.is_finite())

def test_nan(self):
nanVec = Vector3d.NAN
self.assertFalse(nanVec.is_finite())
self.assertTrue(math.isnan(nanVec.x()))
self.assertTrue(math.isnan(nanVec.y()))
self.assertTrue(math.isnan(nanVec.z()))

nanVec.correct()
self.assertEqual(Vector3d.ZERO, nanVec)
self.assertTrue(nanVec.is_finite())

nanVecF = Vector3f.NAN
self.assertFalse(nanVecF.is_finite())
self.assertTrue(math.isnan(nanVecF.x()))
self.assertTrue(math.isnan(nanVecF.y()))
self.assertTrue(math.isnan(nanVecF.z()))

nanVecF.correct()
self.assertEqual(Vector3f.ZERO, nanVecF)
self.assertTrue(nanVecF.is_finite())

if __name__ == '__main__':
unittest.main()
2 changes: 2 additions & 0 deletions src/python/Vector4.i
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ namespace ignition
%rename("%(uppercase)s", %$isstatic, %$isvariable) "";
public: static const Vector4 Zero;
public: static const Vector4 One;
public: static const Vector4 NaN;
public: Vector4();
public: Vector4(const T &_x, const T &_y, const T &_z, const T &_w);
public: Vector4(const Vector4<T> &_v);
Expand All @@ -58,6 +59,7 @@ namespace ignition
public: bool operator==(const Vector4<T> &_v) const;
public: bool Equal(const Vector4 &_v, const T &_tol) const;
public: bool IsFinite() const;
public: inline void Correct();
public: inline T X() const;
public: inline T Y() const;
public: inline T Z() const;
Expand Down
23 changes: 23 additions & 0 deletions src/python/Vector4_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
import unittest
import math
from ignition.math import Vector4d
from ignition.math import Vector4f


class TestVector4(unittest.TestCase):
Expand Down Expand Up @@ -256,6 +257,28 @@ def test_finite(self):
vec1 = Vector4d(0.1, 0.2, 0.3, 0.4)
self.assertTrue(vec1.is_finite())

def test_nan(self):
nanVec = Vector4d.NAN
self.assertFalse(nanVec.is_finite())
self.assertTrue(math.isnan(nanVec.x()))
self.assertTrue(math.isnan(nanVec.y()))
self.assertTrue(math.isnan(nanVec.z()))
self.assertTrue(math.isnan(nanVec.w()))

nanVec.correct()
self.assertEqual(Vector4d.ZERO, nanVec)
self.assertTrue(nanVec.is_finite())

nanVecF = Vector4f.NAN
self.assertFalse(nanVecF.is_finite())
self.assertTrue(math.isnan(nanVecF.x()))
self.assertTrue(math.isnan(nanVecF.y()))
self.assertTrue(math.isnan(nanVecF.z()))
self.assertTrue(math.isnan(nanVecF.w()))

nanVecF.correct()
self.assertEqual(Vector4f.ZERO, nanVecF)
self.assertTrue(nanVecF.is_finite())

if __name__ == '__main__':
unittest.main()
1 change: 1 addition & 0 deletions src/ruby/Vector2.i
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@ namespace ignition
{
public: static const Vector2 Zero;
public: static const Vector2 One;
public: static const Vector2 NaN;

public: Vector2();
public: Vector2(const T &_x, const T &_y);
Expand Down
22 changes: 22 additions & 0 deletions src/ruby/Vector2_TEST.rb
Original file line number Diff line number Diff line change
Expand Up @@ -257,6 +257,28 @@ def test_length
assert((v.SquaredLength() - 17.65).abs < 1e-8,
"Squared length of v should be near 17.65")
end

def test_nan
nanVec = Ignition::Math::Vector2d.NaN
assert(!nanVec.IsFinite(),
"NaN vector shouldn't be finite")
assert(nanVec.X().nan?, "X should be NaN")
assert(nanVec.Y().nan?, "Y should be NaN")

nanVec.Correct()
assert(Ignition::Math::Vector2d.Zero == nanVec,
"Corrected vector should equal zero")

nanVecF = Ignition::Math::Vector2f.NaN
assert(!nanVecF.IsFinite(),
"NaN vector shouldn't be finite")
assert(nanVecF.X().nan?, "X should be NaN")
assert(nanVecF.Y().nan?, "Y should be NaN")

nanVecF.Correct()
assert(Ignition::Math::Vector2f.Zero == nanVecF,
"Corrected vector should equal zero")
end
end

exit Test::Unit::UI::Console::TestRunner.run(Vector2_TEST).passed? ? 0 : -1
1 change: 1 addition & 0 deletions src/ruby/Vector3.i
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ namespace ignition
public: static const Vector3 UnitX;
public: static const Vector3 UnitY;
public: static const Vector3 UnitZ;
public: static const Vector3 NaN;
public: Vector3();
public: Vector3(const T &_x, const T &_y, const T &_z);
public: Vector3(const Vector3<T> &_v);
Expand Down
Loading

0 comments on commit 9739419

Please sign in to comment.