Skip to content

Commit

Permalink
Ticktock IGN_*_SIZE_T and IGN_MASSMATRIX3_DEFAULT_TOLERANCE
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon committed Jun 7, 2022
1 parent d1d51c0 commit 1a32dfc
Show file tree
Hide file tree
Showing 20 changed files with 133 additions and 85 deletions.
3 changes: 3 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,9 @@ release will remove the deprecated code.
1. `IGN_SQRT2`
1. `IGN_FP_VOLATILE`
1. `IGN_SPHERE_VOLUME`, `IGN_CYLINDER_VOLUME`, `IGN_BOX_VOLUME`, `IGN_BOX_VOLUME_V`
1. `IGN_MASSMATRIX3_DEFAULT_TOLERANCE`
1. All `IGN_*_SIZE_T` variables are deprecated and will be removed in future versions.
Please use `GZ_*_SIZE_T` instead.


### Modifications
Expand Down
48 changes: 32 additions & 16 deletions include/gz/math/Helpers.hh
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,10 @@
/// \brief The default tolerance value used by MassMatrix3::IsValid(),
/// MassMatrix3::IsPositive(), and MassMatrix3::ValidMoments()
template <typename T>
constexpr T GZ_MASSMATRIX3_DEFAULT_TOLERANCE = T(10);

// TODO(CH3): Deprecated. Remove on tock.
template <typename T>
constexpr T IGN_MASSMATRIX3_DEFAULT_TOLERANCE = T(10);

/// \brief Define GZ_PI, GZ_PI_2, and GZ_PI_4.
Expand Down Expand Up @@ -88,34 +92,46 @@ namespace gz
inline namespace GZ_MATH_VERSION_NAMESPACE {
//
/// \brief size_t type with a value of 0
static const size_t IGN_ZERO_SIZE_T = 0u;
static const size_t GZ_ZERO_SIZE_T = 0u;

/// \brief size_t type with a value of 1
static const size_t IGN_ONE_SIZE_T = 1u;
static const size_t GZ_ONE_SIZE_T = 1u;

/// \brief size_t type with a value of 2
static const size_t IGN_TWO_SIZE_T = 2u;
static const size_t GZ_TWO_SIZE_T = 2u;

/// \brief size_t type with a value of 3
static const size_t IGN_THREE_SIZE_T = 3u;
static const size_t GZ_THREE_SIZE_T = 3u;

/// \brief size_t type with a value of 4
static const size_t IGN_FOUR_SIZE_T = 4u;
static const size_t GZ_FOUR_SIZE_T = 4u;

/// \brief size_t type with a value of 5
static const size_t IGN_FIVE_SIZE_T = 5u;
static const size_t GZ_FIVE_SIZE_T = 5u;

/// \brief size_t type with a value of 6
static const size_t IGN_SIX_SIZE_T = 6u;
static const size_t GZ_SIX_SIZE_T = 6u;

/// \brief size_t type with a value of 7
static const size_t IGN_SEVEN_SIZE_T = 7u;
static const size_t GZ_SEVEN_SIZE_T = 7u;

/// \brief size_t type with a value of 8
static const size_t IGN_EIGHT_SIZE_T = 8u;
static const size_t GZ_EIGHT_SIZE_T = 8u;

/// \brief size_t type with a value of 9
static const size_t IGN_NINE_SIZE_T = 9u;
static const size_t GZ_NINE_SIZE_T = 9u;

// TODO(CH3): Deprecated. Remove on tock.
constexpr auto GZ_DEPRECATED(7) IGN_ZERO_SIZE_T = &GZ_ZERO_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_ONE_SIZE_T = &GZ_ONE_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_TWO_SIZE_T = &GZ_TWO_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_THREE_SIZE_T = &GZ_THREE_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_FOUR_SIZE_T = &GZ_FOUR_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_FIVE_SIZE_T = &GZ_FIVE_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_SIX_SIZE_T = &GZ_SIX_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_SEVEN_SIZE_T = &GZ_SEVEN_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_EIGHT_SIZE_T = &GZ_EIGHT_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_NINE_SIZE_T = &GZ_NINE_SIZE_T;

/// \brief Double maximum value. This value will be similar to 1.79769e+308
static const double MAX_D = std::numeric_limits<double>::max();
Expand Down Expand Up @@ -154,7 +170,7 @@ namespace gz
static const uint16_t MIN_UI16 = std::numeric_limits<uint16_t>::min();

/// \brief 16bit unsigned integer lowest value. This is equivalent to
/// IGN_UINT16_MIN, and is defined here for completeness.
/// GZ_UINT16_MIN, and is defined here for completeness.
static const uint16_t LOW_UI16 = std::numeric_limits<uint16_t>::lowest();

/// \brief 16-bit unsigned integer positive infinite value
Expand All @@ -167,7 +183,7 @@ namespace gz
static const int16_t MIN_I16 = std::numeric_limits<int16_t>::min();

/// \brief 16bit unsigned integer lowest value. This is equivalent to
/// IGN_INT16_MIN, and is defined here for completeness.
/// GZ_INT16_MIN, and is defined here for completeness.
static const int16_t LOW_I16 = std::numeric_limits<int16_t>::lowest();

/// \brief 16-bit unsigned integer positive infinite value
Expand All @@ -180,7 +196,7 @@ namespace gz
static const uint32_t MIN_UI32 = std::numeric_limits<uint32_t>::min();

/// \brief 32bit unsigned integer lowest value. This is equivalent to
/// IGN_UINT32_MIN, and is defined here for completeness.
/// GZ_UINT32_MIN, and is defined here for completeness.
static const uint32_t LOW_UI32 = std::numeric_limits<uint32_t>::lowest();

/// \brief 32-bit unsigned integer positive infinite value
Expand All @@ -193,7 +209,7 @@ namespace gz
static const int32_t MIN_I32 = std::numeric_limits<int32_t>::min();

/// \brief 32bit unsigned integer lowest value. This is equivalent to
/// IGN_INT32_MIN, and is defined here for completeness.
/// GZ_INT32_MIN, and is defined here for completeness.
static const int32_t LOW_I32 = std::numeric_limits<int32_t>::lowest();

/// \brief 32-bit unsigned integer positive infinite value
Expand All @@ -206,7 +222,7 @@ namespace gz
static const uint64_t MIN_UI64 = std::numeric_limits<uint64_t>::min();

/// \brief 64bit unsigned integer lowest value. This is equivalent to
/// IGN_UINT64_MIN, and is defined here for completeness.
/// GZ_UINT64_MIN, and is defined here for completeness.
static const uint64_t LOW_UI64 = std::numeric_limits<uint64_t>::lowest();

/// \brief 64-bit unsigned integer positive infinite value
Expand All @@ -219,7 +235,7 @@ namespace gz
static const int64_t MIN_I64 = std::numeric_limits<int64_t>::min();

/// \brief 64bit unsigned integer lowest value. This is equivalent to
/// IGN_INT64_MIN, and is defined here for completeness.
/// GZ_INT64_MIN, and is defined here for completeness.
static const int64_t LOW_I64 = std::numeric_limits<int64_t>::lowest();

/// \brief 64-bit unsigned integer positive infinite value
Expand Down
2 changes: 1 addition & 1 deletion include/gz/math/Inertial.hh
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ namespace gz
///
/// \return True if the MassMatrix3 is valid.
public: bool SetMassMatrix(const MassMatrix3<T> &_m,
const T _tolerance = IGN_MASSMATRIX3_DEFAULT_TOLERANCE<T>)
const T _tolerance = GZ_MASSMATRIX3_DEFAULT_TOLERANCE<T>)
{
this->massMatrix = _m;
return this->massMatrix.IsValid(_tolerance);
Expand Down
2 changes: 1 addition & 1 deletion include/gz/math/Line2.hh
Original file line number Diff line number Diff line change
Expand Up @@ -293,7 +293,7 @@ namespace gz
/// is clamped to the range [0, 1]
public: math::Vector2<T> operator[](size_t _index) const
{
return this->pts[clamp(_index, IGN_ZERO_SIZE_T, IGN_ONE_SIZE_T)];
return this->pts[clamp(_index, GZ_ZERO_SIZE_T, GZ_ONE_SIZE_T)];
}

/// \brief Stream extraction operator
Expand Down
2 changes: 1 addition & 1 deletion include/gz/math/Line3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -382,7 +382,7 @@ namespace gz
/// parameter is clamped to the range [0, 1].
public: math::Vector3<T> operator[](const size_t _index) const
{
return this->pts[clamp(_index, IGN_ZERO_SIZE_T, IGN_ONE_SIZE_T)];
return this->pts[clamp(_index, GZ_ZERO_SIZE_T, GZ_ONE_SIZE_T)];
}

/// \brief Stream extraction operator
Expand Down
12 changes: 6 additions & 6 deletions include/gz/math/MassMatrix3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -297,7 +297,7 @@ namespace gz
/// \endcode
///
public: bool IsNearPositive(const T _tolerance =
IGN_MASSMATRIX3_DEFAULT_TOLERANCE<T>) const
GZ_MASSMATRIX3_DEFAULT_TOLERANCE<T>) const
{
const T epsilon = this->Epsilon(_tolerance);

Expand Down Expand Up @@ -330,7 +330,7 @@ namespace gz
/// \endcode
///
public: bool IsPositive(const T _tolerance =
IGN_MASSMATRIX3_DEFAULT_TOLERANCE<T>) const
GZ_MASSMATRIX3_DEFAULT_TOLERANCE<T>) const
{
const T epsilon = this->Epsilon(_tolerance);

Expand All @@ -351,7 +351,7 @@ namespace gz
/// A good value is 10, which is also the
/// MASSMATRIX3_DEFAULT_TOLERANCE.
public: T Epsilon(const T _tolerance =
IGN_MASSMATRIX3_DEFAULT_TOLERANCE<T>) const
GZ_MASSMATRIX3_DEFAULT_TOLERANCE<T>) const
{
return Epsilon(this->DiagonalMoments(), _tolerance);
}
Expand Down Expand Up @@ -379,7 +379,7 @@ namespace gz
/// \endcode
public: static T Epsilon(const Vector3<T> &_moments,
const T _tolerance =
IGN_MASSMATRIX3_DEFAULT_TOLERANCE<T>)
GZ_MASSMATRIX3_DEFAULT_TOLERANCE<T>)
{
// The following was borrowed heavily from:
// https://github.com/RobotLocomotion/drake/blob/v0.27.0/multibody/tree/rotational_inertia.h
Expand Down Expand Up @@ -417,7 +417,7 @@ namespace gz
/// \return True if IsNearPositive(_tolerance) and
/// ValidMoments(this->PrincipalMoments(), _tolerance) both return true.
public: bool IsValid(const T _tolerance =
IGN_MASSMATRIX3_DEFAULT_TOLERANCE<T>) const
GZ_MASSMATRIX3_DEFAULT_TOLERANCE<T>) const
{
return this->IsNearPositive(_tolerance) &&
ValidMoments(this->PrincipalMoments(), _tolerance);
Expand All @@ -444,7 +444,7 @@ namespace gz
/// _moments[2] + _moments[0] + epsilon >= _moments[1];
/// \endcode
public: static bool ValidMoments(const Vector3<T> &_moments,
const T _tolerance = IGN_MASSMATRIX3_DEFAULT_TOLERANCE<T>)
const T _tolerance = GZ_MASSMATRIX3_DEFAULT_TOLERANCE<T>)
{
T epsilon = Epsilon(_moments, _tolerance);

Expand Down
12 changes: 6 additions & 6 deletions include/gz/math/Matrix3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -156,8 +156,8 @@ namespace gz
/// \param[in] _v New value.
public: void Set(size_t _row, size_t _col, T _v)
{
this->data[clamp(_row, IGN_ZERO_SIZE_T, IGN_TWO_SIZE_T)]
[clamp(_col, IGN_ZERO_SIZE_T, IGN_TWO_SIZE_T)] = _v;
this->data[clamp(_row, GZ_ZERO_SIZE_T, GZ_TWO_SIZE_T)]
[clamp(_col, GZ_ZERO_SIZE_T, GZ_TWO_SIZE_T)] = _v;
}

/// \brief Set values.
Expand Down Expand Up @@ -504,8 +504,8 @@ namespace gz
/// \return a pointer to the row
public: inline T operator()(size_t _row, size_t _col) const
{
return this->data[clamp(_row, IGN_ZERO_SIZE_T, IGN_TWO_SIZE_T)]
[clamp(_col, IGN_ZERO_SIZE_T, IGN_TWO_SIZE_T)];
return this->data[clamp(_row, GZ_ZERO_SIZE_T, GZ_TWO_SIZE_T)]
[clamp(_col, GZ_ZERO_SIZE_T, GZ_TWO_SIZE_T)];
}

/// \brief Array subscript operator.
Expand All @@ -514,8 +514,8 @@ namespace gz
/// \return a pointer to the row
public: inline T &operator()(size_t _row, size_t _col)
{
return this->data[clamp(_row, IGN_ZERO_SIZE_T, IGN_TWO_SIZE_T)]
[clamp(_col, IGN_ZERO_SIZE_T, IGN_TWO_SIZE_T)];
return this->data[clamp(_row, GZ_ZERO_SIZE_T, GZ_TWO_SIZE_T)]
[clamp(_col, GZ_ZERO_SIZE_T, GZ_TWO_SIZE_T)];
}

/// \brief Return the determinant of the matrix.
Expand Down
8 changes: 4 additions & 4 deletions include/gz/math/Matrix4.hh
Original file line number Diff line number Diff line change
Expand Up @@ -686,8 +686,8 @@ namespace gz
public: inline const T &operator()(const size_t _row,
const size_t _col) const
{
return this->data[clamp(_row, IGN_ZERO_SIZE_T, IGN_THREE_SIZE_T)][
clamp(_col, IGN_ZERO_SIZE_T, IGN_THREE_SIZE_T)];
return this->data[clamp(_row, GZ_ZERO_SIZE_T, GZ_THREE_SIZE_T)][
clamp(_col, GZ_ZERO_SIZE_T, GZ_THREE_SIZE_T)];
}

/// \brief Get a mutable version the value at the specified row,
Expand All @@ -699,8 +699,8 @@ namespace gz
/// \return The value at the specified index
public: inline T &operator()(const size_t _row, const size_t _col)
{
return this->data[clamp(_row, IGN_ZERO_SIZE_T, IGN_THREE_SIZE_T)]
[clamp(_col, IGN_ZERO_SIZE_T, IGN_THREE_SIZE_T)];
return this->data[clamp(_row, GZ_ZERO_SIZE_T, GZ_THREE_SIZE_T)]
[clamp(_col, GZ_ZERO_SIZE_T, GZ_THREE_SIZE_T)];
}

/// \brief Equality test with tolerance.
Expand Down
2 changes: 1 addition & 1 deletion include/gz/math/Triangle.hh
Original file line number Diff line number Diff line change
Expand Up @@ -226,7 +226,7 @@ namespace gz
/// \return The point specified by _index.
public: math::Vector2<T> operator[](const size_t _index) const
{
return this->pts[clamp(_index, IGN_ZERO_SIZE_T, IGN_TWO_SIZE_T)];
return this->pts[clamp(_index, GZ_ZERO_SIZE_T, GZ_TWO_SIZE_T)];
}

/// The points of the triangle
Expand Down
2 changes: 1 addition & 1 deletion include/gz/math/Triangle3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -265,7 +265,7 @@ namespace gz
/// \return The triangle point at _index.
public: Vector3<T> operator[](const size_t _index) const
{
return this->pts[clamp(_index, IGN_ZERO_SIZE_T, IGN_TWO_SIZE_T)];
return this->pts[clamp(_index, GZ_ZERO_SIZE_T, GZ_TWO_SIZE_T)];
}

/// The points of the triangle
Expand Down
4 changes: 2 additions & 2 deletions include/gz/math/Vector2.hh
Original file line number Diff line number Diff line change
Expand Up @@ -473,15 +473,15 @@ namespace gz
/// The index is clamped to the range [0,1].
public: T &operator[](const std::size_t _index)
{
return this->data[clamp(_index, IGN_ZERO_SIZE_T, IGN_ONE_SIZE_T)];
return this->data[clamp(_index, GZ_ZERO_SIZE_T, GZ_ONE_SIZE_T)];
}

/// \brief Const-qualified array subscript operator
/// \param[in] _index The index, where 0 == x and 1 == y.
/// The index is clamped to the range [0,1].
public: T operator[](const std::size_t _index) const
{
return this->data[clamp(_index, IGN_ZERO_SIZE_T, IGN_ONE_SIZE_T)];
return this->data[clamp(_index, GZ_ZERO_SIZE_T, GZ_ONE_SIZE_T)];
}

/// \brief Return the x value.
Expand Down
4 changes: 2 additions & 2 deletions include/gz/math/Vector3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -619,7 +619,7 @@ namespace gz
/// \return The value.
public: T &operator[](const std::size_t _index)
{
return this->data[clamp(_index, IGN_ZERO_SIZE_T, IGN_TWO_SIZE_T)];
return this->data[clamp(_index, GZ_ZERO_SIZE_T, GZ_TWO_SIZE_T)];
}

/// \brief Const-qualified array subscript operator
Expand All @@ -628,7 +628,7 @@ namespace gz
/// \return The value.
public: T operator[](const std::size_t _index) const
{
return this->data[clamp(_index, IGN_ZERO_SIZE_T, IGN_TWO_SIZE_T)];
return this->data[clamp(_index, GZ_ZERO_SIZE_T, GZ_TWO_SIZE_T)];
}

/// \brief Round all values to _precision decimal places
Expand Down
4 changes: 2 additions & 2 deletions include/gz/math/Vector4.hh
Original file line number Diff line number Diff line change
Expand Up @@ -578,7 +578,7 @@ namespace gz
/// \return The value.
public: T &operator[](const std::size_t _index)
{
return this->data[clamp(_index, IGN_ZERO_SIZE_T, IGN_THREE_SIZE_T)];
return this->data[clamp(_index, GZ_ZERO_SIZE_T, GZ_THREE_SIZE_T)];
}

/// \brief Const-qualified array subscript operator
Expand All @@ -587,7 +587,7 @@ namespace gz
/// \return The value.
public: T operator[](const std::size_t _index) const
{
return this->data[clamp(_index, IGN_ZERO_SIZE_T, IGN_THREE_SIZE_T)];
return this->data[clamp(_index, GZ_ZERO_SIZE_T, GZ_THREE_SIZE_T)];
}

/// \brief Return a mutable x value.
Expand Down
37 changes: 27 additions & 10 deletions src/Helpers.i
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,10 @@
#include <gz/math/Helpers.hh>
%}

template <typename T>
constexpr T GZ_MASSMATRIX3_DEFAULT_TOLERANCE = T(10);

// TODO(CH3): Deprecated. Remove on tock.
template <typename T>
constexpr T IGN_MASSMATRIX3_DEFAULT_TOLERANCE = T(10);

Expand Down Expand Up @@ -54,16 +58,29 @@ namespace gz
{
namespace math
{
static const size_t IGN_ZERO_SIZE_T = 0u;
static const size_t IGN_ONE_SIZE_T = 1u;
static const size_t IGN_TWO_SIZE_T = 2u;
static const size_t IGN_THREE_SIZE_T = 3u;
static const size_t IGN_FOUR_SIZE_T = 4u;
static const size_t IGN_FIVE_SIZE_T = 5u;
static const size_t IGN_SIX_SIZE_T = 6u;
static const size_t IGN_SEVEN_SIZE_T = 7u;
static const size_t IGN_EIGHT_SIZE_T = 8u;
static const size_t IGN_NINE_SIZE_T = 9u;
static const size_t GZ_ZERO_SIZE_T = 0u;
static const size_t GZ_ONE_SIZE_T = 1u;
static const size_t GZ_TWO_SIZE_T = 2u;
static const size_t GZ_THREE_SIZE_T = 3u;
static const size_t GZ_FOUR_SIZE_T = 4u;
static const size_t GZ_FIVE_SIZE_T = 5u;
static const size_t GZ_SIX_SIZE_T = 6u;
static const size_t GZ_SEVEN_SIZE_T = 7u;
static const size_t GZ_EIGHT_SIZE_T = 8u;
static const size_t GZ_NINE_SIZE_T = 9u;

// TODO(CH3): Deprecated. Remove on tock.
constexpr auto GZ_DEPRECATED(7) IGN_ZERO_SIZE_T = &GZ_ZERO_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_ONE_SIZE_T = &GZ_ONE_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_TWO_SIZE_T = &GZ_TWO_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_THREE_SIZE_T = &GZ_THREE_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_FOUR_SIZE_T = &GZ_FOUR_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_FIVE_SIZE_T = &GZ_FIVE_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_SIX_SIZE_T = &GZ_SIX_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_SEVEN_SIZE_T = &GZ_SEVEN_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_EIGHT_SIZE_T = &GZ_EIGHT_SIZE_T;
constexpr auto GZ_DEPRECATED(7) IGN_NINE_SIZE_T = &GZ_NINE_SIZE_T;

static const double MAX_D = std::numeric_limits<double>::max();
static const double MIN_D = std::numeric_limits<double>::min();
static const double LOW_D = std::numeric_limits<double>::lowest();
Expand Down
Loading

0 comments on commit 1a32dfc

Please sign in to comment.