Skip to content

Commit

Permalink
Use const references to constexpr storage for static constants
Browse files Browse the repository at this point in the history
Update the required constructors, operators, and related functions to be
constexpr.

Signed-off-by: Jeremy Nimmer <[email protected]>
  • Loading branch information
jwnimmer-tri committed Dec 10, 2021
1 parent 931d058 commit 6a32e30
Show file tree
Hide file tree
Showing 11 changed files with 228 additions and 172 deletions.
13 changes: 8 additions & 5 deletions include/ignition/math/Angle.hh
Original file line number Diff line number Diff line change
Expand Up @@ -63,19 +63,19 @@ namespace ignition
{
/// \brief An angle with a value of zero.
/// Equivalent to math::Angle(0).
public: static const Angle Zero;
public: static const Angle &Zero;

/// \brief An angle with a value of Pi.
/// Equivalent to math::Angle(IGN_PI).
public: static const Angle Pi;
public: static const Angle &Pi;

/// \brief An angle with a value of Pi * 0.5.
/// Equivalent to math::Angle(IGN_PI * 0.5).
public: static const Angle HalfPi;
public: static const Angle &HalfPi;

/// \brief An angle with a value of Pi * 2.
/// Equivalent to math::Angle(IGN_PI * 2).
public: static const Angle TwoPi;
public: static const Angle &TwoPi;

/// \brief Default constructor that initializes an Angle to zero
/// radians/degrees.
Expand All @@ -91,7 +91,10 @@ namespace ignition
//
/// \param[in] _radian The radians used to initialize this Angle.
// cppcheck-suppress noExplicitConstructor
public: Angle(double _radian);
public: constexpr Angle(double _radian)
: value(_radian)
{
}

/// \brief Set the value from an angle in radians.
/// \param[in] _radian Radian value.
Expand Down
45 changes: 30 additions & 15 deletions include/ignition/math/Color.hh
Original file line number Diff line number Diff line change
Expand Up @@ -38,21 +38,21 @@ namespace ignition
class IGNITION_MATH_VISIBLE Color
{
/// \brief (1, 1, 1)
public: static const Color White;
public: static const Color &White;
/// \brief (0, 0, 0)
public: static const Color Black;
public: static const Color &Black;
/// \brief (1, 0, 0)
public: static const Color Red;
public: static const Color &Red;
/// \brief (0, 1, 0)
public: static const Color Green;
public: static const Color &Green;
/// \brief (0, 0, 1)
public: static const Color Blue;
public: static const Color &Blue;
/// \brief (1, 1, 0)
public: static const Color Yellow;
public: static const Color &Yellow;
/// \brief (1, 0, 1)
public: static const Color Magenta;
public: static const Color &Magenta;
/// \brief (0, 1, 1)
public: static const Color Cyan;
public: static const Color &Cyan;

/// \typedef RGBA
/// \brief A RGBA packed value as an unsigned int
Expand All @@ -71,22 +71,26 @@ namespace ignition
public: typedef unsigned int ABGR;

/// \brief Constructor
public: Color();
public: Color() = default;

/// \brief Constructor
/// \param[in] _r Red value (range 0 to 1)
/// \param[in] _g Green value (range 0 to 1)
/// \param[in] _b Blue value (range 0 to 1)
/// \param[in] _a Alpha value (0=transparent, 1=opaque)
public: Color(const float _r, const float _g, const float _b,
const float _a = 1.0);
public: constexpr Color(const float _r, const float _g, const float _b,
const float _a = 1.0)
: r(_r), g(_g), b(_b), a(_a)
{
this->Clamp();
}

/// \brief Copy Constructor
/// \param[in] _clr Color to copy
public: Color(const Color &_clr);
public: Color(const Color &_clr) = default;

/// \brief Destructor
public: ~Color();
public: ~Color() = default;

/// \brief Reset the color to default values to red=0, green=0,
/// blue=0, alpha=1.
Expand Down Expand Up @@ -124,7 +128,7 @@ namespace ignition
/// \brief Equal operator
/// \param[in] _pt Color to copy
/// \return Reference to this color
public: Color &operator=(const Color &_pt);
public: Color &operator=(const Color &_pt) = default;

/// \brief Array index operator
/// \param[in] _index Color component index(0=red, 1=green, 2=blue,
Expand Down Expand Up @@ -243,7 +247,18 @@ namespace ignition
public: bool operator!=(const Color &_pt) const;

/// \brief Clamp the color values to valid ranges
private: void Clamp();
private: constexpr void Clamp()
{
// These comparisons are carefully written to handle NaNs correctly.
if (!(this->r >= 0)) { this->r = 0; }
if (!(this->g >= 0)) { this->g = 0; }
if (!(this->b >= 0)) { this->b = 0; }
if (!(this->a >= 0)) { this->a = 0; }
if (this->r > 1) { this->r = this->r/255.0f; }
if (this->g > 1) { this->g = this->g/255.0f; }
if (this->b > 1) { this->b = this->b/255.0f; }
if (this->a > 1) { this->a = 1; }
}

/// \brief Stream insertion operator
/// \param[in] _out the output stream
Expand Down
48 changes: 26 additions & 22 deletions include/ignition/math/Matrix3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -95,11 +95,11 @@ namespace ignition
{
/// \brief A Matrix3 initialized to identity.
/// This is equivalent to math::Matrix3<T>(1, 0, 0, 0, 1, 0, 0, 0, 1).
public: static const Matrix3<T> Identity;
public: static const Matrix3<T> &Identity;

/// \brief A Matrix3 initialized to zero.
/// This is equivalent to math::Matrix3<T>(0, 0, 0, 0, 0, 0, 0, 0, 0).
public: static const Matrix3<T> Zero;
public: static const Matrix3<T> &Zero;

/// \brief Default constructor that initializes the matrix3 to zero.
public: Matrix3()
Expand All @@ -121,19 +121,13 @@ namespace ignition
/// \param[in] _v20 Row 2, Col 0 value
/// \param[in] _v21 Row 2, Col 1 value
/// \param[in] _v22 Row 2, Col 2 value
public: Matrix3(T _v00, T _v01, T _v02,
T _v10, T _v11, T _v12,
T _v20, T _v21, T _v22)
public: constexpr Matrix3(T _v00, T _v01, T _v02,
T _v10, T _v11, T _v12,
T _v20, T _v21, T _v22)
: data{{_v00, _v01, _v02},
{_v10, _v11, _v12},
{_v20, _v21, _v22}}
{
this->data[0][0] = _v00;
this->data[0][1] = _v01;
this->data[0][2] = _v02;
this->data[1][0] = _v10;
this->data[1][1] = _v11;
this->data[1][2] = _v12;
this->data[2][0] = _v20;
this->data[2][1] = _v21;
this->data[2][2] = _v22;
}

/// \brief Construct 3x3 rotation Matrix from a quaternion.
Expand Down Expand Up @@ -642,17 +636,27 @@ namespace ignition
private: T data[3][3];
};

namespace detail {

template<typename T>
constexpr Matrix3<T> gMatrix3Identity(
1, 0, 0,
0, 1, 0,
0, 0, 1);

template<typename T>
constexpr Matrix3<T> gMatrix3Zero(
0, 0, 0,
0, 0, 0,
0, 0, 0);

} // namespace detail

template<typename T>
const Matrix3<T> Matrix3<T>::Identity(
1, 0, 0,
0, 1, 0,
0, 0, 1);
const Matrix3<T> &Matrix3<T>::Identity = detail::gMatrix3Identity<T>;

template<typename T>
const Matrix3<T> Matrix3<T>::Zero(
0, 0, 0,
0, 0, 0,
0, 0, 0);
const Matrix3<T> &Matrix3<T>::Zero = detail::gMatrix3Zero<T>;

/// typedef Matrix3<int> as Matrix3i.
typedef Matrix3<int> Matrix3i;
Expand Down
50 changes: 30 additions & 20 deletions include/ignition/math/Matrix4.hh
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,10 @@ namespace ignition
class Matrix4
{
/// \brief Identity matrix
public: static const Matrix4<T> Identity;
public: static const Matrix4<T> &Identity;

/// \brief Zero matrix
public: static const Matrix4<T> Zero;
public: static const Matrix4<T> &Zero;

/// \brief Constructor
public: Matrix4()
Expand Down Expand Up @@ -70,15 +70,15 @@ namespace ignition
/// \param[in] _v31 Row 3, Col 1 value
/// \param[in] _v32 Row 3, Col 2 value
/// \param[in] _v33 Row 3, Col 3 value
public: Matrix4(T _v00, T _v01, T _v02, T _v03,
T _v10, T _v11, T _v12, T _v13,
T _v20, T _v21, T _v22, T _v23,
T _v30, T _v31, T _v32, T _v33)
public: constexpr Matrix4(T _v00, T _v01, T _v02, T _v03,
T _v10, T _v11, T _v12, T _v13,
T _v20, T _v21, T _v22, T _v23,
T _v30, T _v31, T _v32, T _v33)
: data{{_v00, _v01, _v02, _v03},
{_v10, _v11, _v12, _v13},
{_v20, _v21, _v22, _v23},
{_v30, _v31, _v32, _v33}}
{
this->Set(_v00, _v01, _v02, _v03,
_v10, _v11, _v12, _v13,
_v20, _v21, _v22, _v23,
_v30, _v31, _v32, _v33);
}

/// \brief Construct Matrix4 from a quaternion.
Expand Down Expand Up @@ -844,19 +844,29 @@ namespace ignition
private: T data[4][4];
};

namespace detail {

template<typename T>
constexpr Matrix4<T> gMatrix4Identity(
1, 0, 0, 0,
0, 1, 0, 0,
0, 0, 1, 0,
0, 0, 0, 1);

template<typename T>
constexpr Matrix4<T> gMatrix4Zero(
0, 0, 0, 0,
0, 0, 0, 0,
0, 0, 0, 0,
0, 0, 0, 0);

} // namespace detail

template<typename T>
const Matrix4<T> Matrix4<T>::Identity(
1, 0, 0, 0,
0, 1, 0, 0,
0, 0, 1, 0,
0, 0, 0, 1);
const Matrix4<T> &Matrix4<T>::Identity = detail::gMatrix4Identity<T>;

template<typename T>
const Matrix4<T> Matrix4<T>::Zero(
0, 0, 0, 0,
0, 0, 0, 0,
0, 0, 0, 0,
0, 0, 0, 0);
const Matrix4<T> &Matrix4<T>::Zero = detail::gMatrix4Zero<T>;

typedef Matrix4<int> Matrix4i;
typedef Matrix4<double> Matrix4d;
Expand Down
10 changes: 8 additions & 2 deletions include/ignition/math/Pose3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ namespace ignition
{
/// \brief A Pose3 initialized to zero.
/// This is equivalent to math::Pose3<T>(0, 0, 0, 0, 0, 0).
public: static const Pose3<T> Zero;
public: static const Pose3<T> &Zero;

/// \brief Default constructor. This initializes the position
/// component to zero and the quaternion to identity.
Expand Down Expand Up @@ -540,7 +540,13 @@ namespace ignition
private: Quaternion<T> q;
};

template<typename T> const Pose3<T> Pose3<T>::Zero(0, 0, 0, 0, 0, 0);
namespace detail {

template<typename T> constexpr Pose3<T> gPose3Zero{};

} // namespace detail

template<typename T> const Pose3<T> &Pose3<T>::Zero = detail::gPose3Zero<T>;

/// typedef Pose3<double> as Pose3d.
typedef Pose3<double> Pose3d;
Expand Down
23 changes: 17 additions & 6 deletions include/ignition/math/Quaternion.hh
Original file line number Diff line number Diff line change
Expand Up @@ -81,14 +81,14 @@ namespace ignition
{
/// \brief A Quaternion initialized to identity.
/// This is equivalent to math::Quaternion<T>(1, 0, 0, 0)
public: static const Quaternion Identity;
public: static const Quaternion &Identity;

/// \brief A Quaternion initialized to zero.
/// This is equivalent to math::Quaternion<T>(0, 0, 0, 0)
public: static const Quaternion Zero;
public: static const Quaternion &Zero;

/// \brief Default Constructor
public: Quaternion()
public: constexpr Quaternion()
: qw(1), qx(0), qy(0), qz(0)
{
// quaternion not normalized, because that breaks
Expand All @@ -102,7 +102,8 @@ namespace ignition
/// \param[in] _x X param
/// \param[in] _y Y param
/// \param[in] _z Z param
public: Quaternion(const T &_w, const T &_x, const T &_y, const T &_z)
public: constexpr Quaternion(const T &_w, const T &_x, const T &_y,
const T &_z)
: qw(_w), qx(_x), qy(_y), qz(_z)
{}

Expand Down Expand Up @@ -1256,11 +1257,21 @@ namespace ignition
private: T qz;
};

namespace detail {

template<typename T> constexpr Quaternion<T>
gQuaternionIdentity(1, 0, 0, 0);

template<typename T> constexpr Quaternion<T>
gQuaternionZero(0, 0, 0, 0);

} // namespace detail

template<typename T> const Quaternion<T>
Quaternion<T>::Identity(1, 0, 0, 0);
&Quaternion<T>::Identity = detail::gQuaternionIdentity<T>;

template<typename T> const Quaternion<T>
Quaternion<T>::Zero(0, 0, 0, 0);
&Quaternion<T>::Zero = detail::gQuaternionZero<T>;

/// typedef Quaternion<double> as Quaterniond
typedef Quaternion<double> Quaterniond;
Expand Down
Loading

0 comments on commit 6a32e30

Please sign in to comment.