From e8e5585c5ccbe8e568baa263094085466ee57f43 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 6 Jun 2022 14:43:01 -0700 Subject: [PATCH 1/9] Migrate macros Signed-off-by: methylDragon --- Migration.md | 9 ++ examples/diff_drive_odometry.cc | 6 +- examples/helpers_example.cc | 6 +- examples/helpers_example.rb | 6 +- examples/pose3_example.cc | 4 +- examples/pose3_example.rb | 2 +- examples/quaternion_from_euler.cc | 12 +- examples/quaternion_to_euler.cc | 6 +- include/gz/math/Angle.hh | 18 +-- include/gz/math/AxisAlignedBox.hh | 2 +- include/gz/math/DiffDriveOdometry.hh | 6 +- include/gz/math/Filter.hh | 4 +- include/gz/math/Frustum.hh | 2 +- include/gz/math/GaussMarkovProcess.hh | 2 +- include/gz/math/Helpers.hh | 34 +++--- include/gz/math/Kmeans.hh | 2 +- include/gz/math/MassMatrix3.hh | 10 +- include/gz/math/Material.hh | 2 +- include/gz/math/Matrix4.hh | 10 +- include/gz/math/PID.hh | 2 +- include/gz/math/Pose3.hh | 2 +- include/gz/math/Quaternion.hh | 4 +- include/gz/math/RollingMean.hh | 2 +- include/gz/math/RotationSpline.hh | 2 +- include/gz/math/SemanticVersion.hh | 2 +- include/gz/math/SphericalCoordinates.hh | 2 +- include/gz/math/Spline.hh | 2 +- include/gz/math/Stopwatch.hh | 2 +- include/gz/math/Temperature.hh | 2 +- include/gz/math/Vector3Stats.hh | 2 +- include/gz/math/detail/Capsule.hh | 4 +- include/gz/math/detail/Cylinder.hh | 2 +- include/gz/math/detail/Ellipsoid.hh | 2 +- include/gz/math/detail/Sphere.hh | 4 +- include/ignition/math/Angle.hh | 4 + include/ignition/math/Helpers.hh | 12 ++ src/Angle.cc | 12 +- src/Angle_TEST.cc | 20 ++-- src/AxisAlignedBox_TEST.cc | 6 +- src/Capsule_TEST.cc | 6 +- src/Cylinder_TEST.cc | 2 +- src/DiffDriveOdometry_TEST.cc | 10 +- src/Ellipsoid_TEST.cc | 4 +- src/Frustum.cc | 2 +- src/Frustum_TEST.cc | 116 +++++++++---------- src/Helpers.i | 30 +++-- src/Helpers_TEST.cc | 20 ++-- src/Inertial_TEST.cc | 54 ++++----- src/Line3_TEST.cc | 2 +- src/MassMatrix3_TEST.cc | 42 +++---- src/Matrix3_TEST.cc | 2 +- src/Matrix4_TEST.cc | 18 +-- src/OrientedBox_TEST.cc | 2 +- src/Pose_TEST.cc | 12 +- src/Quaternion_TEST.cc | 42 +++---- src/Sphere_TEST.cc | 2 +- src/SphericalCoordinates.cc | 8 +- src/SphericalCoordinates_TEST.cc | 10 +- src/Vector2_TEST.cc | 2 +- src/python_pybind11/src/Angle.cc | 6 +- src/python_pybind11/src/Helpers.cc | 18 +-- src/python_pybind11/test/Helpers_TEST.py | 20 ++-- src/python_pybind11/test/MassMatrix3_TEST.py | 50 ++++---- src/ruby/Helpers.i | 47 +++++--- 64 files changed, 409 insertions(+), 351 deletions(-) diff --git a/Migration.md b/Migration.md index 9ab36ad94..ffbe800b6 100644 --- a/Migration.md +++ b/Migration.md @@ -69,6 +69,15 @@ release will remove the deprecated code. 1. The `ignition` namespace is deprecated and will be removed in future versions. Use `gz` instead. 1. Header files under `ignition/...` are deprecated and will be removed in future versions. Use `gz/...` instead. +1. The following `IGN_` prefixed macros are deprecated and will be removed in future versions. + Use the `GZ_` prefix instead. + 1. `IGN_RTOD`, `IGN_DTOR` + 1. `IGN_NORMALIZE` + 1. `IGN_PI`, `IGN_PI_2`, `IGN_PI_4` + 1. `IGN_SQRT2` + 1. `IGN_FP_VOLATILE` + 1. `IGN_SPHERE_VOLUME`, `IGN_CYLINDER_VOLUME`, `IGN_BOX_VOLUME`, `IGN_BOX_VOLUME_V` + ### Modifications diff --git a/examples/diff_drive_odometry.cc b/examples/diff_drive_odometry.cc index 7b0a2be06..01d0a23c0 100644 --- a/examples/diff_drive_odometry.cc +++ b/examples/diff_drive_odometry.cc @@ -31,7 +31,7 @@ int main(int argc, char **argv) double wheelSeparation = 2.0; double wheelRadius = 0.5; - double wheelCircumference = 2 * IGN_PI * wheelRadius; + double wheelCircumference = 2 * GZ_PI * wheelRadius; // This is the linear distance traveled per degree of wheel rotation. double distPerDegree = wheelCircumference / 360.0; @@ -45,7 +45,7 @@ int main(int argc, char **argv) // position. std::cout << "--- Rotate both wheels by 1 degree. ---" << '\n'; auto time1 = startTime + std::chrono::milliseconds(100); - odom.Update(IGN_DTOR(1.0), IGN_DTOR(1.0), time1); + odom.Update(GZ_DTOR(1.0), GZ_DTOR(1.0), time1); std::cout << "\tLinear velocity:\t" << distPerDegree / 0.1 << " m/s" << "\n\tOdom linear velocity:\t" << odom.LinearVelocity() << " m/s" @@ -62,7 +62,7 @@ int main(int argc, char **argv) << "by 2 degrees ---" << std::endl; auto time2 = time1 + std::chrono::milliseconds(100); - odom.Update(IGN_DTOR(2.0), IGN_DTOR(3.0), time2); + odom.Update(GZ_DTOR(2.0), GZ_DTOR(3.0), time2); std::cout << "The heading should be the arc tangent of the linear distance\n" << "traveled by the right wheel (the left wheel was stationary)\n" diff --git a/examples/helpers_example.cc b/examples/helpers_example.cc index a7ae27632..a75d1f515 100644 --- a/examples/helpers_example.cc +++ b/examples/helpers_example.cc @@ -21,13 +21,13 @@ int main(int argc, char **argv) { std::cout << "The volume of a sphere with r=2 is " - << IGN_SPHERE_VOLUME(2) << std::endl; + << GZ_SPHERE_VOLUME(2) << std::endl; std::cout << "The volume of a cylinder with r=4 and l=5 is " - << IGN_CYLINDER_VOLUME(4, 5) << std::endl; + << GZ_CYLINDER_VOLUME(4, 5) << std::endl; std::cout << "The volume of a box with x=1, y=2, and z=3 is " - << IGN_BOX_VOLUME(1, 2, 3) << std::endl; + << GZ_BOX_VOLUME(1, 2, 3) << std::endl; std::cout << "The result of clamping 2.4 to the range [1,2] is " << gz::math::clamp(2.4f, 1.0f, 2.0f) << std::endl; diff --git a/examples/helpers_example.rb b/examples/helpers_example.rb index be3100514..993b6660e 100644 --- a/examples/helpers_example.rb +++ b/examples/helpers_example.rb @@ -22,13 +22,13 @@ # require 'ignition/math' -printf("The volume of a sphere with r=2 is %f.\n", IGN_SPHERE_VOLUME(2)) +printf("The volume of a sphere with r=2 is %f.\n", GZ_SPHERE_VOLUME(2)) printf("The volume of a cylinder with r=4 and l=5 is %f.\n", - IGN_CYLINDER_VOLUME(4, 5)) + GZ_CYLINDER_VOLUME(4, 5)) printf("The volume of a box with x=1, y=2, and z=3 is %f.\n", - IGN_BOX_VOLUME(1, 2, 3)) + GZ_BOX_VOLUME(1, 2, 3)) printf("The result of clamping 2.4 to the range [1,2] is %f.\n", Gz::Math::Clamp(2.4, 1, 2)) diff --git a/examples/pose3_example.cc b/examples/pose3_example.cc index cb010eeb0..ff55e8764 100644 --- a/examples/pose3_example.cc +++ b/examples/pose3_example.cc @@ -26,8 +26,8 @@ int main(int argc, char **argv) << p << std::endl; // Construct a pose at position 1, 2, 3 with a yaw of PI radians. - gz::math::Pose3d p1(1, 2, 3, 0, 0, IGN_PI); - std::cout << "A pose3d(1, 2, 3, 0, 0, IGN_PI) has the following values\n" + gz::math::Pose3d p1(1, 2, 3, 0, 0, GZ_PI); + std::cout << "A pose3d(1, 2, 3, 0, 0, GZ_PI) has the following values\n" << p1 << std::endl; // Set the position of a pose to 10, 20, 30 diff --git a/examples/pose3_example.rb b/examples/pose3_example.rb index b8465c167..0574df411 100644 --- a/examples/pose3_example.rb +++ b/examples/pose3_example.rb @@ -30,7 +30,7 @@ # Construct a pose at position 1, 2, 3 with a yaw of PI radians. p1 = Gz::Math::Pose3d.new(1, 2, 3, 0, 0, Math::PI) -printf("A pose3d(1, 2, 3, 0, 0, IGN_PI) has the following values\n" + +printf("A pose3d(1, 2, 3, 0, 0, GZ_PI) has the following values\n" + "%f %f %f %f %f %f\n", p1.Pos().X(), p1.Pos().Y(), p1.Pos().Z(), p1.Rot().Euler().X(), p1.Rot().Euler().Y(), p1.Rot().Euler().Z()) diff --git a/examples/quaternion_from_euler.cc b/examples/quaternion_from_euler.cc index b1353c0b5..cff627101 100644 --- a/examples/quaternion_from_euler.cc +++ b/examples/quaternion_from_euler.cc @@ -53,9 +53,9 @@ int main(int argc, char **argv) return -1; } - double roll = IGN_DTOR(strToDouble(argv[1])); - double pitch = IGN_DTOR(strToDouble(argv[2])); - double yaw = IGN_DTOR(strToDouble(argv[3])); + double roll = GZ_DTOR(strToDouble(argv[1])); + double pitch = GZ_DTOR(strToDouble(argv[2])); + double yaw = GZ_DTOR(strToDouble(argv[3])); std::cout << "Converting Euler angles:\n"; printf(" roll % .6f radians\n" @@ -65,9 +65,9 @@ int main(int argc, char **argv) printf(" roll % 12.6f degrees\n" " pitch % 12.6f degrees\n" " yaw % 12.6f degrees\n", - IGN_RTOD(roll), - IGN_RTOD(pitch), - IGN_RTOD(yaw)); + GZ_RTOD(roll), + GZ_RTOD(pitch), + GZ_RTOD(yaw)); //![constructor] gz::math::Quaterniond q(roll, pitch, yaw); diff --git a/examples/quaternion_to_euler.cc b/examples/quaternion_to_euler.cc index 42886a4bf..379fa76c8 100644 --- a/examples/quaternion_to_euler.cc +++ b/examples/quaternion_to_euler.cc @@ -87,9 +87,9 @@ int main(int argc, char **argv) printf(" roll % .6f degrees\n" " pitch % .6f degrees\n" " yaw % .6f degrees\n", - IGN_RTOD(euler.X()), - IGN_RTOD(euler.Y()), - IGN_RTOD(euler.Z())); + GZ_RTOD(euler.X()), + GZ_RTOD(euler.Y()), + GZ_RTOD(euler.Z())); std::cout << "\nto Rotation matrix\n"; printf(" % .6f % .6f % .6f\n" diff --git a/include/gz/math/Angle.hh b/include/gz/math/Angle.hh index 2025c03af..635894581 100644 --- a/include/gz/math/Angle.hh +++ b/include/gz/math/Angle.hh @@ -22,23 +22,23 @@ #include #include -/// \def IGN_RTOD(d) +/// \def GZ_RTOD(d) /// \brief Macro that converts radians to degrees /// \param[in] r radians /// \return degrees -#define IGN_RTOD(r) ((r) * 180 / IGN_PI) +#define GZ_RTOD(r) ((r) * 180 / GZ_PI) -/// \def IGN_DTOR(d) +/// \def GZ_DTOR(d) /// \brief Converts degrees to radians /// \param[in] d degrees /// \return radians -#define IGN_DTOR(d) ((d) * IGN_PI / 180) +#define GZ_DTOR(d) ((d) * GZ_PI / 180) -/// \def IGN_NORMALIZE(a) +/// \def GZ_NORMALIZE(a) /// \brief Macro that normalizes an angle in the range -Pi to Pi /// \param[in] a angle /// \return the angle, in range -#define IGN_NORMALIZE(a) (atan2(sin(a), cos(a))) +#define GZ_NORMALIZE(a) (atan2(sin(a), cos(a))) namespace gz { @@ -66,15 +66,15 @@ namespace gz public: static const Angle &Zero; /// \brief An angle with a value of Pi. - /// Equivalent to math::Angle(IGN_PI). + /// Equivalent to math::Angle(GZ_PI). public: static const Angle Π /// \brief An angle with a value of Pi * 0.5. - /// Equivalent to math::Angle(IGN_PI * 0.5). + /// Equivalent to math::Angle(GZ_PI * 0.5). public: static const Angle &HalfPi; /// \brief An angle with a value of Pi * 2. - /// Equivalent to math::Angle(IGN_PI * 2). + /// Equivalent to math::Angle(GZ_PI * 2). public: static const Angle &TwoPi; /// \brief Default constructor that initializes an Angle to zero diff --git a/include/gz/math/AxisAlignedBox.hh b/include/gz/math/AxisAlignedBox.hh index 7609c75f1..d27e48a99 100644 --- a/include/gz/math/AxisAlignedBox.hh +++ b/include/gz/math/AxisAlignedBox.hh @@ -241,7 +241,7 @@ namespace gz double &_low, double &_high) const; /// \brief Private data pointer - IGN_UTILS_IMPL_PTR(dataPtr) + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/gz/math/DiffDriveOdometry.hh b/include/gz/math/DiffDriveOdometry.hh index 26efd9fbe..ad43dd724 100644 --- a/include/gz/math/DiffDriveOdometry.hh +++ b/include/gz/math/DiffDriveOdometry.hh @@ -67,12 +67,12 @@ namespace gz /// // ... Some time later /// /// // Both wheels have rotated the same amount - /// odom.Update(IGN_DTOR(2), IGN_DTOR(2), std::chrono::steady_clock::now()); + /// odom.Update(GZ_DTOR(2), GZ_DTOR(2), std::chrono::steady_clock::now()); /// /// // ... Some time later /// /// // The left wheel has rotated, the right wheel did not rotate - /// odom.Update(IGN_DTOR(4), IGN_DTOR(2), std::chrono::steady_clock::now()); + /// odom.Update(GZ_DTOR(4), GZ_DTOR(2), std::chrono::steady_clock::now()); /// \endcode class GZ_MATH_VISIBLE DiffDriveOdometry { @@ -131,7 +131,7 @@ namespace gz public: void SetVelocityRollingWindowSize(size_t _size); /// \brief Private data pointer. - IGN_UTILS_IMPL_PTR(dataPtr) + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/gz/math/Filter.hh b/include/gz/math/Filter.hh index bf81484ee..ef53aef6d 100644 --- a/include/gz/math/Filter.hh +++ b/include/gz/math/Filter.hh @@ -80,7 +80,7 @@ namespace gz // Documentation Inherited. public: virtual void Fc(double _fc, double _fs) override { - b1 = exp(-2.0 * IGN_PI * _fc / _fs); + b1 = exp(-2.0 * GZ_PI * _fc / _fs); a0 = 1.0 - b1; } @@ -179,7 +179,7 @@ namespace gz /// \param[in] _q Q coefficient. public: void Fc(double _fc, double _fs, double _q) { - double k = tan(IGN_PI * _fc / _fs); + double k = tan(GZ_PI * _fc / _fs); double kQuadDenom = k * k + k / _q + 1.0; this->a0 = k * k/ kQuadDenom; this->a1 = 2 * this->a0; diff --git a/include/gz/math/Frustum.hh b/include/gz/math/Frustum.hh index 7b715d91c..462e1385a 100644 --- a/include/gz/math/Frustum.hh +++ b/include/gz/math/Frustum.hh @@ -164,7 +164,7 @@ namespace gz private: void ComputePlanes(); /// \brief Private data pointer - IGN_UTILS_IMPL_PTR(dataPtr) + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/gz/math/GaussMarkovProcess.hh b/include/gz/math/GaussMarkovProcess.hh index 51e62e5b0..59a43f2c2 100644 --- a/include/gz/math/GaussMarkovProcess.hh +++ b/include/gz/math/GaussMarkovProcess.hh @@ -129,7 +129,7 @@ namespace gz public: double Update(double _dt); /// \brief Private data pointer. - IGN_UTILS_IMPL_PTR(dataPtr) + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/gz/math/Helpers.hh b/include/gz/math/Helpers.hh index 148860234..28364423b 100644 --- a/include/gz/math/Helpers.hh +++ b/include/gz/math/Helpers.hh @@ -36,47 +36,47 @@ template constexpr T IGN_MASSMATRIX3_DEFAULT_TOLERANCE = T(10); -/// \brief Define IGN_PI, IGN_PI_2, and IGN_PI_4. +/// \brief Define GZ_PI, GZ_PI_2, and GZ_PI_4. /// This was put here for Windows support. #ifdef M_PI -#define IGN_PI M_PI -#define IGN_PI_2 M_PI_2 -#define IGN_PI_4 M_PI_4 -#define IGN_SQRT2 M_SQRT2 +#define GZ_PI M_PI +#define GZ_PI_2 M_PI_2 +#define GZ_PI_4 M_PI_4 +#define GZ_SQRT2 M_SQRT2 #else -#define IGN_PI 3.14159265358979323846 -#define IGN_PI_2 1.57079632679489661923 -#define IGN_PI_4 0.78539816339744830962 -#define IGN_SQRT2 1.41421356237309504880 +#define GZ_PI 3.14159265358979323846 +#define GZ_PI_2 1.57079632679489661923 +#define GZ_PI_4 0.78539816339744830962 +#define GZ_SQRT2 1.41421356237309504880 #endif -/// \brief Define IGN_FP_VOLATILE for FP equality comparisons +/// \brief Define GZ_FP_VOLATILE for FP equality comparisons /// Use volatile parameters when checking floating point equality on /// the 387 math coprocessor to work around bugs from the 387 extra precision #if defined __FLT_EVAL_METHOD__ && __FLT_EVAL_METHOD__ == 2 -#define IGN_FP_VOLATILE volatile +#define GZ_FP_VOLATILE volatile #else -#define IGN_FP_VOLATILE +#define GZ_FP_VOLATILE #endif /// \brief Compute sphere volume /// \param[in] _radius Sphere radius -#define IGN_SPHERE_VOLUME(_radius) (4.0*IGN_PI*std::pow(_radius, 3)/3.0) +#define GZ_SPHERE_VOLUME(_radius) (4.0*GZ_PI*std::pow(_radius, 3)/3.0) /// \brief Compute cylinder volume /// \param[in] _r Cylinder base radius /// \param[in] _l Cylinder length -#define IGN_CYLINDER_VOLUME(_r, _l) (_l * IGN_PI * std::pow(_r, 2)) +#define GZ_CYLINDER_VOLUME(_r, _l) (_l * GZ_PI * std::pow(_r, 2)) /// \brief Compute box volume /// \param[in] _x X length /// \param[in] _y Y length /// \param[in] _z Z length -#define IGN_BOX_VOLUME(_x, _y, _z) (_x *_y * _z) +#define GZ_BOX_VOLUME(_x, _y, _z) (_x *_y * _z) /// \brief Compute box volume from a vector /// \param[in] _v Vector3d that contains the box's dimensions. -#define IGN_BOX_VOLUME_V(_v) (_v.X() *_v.Y() * _v.Z()) +#define GZ_BOX_VOLUME_V(_v) (_v.X() *_v.Y() * _v.Z()) namespace gz { @@ -381,7 +381,7 @@ namespace gz inline bool equal(const T &_a, const T &_b, const T &_epsilon = T(1e-6)) { - IGN_FP_VOLATILE T diff = std::abs(_a - _b); + GZ_FP_VOLATILE T diff = std::abs(_a - _b); return diff <= _epsilon; } diff --git a/include/gz/math/Kmeans.hh b/include/gz/math/Kmeans.hh index ff93ea53d..13c198d56 100644 --- a/include/gz/math/Kmeans.hh +++ b/include/gz/math/Kmeans.hh @@ -76,7 +76,7 @@ namespace gz /// \return The index of the closest centroid to the point _p. private: unsigned int ClosestCentroid(const Vector3d &_p) const; - IGN_UTILS_IMPL_PTR(dataPtr) + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/gz/math/MassMatrix3.hh b/include/gz/math/MassMatrix3.hh index e629a0b0a..9c31e146d 100644 --- a/include/gz/math/MassMatrix3.hh +++ b/include/gz/math/MassMatrix3.hh @@ -516,8 +516,8 @@ namespace gz // sort the moments from smallest to largest T moment0 = (b + 2*sqrt(p) * cos(delta / 3.0)) / 3.0; - T moment1 = (b + 2*sqrt(p) * cos((delta + 2*IGN_PI)/3.0)) / 3.0; - T moment2 = (b + 2*sqrt(p) * cos((delta - 2*IGN_PI)/3.0)) / 3.0; + T moment1 = (b + 2*sqrt(p) * cos((delta + 2*GZ_PI)/3.0)) / 3.0; + T moment2 = (b + 2*sqrt(p) * cos((delta - 2*GZ_PI)/3.0)) / 3.0; sort3(moment0, moment1, moment2); return Vector3(moment0, moment1, moment2); } @@ -673,7 +673,7 @@ namespace gz // [-1 0 0] // That is equivalent to a 90 degree pitch if (unequalMoment == 0) - result *= Quaternion(0, IGN_PI_2, 0); + result *= Quaternion(0, GZ_PI_2, 0); return result; } @@ -950,7 +950,7 @@ namespace gz { return false; } - T volume = IGN_PI * _radius * _radius * _length; + T volume = GZ_PI * _radius * _radius * _length; return this->SetFromCylinderZ(_mat.Density() * volume, _length, _radius, _rot); } @@ -1020,7 +1020,7 @@ namespace gz return false; } - T volume = (4.0/3.0) * IGN_PI * std::pow(_radius, 3); + T volume = (4.0/3.0) * GZ_PI * std::pow(_radius, 3); return this->SetFromSphere(_mat.Density() * volume, _radius); } diff --git a/include/gz/math/Material.hh b/include/gz/math/Material.hh index e3e2f8ac7..99be5d5e8 100644 --- a/include/gz/math/Material.hh +++ b/include/gz/math/Material.hh @@ -134,7 +134,7 @@ namespace gz public: void SetDensity(const double _density); /// \brief Private data pointer. - IGN_UTILS_IMPL_PTR(dataPtr) + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/gz/math/Matrix4.hh b/include/gz/math/Matrix4.hh index 13ffc592f..de26018ff 100644 --- a/include/gz/math/Matrix4.hh +++ b/include/gz/math/Matrix4.hh @@ -305,15 +305,15 @@ namespace gz if (m31 < 0.0) { - euler.Y(IGN_PI / 2.0); - euler2.Y(IGN_PI / 2.0); + euler.Y(GZ_PI / 2.0); + euler2.Y(GZ_PI / 2.0); euler.X(atan2(m12, m13)); euler2.X(atan2(m12, m13)); } else { - euler.Y(-IGN_PI / 2.0); - euler2.Y(-IGN_PI / 2.0); + euler.Y(-GZ_PI / 2.0); + euler2.Y(-GZ_PI / 2.0); euler.X(atan2(-m12, -m13)); euler2.X(atan2(-m12, -m13)); } @@ -321,7 +321,7 @@ namespace gz else { euler.Y(-asin(m31)); - euler2.Y(IGN_PI - euler.Y()); + euler2.Y(GZ_PI - euler.Y()); euler.X(atan2(m32 / cos(euler.Y()), m33 / cos(euler.Y()))); euler2.X(atan2(m32 / cos(euler2.Y()), m33 / cos(euler2.Y()))); diff --git a/include/gz/math/PID.hh b/include/gz/math/PID.hh index 7092cc77f..0b3276b89 100644 --- a/include/gz/math/PID.hh +++ b/include/gz/math/PID.hh @@ -183,7 +183,7 @@ namespace gz public: void Reset(); /// \brief Pointer to private data. - IGN_UTILS_IMPL_PTR(dataPtr) + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/gz/math/Pose3.hh b/include/gz/math/Pose3.hh index 02b5dc29d..31cb748f7 100644 --- a/include/gz/math/Pose3.hh +++ b/include/gz/math/Pose3.hh @@ -57,7 +57,7 @@ namespace gz /// /// # Construct a pose at position 1, 2, 3 with a yaw of PI radians. /// p1 = Gz::Math::Pose3d.new(1, 2, 3, 0, 0, Math::PI) - /// printf("A pose3d(1, 2, 3, 0, 0, IGN_PI) has the following values\n" + + /// printf("A pose3d(1, 2, 3, 0, 0, GZ_PI) has the following values\n" + /// "%f %f %f %f %f %f\n", p1.Pos().X(), p1.Pos().Y(), p1.Pos().Z(), /// p1.Rot().Euler().X(), p1.Rot().Euler().Y(), p1.Rot().Euler().Z()) /// diff --git a/include/gz/math/Quaternion.hh b/include/gz/math/Quaternion.hh index 3aecf73c2..0ef1e38cc 100644 --- a/include/gz/math/Quaternion.hh +++ b/include/gz/math/Quaternion.hh @@ -447,11 +447,11 @@ namespace gz T sarg = -2 * (copy.qx*copy.qz - copy.qw * copy.qy); if (sarg <= T(-1.0)) { - vec.Y(T(-0.5*IGN_PI)); + vec.Y(T(-0.5*GZ_PI)); } else if (sarg >= T(1.0)) { - vec.Y(T(0.5*IGN_PI)); + vec.Y(T(0.5*GZ_PI)); } else { diff --git a/include/gz/math/RollingMean.hh b/include/gz/math/RollingMean.hh index 6b5ce5865..ac15da710 100644 --- a/include/gz/math/RollingMean.hh +++ b/include/gz/math/RollingMean.hh @@ -65,7 +65,7 @@ namespace gz public: size_t WindowSize() const; /// \brief Private data pointer. - IGN_UTILS_IMPL_PTR(dataPtr) + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/gz/math/RotationSpline.hh b/include/gz/math/RotationSpline.hh index a45deff91..643280a89 100644 --- a/include/gz/math/RotationSpline.hh +++ b/include/gz/math/RotationSpline.hh @@ -111,7 +111,7 @@ namespace gz public: void RecalcTangents(); /// \brief Private data pointer - IGN_UTILS_IMPL_PTR(dataPtr) + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/gz/math/SemanticVersion.hh b/include/gz/math/SemanticVersion.hh index a246a114e..3eca0c99e 100644 --- a/include/gz/math/SemanticVersion.hh +++ b/include/gz/math/SemanticVersion.hh @@ -131,7 +131,7 @@ namespace gz return _out; } - IGN_UTILS_IMPL_PTR(dataPtr) + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/gz/math/SphericalCoordinates.hh b/include/gz/math/SphericalCoordinates.hh index 755a6f83e..7ea183a6b 100644 --- a/include/gz/math/SphericalCoordinates.hh +++ b/include/gz/math/SphericalCoordinates.hh @@ -233,7 +233,7 @@ namespace gz public: bool operator!=(const SphericalCoordinates &_sc) const; /// \brief Pointer to the private data - IGN_UTILS_IMPL_PTR(dataPtr) + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/gz/math/Spline.hh b/include/gz/math/Spline.hh index c9d6650a0..9ae1db47e 100644 --- a/include/gz/math/Spline.hh +++ b/include/gz/math/Spline.hh @@ -255,7 +255,7 @@ namespace gz /// \internal /// \brief Private data pointer - IGN_UTILS_IMPL_PTR(dataPtr) + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/gz/math/Stopwatch.hh b/include/gz/math/Stopwatch.hh index c52cf1845..9b305e5ac 100644 --- a/include/gz/math/Stopwatch.hh +++ b/include/gz/math/Stopwatch.hh @@ -114,7 +114,7 @@ namespace gz public: bool operator!=(const Stopwatch &_watch) const; /// \brief Private data pointer. - IGN_UTILS_IMPL_PTR(dataPtr) + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/gz/math/Temperature.hh b/include/gz/math/Temperature.hh index 54a2f7ccc..03f629a34 100644 --- a/include/gz/math/Temperature.hh +++ b/include/gz/math/Temperature.hh @@ -362,7 +362,7 @@ namespace gz return _in; } - IGN_UTILS_IMPL_PTR(dataPtr) + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/gz/math/Vector3Stats.hh b/include/gz/math/Vector3Stats.hh index bb62c260a..a9b17dbc9 100644 --- a/include/gz/math/Vector3Stats.hh +++ b/include/gz/math/Vector3Stats.hh @@ -97,7 +97,7 @@ namespace gz public: SignalStats &Mag(); /// \brief Pointer to private data. - IGN_UTILS_IMPL_PTR(dataPtr) + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/gz/math/detail/Capsule.hh b/include/gz/math/detail/Capsule.hh index 8fb0f19ca..8169b2624 100644 --- a/include/gz/math/detail/Capsule.hh +++ b/include/gz/math/detail/Capsule.hh @@ -106,7 +106,7 @@ std::optional< MassMatrix3 > Capsule::MassMatrix() const // mass and moment of inertia of hemisphere about centroid const T r2 = this->radius * this->radius; const T hemisphereMass = this->material.Density() * - 2. / 3. * IGN_PI * r2 * this->radius; + 2. / 3. * GZ_PI * r2 * this->radius; // efunda.com/math/solids/solids_display.cfm?SolidName=Hemisphere const T ixx = 83. / 320. * hemisphereMass * r2; const T izz = 2. / 5. * hemisphereMass * r2; @@ -135,7 +135,7 @@ std::optional< MassMatrix3 > Capsule::MassMatrix() const template T Capsule::Volume() const { - return IGN_PI * std::pow(this->radius, 2) * + return GZ_PI * std::pow(this->radius, 2) * (this->length + 4. / 3. * this->radius); } diff --git a/include/gz/math/detail/Cylinder.hh b/include/gz/math/detail/Cylinder.hh index 8220a50f8..f4db1b335 100644 --- a/include/gz/math/detail/Cylinder.hh +++ b/include/gz/math/detail/Cylinder.hh @@ -120,7 +120,7 @@ bool Cylinder::MassMatrix(MassMatrix3d &_massMat) const template T Cylinder::Volume() const { - return IGN_PI * std::pow(this->radius, 2) * + return GZ_PI * std::pow(this->radius, 2) * this->length; } diff --git a/include/gz/math/detail/Ellipsoid.hh b/include/gz/math/detail/Ellipsoid.hh index 16ba4c8cb..5b9db31a2 100644 --- a/include/gz/math/detail/Ellipsoid.hh +++ b/include/gz/math/detail/Ellipsoid.hh @@ -96,7 +96,7 @@ std::optional< MassMatrix3 > Ellipsoid::MassMatrix() const template T Ellipsoid::Volume() const { - const T kFourThirdsPi = 4. * IGN_PI / 3.; + const T kFourThirdsPi = 4. * GZ_PI / 3.; return kFourThirdsPi * this->radii.X() * this->radii.Y() * this->radii.Z(); } diff --git a/include/gz/math/detail/Sphere.hh b/include/gz/math/detail/Sphere.hh index 04a43be6a..597c76639 100644 --- a/include/gz/math/detail/Sphere.hh +++ b/include/gz/math/detail/Sphere.hh @@ -92,7 +92,7 @@ bool Sphere::MassMatrix(MassMatrix3d &_massMat) const template T Sphere::Volume() const { - return (4.0/3.0) * IGN_PI * std::pow(this->radius, 3); + return (4.0/3.0) * GZ_PI * std::pow(this->radius, 3); } ////////////////////////////////////////////////// @@ -115,7 +115,7 @@ T Sphere::VolumeBelow(const Plane &_plane) const } auto h = r - dist; - return IGN_PI * h * h * (3 * r - h) / 3; + return GZ_PI * h * h * (3 * r - h) / 3; } ////////////////////////////////////////////////// diff --git a/include/ignition/math/Angle.hh b/include/ignition/math/Angle.hh index 1bbb9750e..834fcc6e4 100644 --- a/include/ignition/math/Angle.hh +++ b/include/ignition/math/Angle.hh @@ -17,3 +17,7 @@ #include #include + +#define IGN_RTOD(r) GZ_RTOD(r) +#define IGN_DTOR(d) GZ_DTOR(d) +#define IGN_NORMALIZE(a) GZ_NORMALIZE(a) diff --git a/include/ignition/math/Helpers.hh b/include/ignition/math/Helpers.hh index efd519133..6690ec80e 100644 --- a/include/ignition/math/Helpers.hh +++ b/include/ignition/math/Helpers.hh @@ -17,3 +17,15 @@ #include #include + +#define IGN_PI GZ_PI +#define IGN_PI_2 GZ_PI_2 +#define IGN_PI_4 GZ_PI_4 +#define IGN_SQRT2 GZ_SQRT2 + +#define IGN_FP_VOLATILE GZ_FP_VOLATILE + +#define IGN_SPHERE_VOLUME(_radius) GZ_SPHERE_VOLUME(_radius) +#define IGN_CYLINDER_VOLUME(_r, _l) GZ_CYLINDER_VOLUME(_r, _l) +#define IGN_BOX_VOLUME(_x, _y, _z) GZ_BOX_VOLUME(_x, _y, _z) +#define IGN_BOX_VOLUME_V(_v) GZ_BOX_VOLUME_V(_v) diff --git a/src/Angle.cc b/src/Angle.cc index 29d733b4a..30c1e856c 100644 --- a/src/Angle.cc +++ b/src/Angle.cc @@ -24,9 +24,9 @@ namespace { // Use constexpr storage for the Color constants, to avoid the C++ static // initialization order fiasco. constexpr Angle gZero(0); -constexpr Angle gPi(IGN_PI); -constexpr Angle gHalfPi(IGN_PI_2); -constexpr Angle gTwoPi(IGN_PI * 2.0); +constexpr Angle gPi(GZ_PI); +constexpr Angle gHalfPi(GZ_PI_2); +constexpr Angle gTwoPi(GZ_PI * 2.0); } // namespace @@ -50,13 +50,13 @@ void Angle::SetRadian(double _radian) ////////////////////////////////////////////////// void Angle::Degree(double _degree) { - this->value = _degree * IGN_PI / 180.0; + this->value = _degree * GZ_PI / 180.0; } ////////////////////////////////////////////////// void Angle::SetDegree(double _degree) { - this->value = _degree * IGN_PI / 180.0; + this->value = _degree * GZ_PI / 180.0; } ////////////////////////////////////////////////// @@ -68,7 +68,7 @@ double Angle::Radian() const ////////////////////////////////////////////////// double Angle::Degree() const { - return this->value * 180.0 / IGN_PI; + return this->value * 180.0 / GZ_PI; } ////////////////////////////////////////////////// diff --git a/src/Angle_TEST.cc b/src/Angle_TEST.cc index ba5e53cdb..7e6089b05 100644 --- a/src/Angle_TEST.cc +++ b/src/Angle_TEST.cc @@ -31,13 +31,13 @@ TEST(AngleTest, Angle) EXPECT_TRUE(math::equal(0.0, angle1.Radian())); angle1.SetDegree(90.0); - EXPECT_TRUE(angle1 == IGN_PI_2); + EXPECT_TRUE(angle1 == GZ_PI_2); angle1.SetDegree(180.0); - EXPECT_TRUE(angle1 == IGN_PI); + EXPECT_TRUE(angle1 == GZ_PI); - EXPECT_FALSE(angle1 == IGN_PI + 0.1); - EXPECT_TRUE(angle1 == IGN_PI + 0.0001); - EXPECT_TRUE(angle1 == IGN_PI - 0.0001); + EXPECT_FALSE(angle1 == GZ_PI + 0.1); + EXPECT_TRUE(angle1 == GZ_PI + 0.0001); + EXPECT_TRUE(angle1 == GZ_PI - 0.0001); EXPECT_TRUE(math::Angle(0) == math::Angle(0)); EXPECT_TRUE(math::Angle(0) == math::Angle(0.001)); @@ -47,15 +47,15 @@ TEST(AngleTest, Angle) math::Angle angle(0.5); EXPECT_TRUE(math::equal(0.5, angle.Radian())); - angle.SetRadian(IGN_PI_2); - EXPECT_TRUE(math::equal(IGN_RTOD(IGN_PI_2), angle.Degree())); + angle.SetRadian(GZ_PI_2); + EXPECT_TRUE(math::equal(GZ_RTOD(GZ_PI_2), angle.Degree())); - angle.SetRadian(IGN_PI); - EXPECT_TRUE(math::equal(IGN_RTOD(IGN_PI), angle.Degree())); + angle.SetRadian(GZ_PI); + EXPECT_TRUE(math::equal(GZ_RTOD(GZ_PI), angle.Degree())); math::Angle normalized = angle.Normalized(); angle.Normalize(); - EXPECT_TRUE(math::equal(IGN_RTOD(IGN_PI), angle.Degree())); + EXPECT_TRUE(math::equal(GZ_RTOD(GZ_PI), angle.Degree())); EXPECT_EQ(normalized, angle); angle = math::Angle(0.1) + math::Angle(0.2); diff --git a/src/AxisAlignedBox_TEST.cc b/src/AxisAlignedBox_TEST.cc index 46d3ccc79..360c6d1c3 100644 --- a/src/AxisAlignedBox_TEST.cc +++ b/src/AxisAlignedBox_TEST.cc @@ -409,7 +409,7 @@ TEST(AxisAlignedBoxTest, Intersect) EXPECT_TRUE(intersect); EXPECT_TRUE(b.IntersectCheck(Vector3d(2, 2, 0), Vector3d(-1, -1, 0), 0, 1000)); - EXPECT_DOUBLE_EQ(dist, IGN_SQRT2); + EXPECT_DOUBLE_EQ(dist, GZ_SQRT2); EXPECT_DOUBLE_EQ(std::get<1>(b.IntersectDist(Vector3d(2, 2, 0), Vector3d(-1, -1, 0), 0, 1000)), dist); EXPECT_EQ(pt, Vector3d(1, 1, 0)); @@ -429,7 +429,7 @@ TEST(AxisAlignedBoxTest, Intersect) EXPECT_TRUE(intersect); EXPECT_TRUE(b.IntersectCheck(Vector3d(-1, -2, 0), Vector3d(1, 1, 0), 0, 1000)); - EXPECT_DOUBLE_EQ(dist, 2*IGN_SQRT2); + EXPECT_DOUBLE_EQ(dist, 2*GZ_SQRT2); EXPECT_DOUBLE_EQ(std::get<1>(b.IntersectDist(Vector3d(-1, -2, 0), Vector3d(1, 1, 0), 0, 1000)), dist); EXPECT_EQ(pt, Vector3d(1, 0, 0)); @@ -439,7 +439,7 @@ TEST(AxisAlignedBoxTest, Intersect) EXPECT_TRUE(intersect); EXPECT_TRUE(b.IntersectCheck(Vector3d(2, 1, 0), Vector3d(-1, -1, 0), 0, 1000)); - EXPECT_DOUBLE_EQ(dist, IGN_SQRT2); + EXPECT_DOUBLE_EQ(dist, GZ_SQRT2); EXPECT_DOUBLE_EQ(std::get<1>(b.IntersectDist(Vector3d(2, 1, 0), Vector3d(-1, -1, 0), 0, 1000)), dist); EXPECT_EQ(pt, Vector3d(1, 0, 0)); diff --git a/src/Capsule_TEST.cc b/src/Capsule_TEST.cc index c3547c274..15b8599fc 100644 --- a/src/Capsule_TEST.cc +++ b/src/Capsule_TEST.cc @@ -83,7 +83,7 @@ TEST(CapsuleTest, VolumeAndDensity) { double mass = 1.0; math::Capsuled capsule(1.0, 0.001); - double expectedVolume = (IGN_PI * std::pow(0.001, 2) * (1.0 + 4./3. * 0.001)); + double expectedVolume = (GZ_PI * std::pow(0.001, 2) * (1.0 + 4./3. * 0.001)); EXPECT_DOUBLE_EQ(expectedVolume, capsule.Volume()); double expectedDensity = mass / expectedVolume; @@ -103,8 +103,8 @@ TEST(CapsuleTest, Mass) math::Capsuled capsule(l, r); capsule.SetDensityFromMass(mass); - const double cylinderVolume = IGN_PI * r*r * l; - const double sphereVolume = IGN_PI * 4. / 3. * r*r*r; + const double cylinderVolume = GZ_PI * r*r * l; + const double sphereVolume = GZ_PI * 4. / 3. * r*r*r; const double volume = cylinderVolume + sphereVolume; const double cylinderMass = mass * cylinderVolume / volume; const double sphereMass = mass * sphereVolume / volume; diff --git a/src/Cylinder_TEST.cc b/src/Cylinder_TEST.cc index 4f195f7c5..5730a7fe7 100644 --- a/src/Cylinder_TEST.cc +++ b/src/Cylinder_TEST.cc @@ -105,7 +105,7 @@ TEST(CylinderTest, VolumeAndDensity) { double mass = 1.0; math::Cylinderd cylinder(1.0, 0.001); - double expectedVolume = (IGN_PI * std::pow(0.001, 2) * 1.0); + double expectedVolume = (GZ_PI * std::pow(0.001, 2) * 1.0); EXPECT_DOUBLE_EQ(expectedVolume, cylinder.Volume()); double expectedDensity = mass / expectedVolume; diff --git a/src/DiffDriveOdometry_TEST.cc b/src/DiffDriveOdometry_TEST.cc index a71974423..9194f48cf 100644 --- a/src/DiffDriveOdometry_TEST.cc +++ b/src/DiffDriveOdometry_TEST.cc @@ -36,7 +36,7 @@ TEST(DiffDriveOdometryTest, DiffDriveOdometry) double wheelSeparation = 2.0; double wheelRadius = 0.5; - double wheelCircumference = 2 * IGN_PI * wheelRadius; + double wheelCircumference = 2 * GZ_PI * wheelRadius; // This is the linear distance traveled per degree of wheel rotation. double distPerDegree = wheelCircumference / 360.0; @@ -53,7 +53,7 @@ TEST(DiffDriveOdometryTest, DiffDriveOdometry) // Sleep for a little while, then update the odometry with the new wheel // position. auto time1 = startTime + std::chrono::milliseconds(100); - EXPECT_TRUE(odom.Update(IGN_DTOR(1.0), IGN_DTOR(1.0), time1)); + EXPECT_TRUE(odom.Update(GZ_DTOR(1.0), GZ_DTOR(1.0), time1)); EXPECT_DOUBLE_EQ(0.0, *odom.Heading()); EXPECT_DOUBLE_EQ(distPerDegree, odom.X()); EXPECT_DOUBLE_EQ(0.0, odom.Y()); @@ -65,7 +65,7 @@ TEST(DiffDriveOdometryTest, DiffDriveOdometry) // Sleep again, then update the odometry with the new wheel position. auto time2 = time1 + std::chrono::milliseconds(100); - EXPECT_TRUE(odom.Update(IGN_DTOR(2.0), IGN_DTOR(2.0), time2)); + EXPECT_TRUE(odom.Update(GZ_DTOR(2.0), GZ_DTOR(2.0), time2)); EXPECT_DOUBLE_EQ(0.0, *odom.Heading()); EXPECT_NEAR(distPerDegree * 2.0, odom.X(), 3e-6); EXPECT_DOUBLE_EQ(0.0, odom.Y()); @@ -87,7 +87,7 @@ TEST(DiffDriveOdometryTest, DiffDriveOdometry) // Sleep again, this time move 2 degrees in 100ms. time1 = startTime + std::chrono::milliseconds(100); - EXPECT_TRUE(odom.Update(IGN_DTOR(2.0), IGN_DTOR(2.0), time1)); + EXPECT_TRUE(odom.Update(GZ_DTOR(2.0), GZ_DTOR(2.0), time1)); EXPECT_DOUBLE_EQ(0.0, *odom.Heading()); EXPECT_NEAR(distPerDegree * 2.0, odom.X(), 3e-6); EXPECT_DOUBLE_EQ(0.0, odom.Y()); @@ -100,7 +100,7 @@ TEST(DiffDriveOdometryTest, DiffDriveOdometry) // Sleep again, this time rotate the right wheel by 1 degree. time2 = time1 + std::chrono::milliseconds(100); - EXPECT_TRUE(odom.Update(IGN_DTOR(2.0), IGN_DTOR(3.0), time2)); + EXPECT_TRUE(odom.Update(GZ_DTOR(2.0), GZ_DTOR(3.0), time2)); // The heading should be the arc tangent of the linear distance traveled // by the right wheel (the left wheel was stationary) divided by the // wheel separation. diff --git a/src/Ellipsoid_TEST.cc b/src/Ellipsoid_TEST.cc index 682b9c1e9..c9adb3e03 100644 --- a/src/Ellipsoid_TEST.cc +++ b/src/Ellipsoid_TEST.cc @@ -84,14 +84,14 @@ TEST(EllipsoidTest, VolumeAndDensity) // Basic sphere math::Ellipsoidd ellipsoid(2. * math::Vector3d::One); - double expectedVolume = (4. / 3.) * IGN_PI * std::pow(2.0, 3); + double expectedVolume = (4. / 3.) * GZ_PI * std::pow(2.0, 3); EXPECT_DOUBLE_EQ(expectedVolume, ellipsoid.Volume()); double expectedDensity = mass / expectedVolume; EXPECT_DOUBLE_EQ(expectedDensity, ellipsoid.DensityFromMass(mass)); math::Ellipsoidd ellipsoid2(math::Vector3d(1, 10, 100)); - expectedVolume = (4. / 3.) * IGN_PI * 1. * 10. * 100.; + expectedVolume = (4. / 3.) * GZ_PI * 1. * 10. * 100.; EXPECT_DOUBLE_EQ(expectedVolume, ellipsoid2.Volume()); expectedDensity = mass / expectedVolume; diff --git a/src/Frustum.cc b/src/Frustum.cc index dc9f2f8a8..269cb5291 100644 --- a/src/Frustum.cc +++ b/src/Frustum.cc @@ -45,7 +45,7 @@ class Frustum::Implementation /// The field of view is the angle between the frustum's vertex and the /// edges of the near or far plane. /// This value represents the horizontal angle. - public: math::Angle fov {IGN_DTOR(45)}; + public: math::Angle fov {GZ_DTOR(45)}; /// \brief Aspect ratio of the near and far planes. This is the // width divided by the height. diff --git a/src/Frustum_TEST.cc b/src/Frustum_TEST.cc index 1c9949bed..81e70f418 100644 --- a/src/Frustum_TEST.cc +++ b/src/Frustum_TEST.cc @@ -30,7 +30,7 @@ TEST(FrustumTest, Constructor) EXPECT_DOUBLE_EQ(frustum.Near(), 0.0); EXPECT_DOUBLE_EQ(frustum.Far(), 1.0); - EXPECT_EQ(frustum.FOV(), IGN_DTOR(45)); + EXPECT_EQ(frustum.FOV(), GZ_DTOR(45)); EXPECT_DOUBLE_EQ(frustum.AspectRatio(), 1.0); EXPECT_EQ(frustum.Pose(), Pose3d::Zero); } @@ -45,7 +45,7 @@ TEST(FrustumTest, CopyConstructor) // Far distance 10, // Field of view - Angle(IGN_DTOR(45)), + Angle(GZ_DTOR(45)), // Aspect ratio 320.0/240.0, // Pose @@ -88,11 +88,11 @@ TEST(FrustumTest, AssignmentOperator) // Far distance 10, // Field of view - Angle(IGN_DTOR(45)), + Angle(GZ_DTOR(45)), // Aspect ratio 320.0/240.0, // Pose - Pose3d(0, 0, 0, 0, 0, IGN_DTOR(45))); + Pose3d(0, 0, 0, 0, 0, GZ_DTOR(45))); Frustum frustum2; frustum2 = frustum; @@ -132,7 +132,7 @@ TEST(FrustumTest, PyramidXAxisPos) // Far distance 10, // Field of view - Angle(IGN_DTOR(45)), + Angle(GZ_DTOR(45)), // Aspect ratio 320.0/240.0, // Pose @@ -161,11 +161,11 @@ TEST(FrustumTest, PyramidXAxisNeg) // Far distance 10, // Field of view - Angle(IGN_DTOR(45)), + Angle(GZ_DTOR(45)), // Aspect ratio 320.0/240.0, // Pose - Pose3d(0, 0, 0, 0, 0, IGN_PI)); + Pose3d(0, 0, 0, 0, 0, GZ_PI)); EXPECT_FALSE(frustum.Contains(Vector3d(0, 0, 0))); EXPECT_FALSE(frustum.Contains(Vector3d(-0.5, 0, 0))); @@ -191,11 +191,11 @@ TEST(FrustumTest, PyramidYAxis) // Far distance 5, // Field of view - Angle(IGN_DTOR(45)), + Angle(GZ_DTOR(45)), // Aspect ratio 1.0, // Pose - Pose3d(0, 0, 0, 0, 0, IGN_PI*0.5)); + Pose3d(0, 0, 0, 0, 0, GZ_PI*0.5)); EXPECT_FALSE(frustum.Contains(Vector3d(0, 0, 0))); EXPECT_FALSE(frustum.Contains(Vector3d(1, 0, 0))); @@ -221,11 +221,11 @@ TEST(FrustumTest, PyramidZAxis) // Far distance 10, // Field of view - Angle(IGN_DTOR(45)), + Angle(GZ_DTOR(45)), // Aspect ratio 1.0, // Pose - Pose3d(0, 0, 0, 0, IGN_PI*0.5, 0)); + Pose3d(0, 0, 0, 0, GZ_PI*0.5, 0)); EXPECT_FALSE(frustum.Contains(Vector3d(0, 0, 0))); EXPECT_FALSE(frustum.Contains(Vector3d(0, 0, -0.9))); @@ -252,11 +252,11 @@ TEST(FrustumTest, NearFar) // Far distance 10, // Field of view - Angle(IGN_DTOR(45)), + Angle(GZ_DTOR(45)), // Aspect ratio 1.0, // Pose - Pose3d(0, 0, 0, 0, IGN_PI*0.5, 0)); + Pose3d(0, 0, 0, 0, GZ_PI*0.5, 0)); EXPECT_DOUBLE_EQ(frustum.Near(), 1.0); EXPECT_DOUBLE_EQ(frustum.Far(), 10.0); @@ -277,13 +277,13 @@ TEST(FrustumTest, FOV) // Far distance 10, // Field of view - Angle(IGN_DTOR(45)), + Angle(GZ_DTOR(45)), // Aspect ratio 1.0, // Pose - Pose3d(0, 0, 0, 0, IGN_PI*0.5, 0)); + Pose3d(0, 0, 0, 0, GZ_PI*0.5, 0)); - EXPECT_EQ(frustum.FOV(), math::Angle(IGN_DTOR(45))); + EXPECT_EQ(frustum.FOV(), math::Angle(GZ_DTOR(45))); frustum.SetFOV(1.5707); @@ -299,11 +299,11 @@ TEST(FrustumTest, AspectRatio) // Far distance 10, // Field of view - Angle(IGN_DTOR(45)), + Angle(GZ_DTOR(45)), // Aspect ratio 1.0, // Pose - Pose3d(0, 0, 0, 0, IGN_PI*0.5, 0)); + Pose3d(0, 0, 0, 0, GZ_PI*0.5, 0)); EXPECT_DOUBLE_EQ(frustum.AspectRatio(), 1); @@ -321,17 +321,17 @@ TEST(FrustumTest, Pose) // Far distance 10, // Field of view - Angle(IGN_DTOR(45)), + Angle(GZ_DTOR(45)), // Aspect ratio 1.0, // Pose - Pose3d(0, 0, 0, 0, IGN_PI*0.5, 0)); + Pose3d(0, 0, 0, 0, GZ_PI*0.5, 0)); - EXPECT_EQ(frustum.Pose(), Pose3d(0, 0, 0, 0, IGN_PI*0.5, 0)); + EXPECT_EQ(frustum.Pose(), Pose3d(0, 0, 0, 0, GZ_PI*0.5, 0)); - frustum.SetPose(Pose3d(1, 2, 3, IGN_PI, 0, 0)); + frustum.SetPose(Pose3d(1, 2, 3, GZ_PI, 0, 0)); - EXPECT_EQ(frustum.Pose(), Pose3d(1, 2, 3, IGN_PI, 0, 0)); + EXPECT_EQ(frustum.Pose(), Pose3d(1, 2, 3, GZ_PI, 0, 0)); } ///////////////////////////////////////////////// @@ -343,11 +343,11 @@ TEST(FrustumTest, PoseContains) // Far distance 10, // Field of view - Angle(IGN_DTOR(60)), + Angle(GZ_DTOR(60)), // Aspect ratio 1920.0/1080.0, // Pose - Pose3d(0, -5, 0, 0, 0, IGN_PI*0.5)); + Pose3d(0, -5, 0, 0, 0, GZ_PI*0.5)); // Test the near clip boundary EXPECT_FALSE(frustum.Contains(Vector3d(0, -4.01, 0))); @@ -366,44 +366,44 @@ TEST(FrustumTest, PoseContains) // Compute near clip points Vector3d nearTopLeft( - -tan(IGN_DTOR(30)) + offset, + -tan(GZ_DTOR(30)) + offset, frustum.Pose().Pos().Y() + frustum.Near() + offset, - tan(IGN_DTOR(30)) / frustum.AspectRatio() - offset); + tan(GZ_DTOR(30)) / frustum.AspectRatio() - offset); Vector3d nearTopLeftBad( - -tan(IGN_DTOR(30)) - offset, + -tan(GZ_DTOR(30)) - offset, frustum.Pose().Pos().Y() + frustum.Near() - offset, - tan(IGN_DTOR(30)) / frustum.AspectRatio() + offset); + tan(GZ_DTOR(30)) / frustum.AspectRatio() + offset); Vector3d nearTopRight( - tan(IGN_DTOR(30)) - offset, + tan(GZ_DTOR(30)) - offset, frustum.Pose().Pos().Y() + frustum.Near() + offset, - tan(IGN_DTOR(30)) / frustum.AspectRatio() - offset); + tan(GZ_DTOR(30)) / frustum.AspectRatio() - offset); Vector3d nearTopRightBad( - tan(IGN_DTOR(30)) + offset, + tan(GZ_DTOR(30)) + offset, frustum.Pose().Pos().Y() + frustum.Near() - offset, - tan(IGN_DTOR(30)) / frustum.AspectRatio() + offset); + tan(GZ_DTOR(30)) / frustum.AspectRatio() + offset); Vector3d nearBottomLeft( - -tan(IGN_DTOR(30)) + offset, + -tan(GZ_DTOR(30)) + offset, frustum.Pose().Pos().Y() + frustum.Near() + offset, - -tan(IGN_DTOR(30)) / frustum.AspectRatio() + offset); + -tan(GZ_DTOR(30)) / frustum.AspectRatio() + offset); Vector3d nearBottomLeftBad( - -tan(IGN_DTOR(30)) - offset, + -tan(GZ_DTOR(30)) - offset, frustum.Pose().Pos().Y() + frustum.Near() - offset, - -tan(IGN_DTOR(30)) / frustum.AspectRatio() - offset); + -tan(GZ_DTOR(30)) / frustum.AspectRatio() - offset); Vector3d nearBottomRight( - tan(IGN_DTOR(30)) - offset, + tan(GZ_DTOR(30)) - offset, frustum.Pose().Pos().Y() + frustum.Near() + offset, - -tan(IGN_DTOR(30)) / frustum.AspectRatio() + offset); + -tan(GZ_DTOR(30)) / frustum.AspectRatio() + offset); Vector3d nearBottomRightBad( - tan(IGN_DTOR(30)) + offset, + tan(GZ_DTOR(30)) + offset, frustum.Pose().Pos().Y() + frustum.Near() - offset, - -tan(IGN_DTOR(30)) / frustum.AspectRatio() - offset); + -tan(GZ_DTOR(30)) / frustum.AspectRatio() - offset); // Test near clip corners EXPECT_TRUE(frustum.Contains(nearTopLeft)); @@ -420,44 +420,44 @@ TEST(FrustumTest, PoseContains) // Compute far clip points Vector3d farTopLeft( - -tan(IGN_DTOR(30)) * frustum.Far() + offset, + -tan(GZ_DTOR(30)) * frustum.Far() + offset, frustum.Pose().Pos().Y() + frustum.Far() - offset, - (tan(IGN_DTOR(30)) * frustum.Far()) / frustum.AspectRatio() - offset); + (tan(GZ_DTOR(30)) * frustum.Far()) / frustum.AspectRatio() - offset); Vector3d farTopLeftBad( - -tan(IGN_DTOR(30))*frustum.Far() - offset, + -tan(GZ_DTOR(30))*frustum.Far() - offset, frustum.Pose().Pos().Y() + frustum.Far() + offset, - (tan(IGN_DTOR(30) * frustum.Far())) / frustum.AspectRatio() + offset); + (tan(GZ_DTOR(30) * frustum.Far())) / frustum.AspectRatio() + offset); Vector3d farTopRight( - tan(IGN_DTOR(30))*frustum.Far() - offset, + tan(GZ_DTOR(30))*frustum.Far() - offset, frustum.Pose().Pos().Y() + frustum.Far() - offset, - (tan(IGN_DTOR(30)) * frustum.Far()) / frustum.AspectRatio() - offset); + (tan(GZ_DTOR(30)) * frustum.Far()) / frustum.AspectRatio() - offset); Vector3d farTopRightBad( - tan(IGN_DTOR(30))*frustum.Far() + offset, + tan(GZ_DTOR(30))*frustum.Far() + offset, frustum.Pose().Pos().Y() + frustum.Far() + offset, - (tan(IGN_DTOR(30)) * frustum.Far()) / frustum.AspectRatio() + offset); + (tan(GZ_DTOR(30)) * frustum.Far()) / frustum.AspectRatio() + offset); Vector3d farBottomLeft( - -tan(IGN_DTOR(30))*frustum.Far() + offset, + -tan(GZ_DTOR(30))*frustum.Far() + offset, frustum.Pose().Pos().Y() + frustum.Far() - offset, - (-tan(IGN_DTOR(30)) * frustum.Far()) / frustum.AspectRatio() + offset); + (-tan(GZ_DTOR(30)) * frustum.Far()) / frustum.AspectRatio() + offset); Vector3d farBottomLeftBad( - -tan(IGN_DTOR(30))*frustum.Far() - offset, + -tan(GZ_DTOR(30))*frustum.Far() - offset, frustum.Pose().Pos().Y() + frustum.Far() + offset, - (-tan(IGN_DTOR(30)) * frustum.Far()) / frustum.AspectRatio() - offset); + (-tan(GZ_DTOR(30)) * frustum.Far()) / frustum.AspectRatio() - offset); Vector3d farBottomRight( - tan(IGN_DTOR(30))*frustum.Far() - offset, + tan(GZ_DTOR(30))*frustum.Far() - offset, frustum.Pose().Pos().Y() + frustum.Far() - offset, - (-tan(IGN_DTOR(30)) * frustum.Far()) / frustum.AspectRatio() + offset); + (-tan(GZ_DTOR(30)) * frustum.Far()) / frustum.AspectRatio() + offset); Vector3d farBottomRightBad( - tan(IGN_DTOR(30))*frustum.Far() + offset, + tan(GZ_DTOR(30))*frustum.Far() + offset, frustum.Pose().Pos().Y() + frustum.Far() + offset, - (-tan(IGN_DTOR(30)) * frustum.Far()) / frustum.AspectRatio() - offset); + (-tan(GZ_DTOR(30)) * frustum.Far()) / frustum.AspectRatio() - offset); // Test far clip corners EXPECT_TRUE(frustum.Contains(farTopLeft)); @@ -473,7 +473,7 @@ TEST(FrustumTest, PoseContains) EXPECT_FALSE(frustum.Contains(farBottomRightBad)); // Adjust to 45 degrees rotation - frustum.SetPose(Pose3d(1, 1, 0, 0, 0, -IGN_PI*0.25)); + frustum.SetPose(Pose3d(1, 1, 0, 0, 0, -GZ_PI*0.25)); EXPECT_TRUE(frustum.Contains(Vector3d(2, -1, 0))); EXPECT_FALSE(frustum.Contains(Vector3d(0, 0, 0))); EXPECT_FALSE(frustum.Contains(Vector3d(1, 1, 0))); diff --git a/src/Helpers.i b/src/Helpers.i index dc46cc394..aba436ae7 100644 --- a/src/Helpers.i +++ b/src/Helpers.i @@ -28,15 +28,27 @@ template constexpr T IGN_MASSMATRIX3_DEFAULT_TOLERANCE = T(10); -#define IGN_PI 3.14159265358979323846 -#define IGN_PI_2 1.57079632679489661923 -#define IGN_PI_4 0.78539816339744830962 -#define IGN_SQRT2 1.41421356237309504880 - -#define IGN_SPHERE_VOLUME(_radius) (4.0*IGN_PI*std::pow(_radius, 3)/3.0) -#define IGN_CYLINDER_VOLUME(_r, _l) (_l * IGN_PI * std::pow(_r, 2)) -#define IGN_BOX_VOLUME(_x, _y, _z) (_x *_y * _z) -#define IGN_BOX_VOLUME_V(_v) (_v.X() *_v.Y() * _v.Z()) +#define GZ_PI 3.14159265358979323846 +#define GZ_PI_2 1.57079632679489661923 +#define GZ_PI_4 0.78539816339744830962 +#define GZ_SQRT2 1.41421356237309504880 + +#define GZ_SPHERE_VOLUME(_radius) (4.0 * GZ_PI * std::pow(_radius, 3)/3.0) +#define GZ_CYLINDER_VOLUME(_r, _l) (_l * GZ_PI * std::pow(_r, 2)) +#define GZ_BOX_VOLUME(_x, _y, _z) (_x *_y * _z) +#define GZ_BOX_VOLUME_V(_v) (_v.X() *_v.Y() * _v.Z()) + +// TODO(CH3): Deprecated. Remove on tock. +#define IGN_PI GZ_PI +#define IGN_PI_2 GZ_PI_2 +#define IGN_PI_4 GZ_PI_4 +#define IGN_SQRT2 GZ_SQRT2 + +// TODO(CH3): Deprecated. Remove on tock. +#define IGN_SPHERE_VOLUME(_radius) GZ_SPHERE_VOLUME(_radius) +#define IGN_CYLINDER_VOLUME(_r, _l) GZ_CYLINDER_VOLUME(_r, _l) +#define IGN_BOX_VOLUME(_x, _y, _z) GZ_BOX_VOLUME(_x, _y, _z) +#define IGN_BOX_VOLUME_V(_v) GZ_BOX_VOLUME_V(_v) namespace gz { diff --git a/src/Helpers_TEST.cc b/src/Helpers_TEST.cc index 5b46fb61d..942abb08b 100644 --- a/src/Helpers_TEST.cc +++ b/src/Helpers_TEST.cc @@ -425,16 +425,16 @@ TEST(HelpersTest, Sort) ///////////////////////////////////////////////// TEST(HelpersTest, Volume) { - EXPECT_DOUBLE_EQ(IGN_SPHERE_VOLUME(1.0), 4.0*IGN_PI*std::pow(1, 3)/3.0); - EXPECT_DOUBLE_EQ(IGN_SPHERE_VOLUME(0.1), 4.0*IGN_PI*std::pow(.1, 3)/3.0); - EXPECT_DOUBLE_EQ(IGN_SPHERE_VOLUME(-1.1), 4.0*IGN_PI*std::pow(-1.1, 3)/3.0); + EXPECT_DOUBLE_EQ(GZ_SPHERE_VOLUME(1.0), 4.0*GZ_PI*std::pow(1, 3)/3.0); + EXPECT_DOUBLE_EQ(GZ_SPHERE_VOLUME(0.1), 4.0*GZ_PI*std::pow(.1, 3)/3.0); + EXPECT_DOUBLE_EQ(GZ_SPHERE_VOLUME(-1.1), 4.0*GZ_PI*std::pow(-1.1, 3)/3.0); - EXPECT_DOUBLE_EQ(IGN_CYLINDER_VOLUME(0.5, 2.0), 2 * IGN_PI * std::pow(.5, 2)); - EXPECT_DOUBLE_EQ(IGN_CYLINDER_VOLUME(1, -1), -1 * IGN_PI * std::pow(1, 2)); + EXPECT_DOUBLE_EQ(GZ_CYLINDER_VOLUME(0.5, 2.0), 2 * GZ_PI * std::pow(.5, 2)); + EXPECT_DOUBLE_EQ(GZ_CYLINDER_VOLUME(1, -1), -1 * GZ_PI * std::pow(1, 2)); - EXPECT_DOUBLE_EQ(IGN_BOX_VOLUME(1, 2, 3), 1 * 2 * 3); - EXPECT_DOUBLE_EQ(IGN_BOX_VOLUME(.1, .2, .3), - IGN_BOX_VOLUME_V(math::Vector3d(0.1, 0.2, 0.3))); + EXPECT_DOUBLE_EQ(GZ_BOX_VOLUME(1, 2, 3), 1 * 2 * 3); + EXPECT_DOUBLE_EQ(GZ_BOX_VOLUME(.1, .2, .3), + GZ_BOX_VOLUME_V(math::Vector3d(0.1, 0.2, 0.3))); } ///////////////////////////////////////////////// @@ -985,7 +985,7 @@ TEST(HelpersTest, AppendToStream) { std::ostringstream out; - IGN_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION + GZ_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION // Deprecated in ign-math7 math::appendToStream(out, 0.12345678, 3); EXPECT_EQ(out.str(), "0.123"); @@ -1006,7 +1006,7 @@ TEST(HelpersTest, AppendToStream) EXPECT_EQ(out.str(), "0.123 0 456 0"); out.str(""); - IGN_UTILS_WARN_RESUME__DEPRECATED_DECLARATION + GZ_UTILS_WARN_RESUME__DEPRECATED_DECLARATION math::appendToStream(out, 0.0f); EXPECT_EQ(out.str(), "0"); diff --git a/src/Inertial_TEST.cc b/src/Inertial_TEST.cc index 24bbea8c8..f47d29c88 100644 --- a/src/Inertial_TEST.cc +++ b/src/Inertial_TEST.cc @@ -64,7 +64,7 @@ TEST(Inertiald_Test, ConstructorNonDefaultValues) math::MassMatrix3d m(mass, Ixxyyzz, Ixyxzyz); EXPECT_TRUE(m.IsPositive()); EXPECT_TRUE(m.IsValid()); - const math::Pose3d pose(1, 2, 3, IGN_PI/6, 0, 0); + const math::Pose3d pose(1, 2, 3, GZ_PI/6, 0, 0); math::Inertiald inertial(m, pose); // Should not match simple constructor @@ -117,7 +117,7 @@ TEST(Inertiald_Test, Setters) math::MassMatrix3d m(mass, Ixxyyzz, Ixyxzyz); EXPECT_TRUE(m.IsPositive()); EXPECT_TRUE(m.IsValid()); - const math::Pose3d pose(1, 2, 3, IGN_PI/6, 0, 0); + const math::Pose3d pose(1, 2, 3, GZ_PI/6, 0, 0); math::Inertiald inertial; // Initially valid @@ -154,7 +154,7 @@ TEST(Inertiald_Test, MOI_Diagonal) // 90 deg rotation about X axis, expect different MOI { - const math::Pose3d pose(0, 0, 0, IGN_PI_2, 0, 0); + const math::Pose3d pose(0, 0, 0, GZ_PI_2, 0, 0); const math::Matrix3d expectedMOI(2, 0, 0, 0, 4, 0, 0, 0, 3); math::Inertiald inertial(m, pose); EXPECT_NE(inertial.Moi(), m.Moi()); @@ -163,7 +163,7 @@ TEST(Inertiald_Test, MOI_Diagonal) // 90 deg rotation about Y axis, expect different MOI { - const math::Pose3d pose(0, 0, 0, 0, IGN_PI_2, 0); + const math::Pose3d pose(0, 0, 0, 0, GZ_PI_2, 0); const math::Matrix3d expectedMOI(4, 0, 0, 0, 3, 0, 0, 0, 2); math::Inertiald inertial(m, pose); EXPECT_NE(inertial.Moi(), m.Moi()); @@ -172,7 +172,7 @@ TEST(Inertiald_Test, MOI_Diagonal) // 90 deg rotation about Z axis, expect different MOI { - const math::Pose3d pose(0, 0, 0, 0, 0, IGN_PI_2); + const math::Pose3d pose(0, 0, 0, 0, 0, GZ_PI_2); const math::Matrix3d expectedMOI(3, 0, 0, 0, 2, 0, 0, 0, 4); math::Inertiald inertial(m, pose); EXPECT_NE(inertial.Moi(), m.Moi()); @@ -181,7 +181,7 @@ TEST(Inertiald_Test, MOI_Diagonal) // 45 deg rotation about Z axis, expect different MOI { - const math::Pose3d pose(0, 0, 0, 0, 0, IGN_PI_4); + const math::Pose3d pose(0, 0, 0, 0, 0, GZ_PI_4); const math::Matrix3d expectedMOI(2.5, -0.5, 0, -0.5, 2.5, 0, 0, 0, 4); math::Inertiald inertial(m, pose); EXPECT_NE(inertial.Moi(), m.Moi()); @@ -215,18 +215,18 @@ void SetRotation(const double _mass, const std::vector rotations = { math::Quaterniond::Identity, - math::Quaterniond(IGN_PI, 0, 0), - math::Quaterniond(0, IGN_PI, 0), - math::Quaterniond(0, 0, IGN_PI), - math::Quaterniond(IGN_PI_2, 0, 0), - math::Quaterniond(0, IGN_PI_2, 0), - math::Quaterniond(0, 0, IGN_PI_2), - math::Quaterniond(IGN_PI_4, 0, 0), - math::Quaterniond(0, IGN_PI_4, 0), - math::Quaterniond(0, 0, IGN_PI_4), - math::Quaterniond(IGN_PI/6, 0, 0), - math::Quaterniond(0, IGN_PI/6, 0), - math::Quaterniond(0, 0, IGN_PI/6), + math::Quaterniond(GZ_PI, 0, 0), + math::Quaterniond(0, GZ_PI, 0), + math::Quaterniond(0, 0, GZ_PI), + math::Quaterniond(GZ_PI_2, 0, 0), + math::Quaterniond(0, GZ_PI_2, 0), + math::Quaterniond(0, 0, GZ_PI_2), + math::Quaterniond(GZ_PI_4, 0, 0), + math::Quaterniond(0, GZ_PI_4, 0), + math::Quaterniond(0, 0, GZ_PI_4), + math::Quaterniond(GZ_PI/6, 0, 0), + math::Quaterniond(0, GZ_PI/6, 0), + math::Quaterniond(0, 0, GZ_PI/6), math::Quaterniond(0.1, 0.2, 0.3), math::Quaterniond(-0.1, 0.2, -0.3), math::Quaterniond(0.4, 0.2, 0.5), @@ -447,12 +447,12 @@ TEST(Inertiald_Test, AdditionSubtraction) const math::Vector3d size(1, 1, 1); math::MassMatrix3d cubeMM3; EXPECT_TRUE(cubeMM3.SetFromBox(mass, size)); - const math::Inertiald cube(cubeMM3, math::Pose3d(0, 0, 0, IGN_PI_4, 0, 0)); + const math::Inertiald cube(cubeMM3, math::Pose3d(0, 0, 0, GZ_PI_4, 0, 0)); math::MassMatrix3d half; EXPECT_TRUE(half.SetFromBox(0.5*mass, math::Vector3d(0.5, 1, 1))); - math::Inertiald left(half, math::Pose3d(-0.25, 0, 0, IGN_PI_4, 0, 0)); - math::Inertiald right(half, math::Pose3d(0.25, 0, 0, IGN_PI_4, 0, 0)); + math::Inertiald left(half, math::Pose3d(-0.25, 0, 0, GZ_PI_4, 0, 0)); + math::Inertiald right(half, math::Pose3d(0.25, 0, 0, GZ_PI_4, 0, 0)); // objects won't match exactly // since inertia matrices will all be in base frame @@ -514,12 +514,12 @@ TEST(Inertiald_Test, AdditionSubtraction) EXPECT_TRUE(cubeMM3.SetFromBox(mass, size)); const math::Inertiald sevenCubes = math::Inertiald(cubeMM3, math::Pose3d(-0.5, -0.5, -0.5, 0, 0, 0)) + - math::Inertiald(cubeMM3, math::Pose3d(-0.5, 0.5, -0.5, IGN_PI_2, 0, 0)) + - math::Inertiald(cubeMM3, math::Pose3d(0.5, -0.5, -0.5, 0, IGN_PI_2, 0)) + - math::Inertiald(cubeMM3, math::Pose3d(0.5, 0.5, -0.5, 0, 0, IGN_PI_2)) + - math::Inertiald(cubeMM3, math::Pose3d(-0.5, -0.5, 0.5, IGN_PI, 0, 0)) + - math::Inertiald(cubeMM3, math::Pose3d(-0.5, 0.5, 0.5, 0, IGN_PI, 0)) + - math::Inertiald(cubeMM3, math::Pose3d(0.5, -0.5, 0.5, 0, 0, IGN_PI)); + math::Inertiald(cubeMM3, math::Pose3d(-0.5, 0.5, -0.5, GZ_PI_2, 0, 0)) + + math::Inertiald(cubeMM3, math::Pose3d(0.5, -0.5, -0.5, 0, GZ_PI_2, 0)) + + math::Inertiald(cubeMM3, math::Pose3d(0.5, 0.5, -0.5, 0, 0, GZ_PI_2)) + + math::Inertiald(cubeMM3, math::Pose3d(-0.5, -0.5, 0.5, GZ_PI, 0, 0)) + + math::Inertiald(cubeMM3, math::Pose3d(-0.5, 0.5, 0.5, 0, GZ_PI, 0)) + + math::Inertiald(cubeMM3, math::Pose3d(0.5, -0.5, 0.5, 0, 0, GZ_PI)); const math::Inertiald lastCube = math::Inertiald(cubeMM3, math::Pose3d(0.5, 0.5, 0.5, 0, 0, 0)); const math::Inertiald addedCube = sevenCubes + lastCube; diff --git a/src/Line3_TEST.cc b/src/Line3_TEST.cc index 92c58a15f..98fe4e953 100644 --- a/src/Line3_TEST.cc +++ b/src/Line3_TEST.cc @@ -202,7 +202,7 @@ TEST(Line3Test, Distance) EXPECT_EQ(result, math::Line3d(0, 0.5, 0, 0, 0.5, 0.4)); EXPECT_TRUE(line.Distance(math::Line3d(0, 0.5, 1, 1, 0.5, 0), result)); - EXPECT_NEAR(result.Length(), sin(IGN_PI / 4), 1e-4); + EXPECT_NEAR(result.Length(), sin(GZ_PI / 4), 1e-4); EXPECT_EQ(result, math::Line3d(0, 0.5, 0, 0.5, 0.5, 0.5)); // Expect true when lines are parallel diff --git a/src/MassMatrix3_TEST.cc b/src/MassMatrix3_TEST.cc index 9e9dd144c..c1daef36e 100644 --- a/src/MassMatrix3_TEST.cc +++ b/src/MassMatrix3_TEST.cc @@ -289,7 +289,7 @@ TEST(MassMatrix3dTest, PrincipalMoments) const math::Vector3d Ixxyyzz(2.0, 2.0, 2.0); const math::Vector3d Ixyxzyz(-1.0, 0, -1.0); math::MassMatrix3d m(1.0, Ixxyyzz, Ixyxzyz); - const math::Vector3d Ieigen(2-IGN_SQRT2, 2, 2+IGN_SQRT2); + const math::Vector3d Ieigen(2-GZ_SQRT2, 2, 2+GZ_SQRT2); EXPECT_EQ(m.PrincipalMoments(), Ieigen); EXPECT_TRUE(m.IsPositive()); EXPECT_FALSE(m.IsValid()); @@ -301,7 +301,7 @@ TEST(MassMatrix3dTest, PrincipalMoments) const math::Vector3d Ixxyyzz(4.0, 4.0, 4.0); const math::Vector3d Ixyxzyz(-1.0, 0, -1.0); math::MassMatrix3d m(1.0, Ixxyyzz, Ixyxzyz); - const math::Vector3d Ieigen(4-IGN_SQRT2, 4, 4+IGN_SQRT2); + const math::Vector3d Ieigen(4-GZ_SQRT2, 4, 4+GZ_SQRT2); EXPECT_EQ(m.PrincipalMoments(), Ieigen); EXPECT_TRUE(m.IsPositive()); EXPECT_TRUE(m.IsValid()); @@ -504,56 +504,56 @@ TEST(MassMatrix3dTest, PrincipalAxesOffsetRepeat) // Rotated by [45, 45, 0] degrees VerifyNondiagonalMomentsAndAxes(math::Vector3d(4, 5, 5), math::Vector3d(4.5, 4.75, 4.75), - 0.25*math::Vector3d(-IGN_SQRT2, IGN_SQRT2, 1)); + 0.25*math::Vector3d(-GZ_SQRT2, GZ_SQRT2, 1)); // Rotated by [-45, 45, 0] degrees VerifyNondiagonalMomentsAndAxes(math::Vector3d(4, 5, 5), math::Vector3d(4.5, 4.75, 4.75), - 0.25*math::Vector3d(IGN_SQRT2, IGN_SQRT2, -1)); + 0.25*math::Vector3d(GZ_SQRT2, GZ_SQRT2, -1)); // Rotated by [45, -45, 0] degrees VerifyNondiagonalMomentsAndAxes(math::Vector3d(4, 5, 5), math::Vector3d(4.5, 4.75, 4.75), - 0.25*math::Vector3d(IGN_SQRT2, -IGN_SQRT2, 1)); + 0.25*math::Vector3d(GZ_SQRT2, -GZ_SQRT2, 1)); // Rotated by [-45, -45, 0] degrees VerifyNondiagonalMomentsAndAxes(math::Vector3d(4, 5, 5), math::Vector3d(4.5, 4.75, 4.75), - 0.25*math::Vector3d(-IGN_SQRT2, -IGN_SQRT2, -1)); + 0.25*math::Vector3d(-GZ_SQRT2, -GZ_SQRT2, -1)); // Principal moments: [4, 4, 5] // Rotated by [45, 45, 45] degrees VerifyNondiagonalMomentsAndAxes(math::Vector3d(4, 4, 5), math::Vector3d(4.5, 4.25, 4.25), - 0.25*math::Vector3d(-IGN_SQRT2, IGN_SQRT2, -1)); + 0.25*math::Vector3d(-GZ_SQRT2, GZ_SQRT2, -1)); // different rotation VerifyNondiagonalMomentsAndAxes(math::Vector3d(4, 4, 5), math::Vector3d(4.5, 4.25, 4.25), - 0.25*math::Vector3d(IGN_SQRT2, IGN_SQRT2, 1)); + 0.25*math::Vector3d(GZ_SQRT2, GZ_SQRT2, 1)); // different rotation VerifyNondiagonalMomentsAndAxes(math::Vector3d(4, 4, 5), math::Vector3d(4.5, 4.25, 4.25), - 0.25*math::Vector3d(-IGN_SQRT2, -IGN_SQRT2, 1)); + 0.25*math::Vector3d(-GZ_SQRT2, -GZ_SQRT2, 1)); // different rotation VerifyNondiagonalMomentsAndAxes(math::Vector3d(4, 4, 5), math::Vector3d(4.5, 4.25, 4.25), - 0.25*math::Vector3d(IGN_SQRT2, -IGN_SQRT2, -1)); + 0.25*math::Vector3d(GZ_SQRT2, -GZ_SQRT2, -1)); // Principal moments [4e-9, 4e-9, 5e-9] // Rotated by [45, 45, 45] degrees // use tolerance of 1e-15 VerifyNondiagonalMomentsAndAxes(1e-9 * math::Vector3d(4, 4, 5), 1e-9 * math::Vector3d(4.5, 4.25, 4.25), - 0.25e-9*math::Vector3d(-IGN_SQRT2, IGN_SQRT2, -1), 1e-15); + 0.25e-9*math::Vector3d(-GZ_SQRT2, GZ_SQRT2, -1), 1e-15); // different rotation VerifyNondiagonalMomentsAndAxes(1e-9 * math::Vector3d(4, 4, 5), 1e-9 * math::Vector3d(4.5, 4.25, 4.25), - 0.25e-9*math::Vector3d(IGN_SQRT2, IGN_SQRT2, 1)); + 0.25e-9*math::Vector3d(GZ_SQRT2, GZ_SQRT2, 1)); // different rotation VerifyNondiagonalMomentsAndAxes(1e-9 * math::Vector3d(4, 4, 5), 1e-9 * math::Vector3d(4.5, 4.25, 4.25), - 0.25e-9*math::Vector3d(-IGN_SQRT2, -IGN_SQRT2, 1)); + 0.25e-9*math::Vector3d(-GZ_SQRT2, -GZ_SQRT2, 1)); // different rotation VerifyNondiagonalMomentsAndAxes(1e-9 * math::Vector3d(4, 4, 5), 1e-9 * math::Vector3d(4.5, 4.25, 4.25), - 0.25e-9*math::Vector3d(IGN_SQRT2, -IGN_SQRT2, -1), 1e-15); + 0.25e-9*math::Vector3d(GZ_SQRT2, -GZ_SQRT2, -1), 1e-15); // Principal moments [4, 4, 6] // rotate by 30, 60, 0 degrees @@ -616,12 +616,12 @@ TEST(MassMatrix3dTest, PrincipalAxesOffsetNoRepeat) math::Vector3d(0.0, 0, -0.5)); // Tri-diagonal matrix with identical diagonal terms - VerifyNondiagonalMomentsAndAxes(math::Vector3d(4-IGN_SQRT2, 4, 4+IGN_SQRT2), + VerifyNondiagonalMomentsAndAxes(math::Vector3d(4-GZ_SQRT2, 4, 4+GZ_SQRT2), math::Vector3d(4.0, 4.0, 4.0), math::Vector3d(-1.0, 0, -1.0)); // small magnitude, use tolerance of 1e-15 VerifyNondiagonalMomentsAndAxes( - 1e-9 * math::Vector3d(4-IGN_SQRT2, 4, 4+IGN_SQRT2), + 1e-9 * math::Vector3d(4-GZ_SQRT2, 4, 4+GZ_SQRT2), 1e-9 * math::Vector3d(4.0, 4.0, 4.0), 1e-9 * math::Vector3d(-1.0, 0, -1.0), 1e-15); @@ -750,7 +750,7 @@ TEST(MassMatrix3dTest, EquivalentBox) math::Quaterniond rot; EXPECT_TRUE(m.EquivalentBox(size, rot, -1e-6)); EXPECT_EQ(size, math::Vector3d(9, 4, 1)); - EXPECT_EQ(rot, math::Quaterniond(0, 0, IGN_PI/2)); + EXPECT_EQ(rot, math::Quaterniond(0, 0, GZ_PI/2)); math::MassMatrix3d m2; EXPECT_TRUE(m2.SetFromBox(mass, size, rot)); @@ -768,8 +768,8 @@ TEST(MassMatrix3dTest, EquivalentBox) EXPECT_TRUE(m.EquivalentBox(size, rot)); EXPECT_EQ(size, math::Vector3d(9, 4, 1)); // There are multiple correct rotations due to box symmetry - EXPECT_TRUE(rot == math::Quaterniond(0, 0, IGN_PI/4) || - rot == math::Quaterniond(IGN_PI, 0, IGN_PI/4)); + EXPECT_TRUE(rot == math::Quaterniond(0, 0, GZ_PI/4) || + rot == math::Quaterniond(GZ_PI, 0, GZ_PI/4)); math::MassMatrix3d m2; EXPECT_TRUE(m2.SetFromBox(mass, size, rot)); @@ -829,7 +829,7 @@ TEST(MassMatrix3dTest, SetFromCylinderZ) EXPECT_EQ(m.DiagonalMoments(), ixxyyzz); EXPECT_EQ(m.OffDiagonalMoments(), math::Vector3d::Zero); - double density = mass / (IGN_PI * radius * radius * length); + double density = mass / (GZ_PI * radius * radius * length); math::Material mat(density); EXPECT_DOUBLE_EQ(density, mat.Density()); math::MassMatrix3d m1; @@ -873,7 +873,7 @@ TEST(MassMatrix3dTest, SetFromSphere) EXPECT_EQ(m.DiagonalMoments(), ixxyyzz); EXPECT_EQ(m.OffDiagonalMoments(), math::Vector3d::Zero); - double density = mass / ((4.0/3.0) * IGN_PI * std::pow(radius, 3)); + double density = mass / ((4.0/3.0) * GZ_PI * std::pow(radius, 3)); math::Material mat(density); EXPECT_DOUBLE_EQ(density, mat.Density()); math::MassMatrix3d m1; diff --git a/src/Matrix3_TEST.cc b/src/Matrix3_TEST.cc index f04824b44..22d2b0fa4 100644 --- a/src/Matrix3_TEST.cc +++ b/src/Matrix3_TEST.cc @@ -49,7 +49,7 @@ TEST(Matrix3dTest, Matrix3d) math::Vector3d(3, 3, 3)); EXPECT_TRUE(matrix == math::Matrix3d(1, 2, 3, 1, 2, 3, 1, 2, 3)); - matrix.SetFromAxisAngle(math::Vector3d(1, 1, 1), IGN_PI); + matrix.SetFromAxisAngle(math::Vector3d(1, 1, 1), GZ_PI); EXPECT_TRUE(matrix == math::Matrix3d(1, 2, 2, 2, 1, 2, 2, 2, 1)); matrix.SetCol(0, math::Vector3d(3, 4, 5)); diff --git a/src/Matrix4_TEST.cc b/src/Matrix4_TEST.cc index a15c35afd..d5fdef8ee 100644 --- a/src/Matrix4_TEST.cc +++ b/src/Matrix4_TEST.cc @@ -125,7 +125,7 @@ TEST(Matrix4dTest, ConstructFromPose3d) // Rotate pitch by pi/2 so yaw coincides with roll causing a gimbal lock { math::Vector3d trans(3, 2, 1); - math::Quaterniond qt(0, IGN_PI / 2, 0); + math::Quaterniond qt(0, GZ_PI / 2, 0); math::Pose3d pose(trans, qt); math::Matrix4d mat(pose); @@ -137,9 +137,9 @@ TEST(Matrix4dTest, ConstructFromPose3d) { // setup a ZXZ rotation to ensure non-commutative rotations - math::Pose3d pose1(1, -2, 3, 0, 0, IGN_PI / 4); - math::Pose3d pose2(0, 1, -1, -IGN_PI / 4, 0, 0); - math::Pose3d pose3(-1, 0, 0, 0, 0, -IGN_PI / 4); + math::Pose3d pose1(1, -2, 3, 0, 0, GZ_PI / 4); + math::Pose3d pose2(0, 1, -1, -GZ_PI / 4, 0, 0); + math::Pose3d pose3(-1, 0, 0, 0, 0, -GZ_PI / 4); math::Matrix4d m1(pose1); math::Matrix4d m2(pose2); @@ -675,17 +675,17 @@ TEST(Matrix4dTest, LookAt) EXPECT_EQ(math::Matrix4d::LookAt(math::Vector3d(3, 2, 0), math::Vector3d(0, 2, 0)) .Pose(), - math::Pose3d(3, 2, 0, 0, 0, IGN_PI)); + math::Pose3d(3, 2, 0, 0, 0, GZ_PI)); EXPECT_EQ(math::Matrix4d::LookAt(math::Vector3d(1, 6, 1), math::Vector3d::One) .Pose(), - math::Pose3d(1, 6, 1, 0, 0, -IGN_PI_2)); + math::Pose3d(1, 6, 1, 0, 0, -GZ_PI_2)); EXPECT_EQ(math::Matrix4d::LookAt(math::Vector3d(-1, -1, 0), math::Vector3d(1, 1, 0)) .Pose(), - math::Pose3d(-1, -1, 0, 0, 0, IGN_PI_4)); + math::Pose3d(-1, -1, 0, 0, 0, GZ_PI_4)); // Default up is Z EXPECT_EQ(math::Matrix4d::LookAt(math::Vector3d(0.1, -5, 222), @@ -733,11 +733,11 @@ TEST(Matrix4dTest, LookAt) math::Vector3d(0, 1, 1), math::Vector3d::UnitY) .Pose(), - math::Pose3d(1, 1, 1, IGN_PI_2, 0, IGN_PI)); + math::Pose3d(1, 1, 1, GZ_PI_2, 0, GZ_PI)); EXPECT_EQ(math::Matrix4d::LookAt(math::Vector3d::One, math::Vector3d(0, 1, 1), math::Vector3d(0, 1, 1)) .Pose(), - math::Pose3d(1, 1, 1, IGN_PI_4, 0, IGN_PI)); + math::Pose3d(1, 1, 1, GZ_PI_4, 0, GZ_PI)); } diff --git a/src/OrientedBox_TEST.cc b/src/OrientedBox_TEST.cc index 19d681d56..70688bd48 100644 --- a/src/OrientedBox_TEST.cc +++ b/src/OrientedBox_TEST.cc @@ -256,7 +256,7 @@ TEST(OrientedBoxTest, ContainsOrientedPosition) TEST(OrientedBoxTest, ContainsOrientedRotation) { // Rotate PI/2 about +x: swap Z and Y - OrientedBoxd box(Vector3d(1, 2, 3), Pose3d(0, 0, 0, IGN_PI*0.5, 0, 0)); + OrientedBoxd box(Vector3d(1, 2, 3), Pose3d(0, 0, 0, GZ_PI*0.5, 0, 0)); // Doesn't contain non-rotated vertices EXPECT_FALSE(box.Contains(Vector3d(-0.5, -1.0, -1.5))); diff --git a/src/Pose_TEST.cc b/src/Pose_TEST.cc index 1f20dc8cf..25bced1ac 100644 --- a/src/Pose_TEST.cc +++ b/src/Pose_TEST.cc @@ -64,17 +64,17 @@ TEST(PoseTest, Pose) // B is the transform from P to Q specified in frame P // then, A * B is the transform from O to Q specified in frame O math::Pose3d A(math::Vector3d(1, 0, 0), - math::Quaterniond(0, 0, IGN_PI/4.0)); + math::Quaterniond(0, 0, GZ_PI/4.0)); math::Pose3d B(math::Vector3d(1, 0, 0), - math::Quaterniond(0, 0, IGN_PI/2.0)); + math::Quaterniond(0, 0, GZ_PI/2.0)); EXPECT_TRUE(math::equal((A * B).Pos().X(), 1.0 + 1.0/sqrt(2))); EXPECT_TRUE(math::equal((A * B).Pos().Y(), 1.0/sqrt(2))); EXPECT_TRUE(math::equal((A * B).Pos().Z(), 0.0)); EXPECT_TRUE(math::equal((A * B).Rot().Euler().X(), 0.0)); EXPECT_TRUE(math::equal((A * B).Rot().Euler().Y(), 0.0)); - EXPECT_TRUE(math::equal((A * B).Rot().Euler().Z(), 3.0*IGN_PI/4.0)); + EXPECT_TRUE(math::equal((A * B).Rot().Euler().Z(), 3.0*GZ_PI/4.0)); - IGN_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION + GZ_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION // Coverage for + operator EXPECT_EQ(A * B, B + A); EXPECT_NE(A * B, A + B); @@ -83,7 +83,7 @@ TEST(PoseTest, Pose) math::Pose3d C(B); C += A; EXPECT_EQ(C, A * B); - IGN_UTILS_WARN_RESUME__DEPRECATED_DECLARATION + GZ_UTILS_WARN_RESUME__DEPRECATED_DECLARATION } { // If: @@ -122,7 +122,7 @@ TEST(PoseTest, Pose) // B is the transform from O to Q in frame O // B - A is the transform from P to Q in frame P math::Pose3d A(math::Vector3d(1, 0, 0), - math::Quaterniond(0, 0, IGN_PI/4.0)); + math::Quaterniond(0, 0, GZ_PI/4.0)); math::Pose3d B(math::Vector3d(1, 1, 0), math::Quaterniond(0, 0, IGN_PI/2.0)); EXPECT_TRUE(math::equal((A.Inverse() * B).Pos().X(), 1.0/sqrt(2))); diff --git a/src/Quaternion_TEST.cc b/src/Quaternion_TEST.cc index fe72f8ee8..917b9e537 100644 --- a/src/Quaternion_TEST.cc +++ b/src/Quaternion_TEST.cc @@ -128,11 +128,11 @@ TEST(QuaternionTest, ConstructEuler) // There are an infinite number of equivalent Euler angle // representations when pitch = PI/2, so rather than comparing Euler // angles, we will compare quaternions. - for (double pitch : { -IGN_PI_2, IGN_PI_2 }) + for (double pitch : { -GZ_PI_2, GZ_PI_2 }) { - for (double roll = 0; roll < 2 * IGN_PI + 0.1; roll += IGN_PI_4) + for (double roll = 0; roll < 2 * GZ_PI + 0.1; roll += GZ_PI_4) { - for (double yaw = 0; yaw < 2 * IGN_PI + 0.1; yaw += IGN_PI_4) + for (double yaw = 0; yaw < 2 * GZ_PI + 0.1; yaw += GZ_PI_4) { math::Quaterniond q_orig(roll, pitch, yaw); math::Quaterniond q_derived(q_orig.Euler()); @@ -145,7 +145,7 @@ TEST(QuaternionTest, ConstructEuler) ///////////////////////////////////////////////// TEST(QuaternionTest, ConstructAxisAngle) { - math::Quaterniond q1(math::Vector3d(0, 0, 1), IGN_PI); + math::Quaterniond q1(math::Vector3d(0, 0, 1), GZ_PI); EXPECT_TRUE(math::equal(q1.X(), 0.0)); EXPECT_TRUE(math::equal(q1.Y(), 0.0)); EXPECT_TRUE(math::equal(q1.Z(), 1.0)); @@ -273,7 +273,7 @@ TEST(QuaternionTest, Integrate) // expect no change. { const math::Quaterniond q(0.5, 0.5, 0.5, 0.5); - const double fourPi = 4 * IGN_PI; + const double fourPi = 4 * GZ_PI; math::Quaterniond qX = q.Integrate(math::Vector3d::UnitX, fourPi); math::Quaterniond qY = q.Integrate(math::Vector3d::UnitY, fourPi); math::Quaterniond qZ = q.Integrate(math::Vector3d::UnitZ, fourPi); @@ -286,7 +286,7 @@ TEST(QuaternionTest, Integrate) ///////////////////////////////////////////////// TEST(QuaternionTest, MathLog) { - math::Quaterniond q(IGN_PI*0.1, IGN_PI*0.5, IGN_PI); + math::Quaterniond q(GZ_PI*0.1, GZ_PI*0.5, GZ_PI); EXPECT_EQ(q.Log(), math::Quaterniond(0, -1.02593, 0.162491, 1.02593)); @@ -298,7 +298,7 @@ TEST(QuaternionTest, MathLog) ///////////////////////////////////////////////// TEST(QuaternionTest, MathExp) { - math::Quaterniond q(IGN_PI*0.1, IGN_PI*0.5, IGN_PI); + math::Quaterniond q(GZ_PI*0.1, GZ_PI*0.5, GZ_PI); EXPECT_EQ(q.Exp(), math::Quaterniond(0.545456, -0.588972, 0.093284, 0.588972)); @@ -314,7 +314,7 @@ TEST(QuaternionTest, MathExp) ///////////////////////////////////////////////// TEST(QuaternionTest, MathInvert) { - math::Quaterniond q(IGN_PI*0.1, IGN_PI*0.5, IGN_PI); + math::Quaterniond q(GZ_PI*0.1, GZ_PI*0.5, GZ_PI); q.Invert(); EXPECT_EQ(q, math::Quaterniond(0.110616, 0.698401, -0.110616, -0.698401)); @@ -323,29 +323,29 @@ TEST(QuaternionTest, MathInvert) ///////////////////////////////////////////////// TEST(QuaternionTest, MathAxis) { - math::Quaterniond q(IGN_PI*0.1, IGN_PI*0.5, IGN_PI); + math::Quaterniond q(GZ_PI*0.1, GZ_PI*0.5, GZ_PI); -IGN_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION +GZ_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION // Deprecated in ign-math7 - q.Axis(0, 1, 0, IGN_PI); + q.Axis(0, 1, 0, GZ_PI); EXPECT_EQ(q, math::Quaterniond(6.12303e-17, 0, 1, 0)); // Deprecated in ign-math7 - q.Axis(1, 0, 0, IGN_PI); + q.Axis(1, 0, 0, GZ_PI); EXPECT_EQ(q, math::Quaterniond(0, 1, 0, 0)); -IGN_UTILS_WARN_RESUME__DEPRECATED_DECLARATION +GZ_UTILS_WARN_RESUME__DEPRECATED_DECLARATION - q.SetFromAxisAngle(0, 1, 0, IGN_PI); + q.SetFromAxisAngle(0, 1, 0, GZ_PI); EXPECT_EQ(q, math::Quaterniond(6.12303e-17, 0, 1, 0)); - q.SetFromAxisAngle(math::Vector3d(1, 0, 0), IGN_PI); + q.SetFromAxisAngle(math::Vector3d(1, 0, 0), GZ_PI); EXPECT_EQ(q, math::Quaterniond(0, 1, 0, 0)); } ///////////////////////////////////////////////// TEST(QuaternionTest, MathSet) { - math::Quaterniond q(IGN_PI*0.1, IGN_PI*0.5, IGN_PI); + math::Quaterniond q(GZ_PI*0.1, GZ_PI*0.5, GZ_PI); q.Set(1, 2, 3, 4); EXPECT_TRUE(math::equal(q.W(), 1.0)); @@ -375,7 +375,7 @@ TEST(QuaternionTest, MathNormalize) ///////////////////////////////////////////////// TEST(QuaternionTest, Math) { - math::Quaterniond q(IGN_PI*0.1, IGN_PI*0.5, IGN_PI); + math::Quaterniond q(GZ_PI*0.1, GZ_PI*0.5, GZ_PI); EXPECT_TRUE(q == math::Quaterniond(0.110616, -0.698401, 0.110616, 0.698401)); q.Set(1, 2, 3, 4); @@ -455,7 +455,7 @@ TEST(QuaternionTest, Math) EXPECT_TRUE(math::equal(angle, 0.0, 1e-3)); { // simple 180 rotation about yaw, should result in x and y flipping signs - q = math::Quaterniond(0, 0, IGN_PI); + q = math::Quaterniond(0, 0, GZ_PI); math::Vector3d v = math::Vector3d(1, 2, 3); math::Vector3d r1 = q.RotateVector(v); math::Vector3d r2 = q.RotateVectorReverse(v); @@ -470,7 +470,7 @@ TEST(QuaternionTest, Math) { // simple 90 rotation about yaw, should map x to y, y to -x // simple -90 rotation about yaw, should map x to -y, y to x - q = math::Quaterniond(0, 0, 0.5*IGN_PI); + q = math::Quaterniond(0, 0, 0.5*GZ_PI); math::Vector3d v = math::Vector3d(1, 2, 3); math::Vector3d r1 = q.RotateVector(v); math::Vector3d r2 = q.RotateVectorReverse(v); @@ -491,7 +491,7 @@ TEST(QuaternionTest, Math) // Test RPY fixed-body-frame convention: // Rotate each unit vector in roll and pitch { - q = math::Quaterniond(IGN_PI/2.0, IGN_PI/2.0, 0); + q = math::Quaterniond(GZ_PI/2.0, GZ_PI/2.0, 0); math::Vector3d v1(1, 0, 0); math::Vector3d r1 = q.RotateVector(v1); // 90 degrees about X does nothing, @@ -514,7 +514,7 @@ TEST(QuaternionTest, Math) { // now try a harder case (axis[1,2,3], rotation[0.3*pi]) // verified with octave - q.SetFromAxisAngle(math::Vector3d(1, 2, 3), 0.3*IGN_PI); + q.SetFromAxisAngle(math::Vector3d(1, 2, 3), 0.3*GZ_PI); std::cout << "[" << q.W() << ", " << q.X() << ", " << q.Y() << ", " << q.Z() << "]\n"; std::cout << " x [" << q.Inverse().XAxis() << "]\n"; diff --git a/src/Sphere_TEST.cc b/src/Sphere_TEST.cc index 2d4a2800c..6faacbfba 100644 --- a/src/Sphere_TEST.cc +++ b/src/Sphere_TEST.cc @@ -96,7 +96,7 @@ TEST(SphereTest, VolumeAndDensity) { double mass = 1.0; math::Sphered sphere(0.001); - double expectedVolume = (4.0/3.0) * IGN_PI * std::pow(0.001, 3); + double expectedVolume = (4.0/3.0) * GZ_PI * std::pow(0.001, 3); EXPECT_DOUBLE_EQ(expectedVolume, sphere.Volume()); double expectedDensity = mass / expectedVolume; diff --git a/src/SphericalCoordinates.cc b/src/SphericalCoordinates.cc index de95c0a2c..9c36a1d3c 100644 --- a/src/SphericalCoordinates.cc +++ b/src/SphericalCoordinates.cc @@ -255,8 +255,8 @@ gz::math::Vector3d SphericalCoordinates::SphericalFromLocalPosition( { gz::math::Vector3d result = this->PositionTransform(_xyz, LOCAL, SPHERICAL); - result.X(IGN_RTOD(result.X())); - result.Y(IGN_RTOD(result.Y())); + result.X(GZ_RTOD(result.X())); + result.Y(GZ_RTOD(result.Y())); return result; } @@ -265,8 +265,8 @@ gz::math::Vector3d SphericalCoordinates::LocalFromSphericalPosition( const gz::math::Vector3d &_xyz) const { gz::math::Vector3d result = _xyz; - result.X(IGN_DTOR(result.X())); - result.Y(IGN_DTOR(result.Y())); + result.X(GZ_DTOR(result.X())); + result.Y(GZ_DTOR(result.Y())); return this->PositionTransform(result, SPHERICAL, LOCAL); } diff --git a/src/SphericalCoordinates_TEST.cc b/src/SphericalCoordinates_TEST.cc index f0e4b0191..3468da276 100644 --- a/src/SphericalCoordinates_TEST.cc +++ b/src/SphericalCoordinates_TEST.cc @@ -436,8 +436,8 @@ TEST(SphericalCoordinatesTest, NoHeading) { // Default heading auto st = math::SphericalCoordinates::EARTH_WGS84; - math::Angle lat(IGN_DTOR(-22.9)); - math::Angle lon(IGN_DTOR(-43.2)); + math::Angle lat(GZ_DTOR(-22.9)); + math::Angle lon(GZ_DTOR(-43.2)); math::Angle heading(0.0); double elev = 0; math::SphericalCoordinates sc(st, lat, lon, elev, heading); @@ -544,9 +544,9 @@ TEST(SphericalCoordinatesTest, WithHeading) { // Heading 90 deg: X == North, Y == West , Z == Up auto st = math::SphericalCoordinates::EARTH_WGS84; - math::Angle lat(IGN_DTOR(-22.9)); - math::Angle lon(IGN_DTOR(-43.2)); - math::Angle heading(IGN_DTOR(90.0)); + math::Angle lat(GZ_DTOR(-22.9)); + math::Angle lon(GZ_DTOR(-43.2)); + math::Angle heading(GZ_DTOR(90.0)); double elev = 0; math::SphericalCoordinates sc(st, lat, lon, elev, heading); diff --git a/src/Vector2_TEST.cc b/src/Vector2_TEST.cc index d5eaa8c3d..2644f4b1c 100644 --- a/src/Vector2_TEST.cc +++ b/src/Vector2_TEST.cc @@ -441,7 +441,7 @@ TEST(Vector2Test, Length) EXPECT_DOUBLE_EQ(math::Vector2d::Zero.SquaredLength(), 0.0); // One vector - EXPECT_NEAR(math::Vector2d::One.Length(), IGN_SQRT2, 1e-10); + EXPECT_NEAR(math::Vector2d::One.Length(), GZ_SQRT2, 1e-10); EXPECT_DOUBLE_EQ(math::Vector2d::One.SquaredLength(), 2.0); // Arbitrary vector diff --git a/src/python_pybind11/src/Angle.cc b/src/python_pybind11/src/Angle.cc index b04760b35..4964af3e3 100644 --- a/src/python_pybind11/src/Angle.cc +++ b/src/python_pybind11/src/Angle.cc @@ -80,9 +80,9 @@ void defineMathAngle(py::module &m, const std::string &typestr) .def(py::self > py::self) .def(py::self >= py::self) .def_readonly_static("ZERO", &Class::Zero, "math::Angle(0)") - .def_readonly_static("PI", &Class::Pi, "math::Angle(IGN_PI)") - .def_readonly_static("HALF_PI", &Class::HalfPi, "math::Angle(IGN_PI * 0.5)") - .def_readonly_static("TWO_PI", &Class::TwoPi, "math::Angle(IGN_PI * 2)") + .def_readonly_static("PI", &Class::Pi, "math::Angle(GZ_PI)") + .def_readonly_static("HALF_PI", &Class::HalfPi, "math::Angle(GZ_PI * 0.5)") + .def_readonly_static("TWO_PI", &Class::TwoPi, "math::Angle(GZ_PI * 2)") .def("__copy__", [](const Class &self) { return Class(self); }) diff --git a/src/python_pybind11/src/Helpers.cc b/src/python_pybind11/src/Helpers.cc index 947bee33c..ca851aa65 100644 --- a/src/python_pybind11/src/Helpers.cc +++ b/src/python_pybind11/src/Helpers.cc @@ -37,7 +37,7 @@ class Helpers /// \return sphere volume float SphereVolume(const float _radius) { - return IGN_SPHERE_VOLUME(_radius); + return GZ_SPHERE_VOLUME(_radius); } /// \brief Compute cylinder volume @@ -46,7 +46,7 @@ float SphereVolume(const float _radius) /// \return cylinder volume float CylinderVolume(const float _r, const float _l) { - return IGN_CYLINDER_VOLUME(_r, _l); + return GZ_CYLINDER_VOLUME(_r, _l); } /// \brief Compute box volume @@ -56,7 +56,7 @@ float CylinderVolume(const float _r, const float _l) /// \return box volume float BoxVolume(const float _x, const float _y, const float _z) { - return IGN_BOX_VOLUME(_x, _y, _z); + return GZ_BOX_VOLUME(_x, _y, _z); } /// \brief Compute box volume from a vector @@ -64,7 +64,7 @@ float BoxVolume(const float _x, const float _y, const float _z) /// \return box volume from a vector float BoxVolumeV(const gz::math::Vector3d &_v) { - return IGN_BOX_VOLUME_V(_v); + return GZ_BOX_VOLUME_V(_v); } /// \brief Sort two numbers, such that _a <= _b @@ -164,23 +164,23 @@ void defineMathHelpers(py::module &m) .def("parse_float", &gz::math::parseFloat, "parse string into an float") - .def("ign_sphere_volume", + .def("gz_sphere_volume", &SphereVolume, "Compute sphere volume") - .def("ign_cylinder_volume", + .def("gz_cylinder_volume", &CylinderVolume, "Compute cylinder volume") - .def("ign_box_volume", + .def("gz_box_volume", &BoxVolume, "Compute box volume") - .def("ign_box_volume_v", + .def("gz_box_volume_v", &BoxVolumeV, "Compute box volume from vector"); py::class_(m, "Helpers", py::buffer_protocol(), py::dynamic_attr()) - .def_readonly_static("IGNZEROSIZET", &IGN_ZERO_SIZE_T, "IGN_PI") + .def_readonly_static("IGNZEROSIZET", &IGN_ZERO_SIZE_T, "GZ_PI") .def_readonly_static("IGN_ONE_SIZE_T", &IGN_ONE_SIZE_T) .def_readonly_static("IGN_TWO_SIZE_T", &IGN_TWO_SIZE_T) .def_readonly_static("IGN_THREE_SIZE_T", &IGN_THREE_SIZE_T) diff --git a/src/python_pybind11/test/Helpers_TEST.py b/src/python_pybind11/test/Helpers_TEST.py index 685e05881..2bbadef9e 100644 --- a/src/python_pybind11/test/Helpers_TEST.py +++ b/src/python_pybind11/test/Helpers_TEST.py @@ -15,8 +15,8 @@ import math import unittest -from ignition.math import (Helpers, ign_box_volume, ign_box_volume_v, ign_cylinder_volume, - ign_sphere_volume, Vector3d, equal, fixnan, +from ignition.math import (Helpers, gz_box_volume, gz_box_volume_v, gz_cylinder_volume, + gz_sphere_volume, Vector3d, equal, fixnan, greater_or_near_equal, is_even, is_odd, is_power_of_two, isnan, less_or_near_equal, max, mean, min, parse_float, parse_int, precision, round_up_multiple, @@ -243,31 +243,31 @@ def test_sort(self): def test_volume(self): self.assertAlmostEqual( - ign_sphere_volume(1.0), + gz_sphere_volume(1.0), 4.0*math.pi*math.pow(1, 3)/3.0, 6) self.assertAlmostEqual( - ign_sphere_volume(0.1), + gz_sphere_volume(0.1), 4.0*math.pi*math.pow(.1, 3)/3.0, 6) self.assertAlmostEqual( - ign_sphere_volume(-1.1), + gz_sphere_volume(-1.1), 4.0*math.pi*math.pow(-1.1, 3)/3.0, 6) self.assertAlmostEqual( - ign_cylinder_volume(0.5, 2.0), + gz_cylinder_volume(0.5, 2.0), 2 * math.pi * math.pow(.5, 2), 6) self.assertAlmostEqual( - ign_cylinder_volume(1, -1), + gz_cylinder_volume(1, -1), -1 * math.pi * math.pow(1, 2), 6) - self.assertEqual(ign_box_volume(1, 2, 3), 1 * 2 * 3) + self.assertEqual(gz_box_volume(1, 2, 3), 1 * 2 * 3) self.assertAlmostEqual( - ign_box_volume(.1, .2, .3), - ign_box_volume_v(Vector3d(0.1, 0.2, 0.3)), + gz_box_volume(.1, .2, .3), + gz_box_volume_v(Vector3d(0.1, 0.2, 0.3)), 6) def test_round_up_multiple(self): diff --git a/src/python_pybind11/test/MassMatrix3_TEST.py b/src/python_pybind11/test/MassMatrix3_TEST.py index 85f1af53d..9a8314648 100644 --- a/src/python_pybind11/test/MassMatrix3_TEST.py +++ b/src/python_pybind11/test/MassMatrix3_TEST.py @@ -23,10 +23,10 @@ from ignition.math import Matrix3d from ignition.math import Quaterniond -IGN_PI = 3.14159265358979323846 -IGN_PI_2 = 1.57079632679489661923 -IGN_PI_4 = 0.78539816339744830962 -IGN_SQRT2 = 1.41421356237309504880 +GZ_PI = 3.14159265358979323846 +GZ_PI_2 = 1.57079632679489661923 +GZ_PI_4 = 0.78539816339744830962 +GZ_SQRT2 = 1.41421356237309504880 def equal(a, b, error): @@ -254,7 +254,7 @@ def test_principal_moments(self): Ixxyyzz = Vector3d(2.0, 2.0, 2.0) Ixyxzyz = Vector3d(-1.0, 0, -1.0) m = MassMatrix3d(1.0, Ixxyyzz, Ixyxzyz) - Ieigen = Vector3d(2-IGN_SQRT2, 2, 2+IGN_SQRT2) + Ieigen = Vector3d(2-GZ_SQRT2, 2, 2+GZ_SQRT2) self.assertEqual(m.principal_moments(), Ieigen) self.assertTrue(m.is_positive()) self.assertFalse(m.is_valid()) @@ -264,7 +264,7 @@ def test_principal_moments(self): Ixxyyzz = Vector3d(4.0, 4.0, 4.0) Ixyxzyz = Vector3d(-1.0, 0, -1.0) m = MassMatrix3d(1.0, Ixxyyzz, Ixyxzyz) - Ieigen = Vector3d(4-IGN_SQRT2, 4, 4+IGN_SQRT2) + Ieigen = Vector3d(4-GZ_SQRT2, 4, 4+GZ_SQRT2) self.assertEqual(m.principal_moments(), Ieigen) self.assertTrue(m.is_positive()) self.assertTrue(m.is_valid()) @@ -453,44 +453,44 @@ def test_principal_axes_offset_repeat(self): self.verify_non_diagonal_moments_and_axes( Vector3d(4, 5, 5), Vector3d(4.5, 4.75, 4.75), - Vector3d(-IGN_SQRT2, IGN_SQRT2, 1) * 0.25) + Vector3d(-GZ_SQRT2, GZ_SQRT2, 1) * 0.25) # Rotated by [-45, 45, 0] degrees self.verify_non_diagonal_moments_and_axes( Vector3d(4, 5, 5), Vector3d(4.5, 4.75, 4.75), - Vector3d(IGN_SQRT2, IGN_SQRT2, -1) * 0.25) + Vector3d(GZ_SQRT2, GZ_SQRT2, -1) * 0.25) # Rotated by [45, -45, 0] degrees self.verify_non_diagonal_moments_and_axes( Vector3d(4, 5, 5), Vector3d(4.5, 4.75, 4.75), - Vector3d(IGN_SQRT2, -IGN_SQRT2, 1) * 0.25) + Vector3d(GZ_SQRT2, -GZ_SQRT2, 1) * 0.25) # Rotated by [-45, -45, 0] degrees self.verify_non_diagonal_moments_and_axes( Vector3d(4, 5, 5), Vector3d(4.5, 4.75, 4.75), - Vector3d(-IGN_SQRT2, -IGN_SQRT2, -1) * 0.25) + Vector3d(-GZ_SQRT2, -GZ_SQRT2, -1) * 0.25) # Principal moments: [4, 4, 5] # Rotated by [45, 45, 45] degrees self.verify_non_diagonal_moments_and_axes( Vector3d(4, 4, 5), Vector3d(4.5, 4.25, 4.25), - Vector3d(-IGN_SQRT2, IGN_SQRT2, -1) * 0.25) + Vector3d(-GZ_SQRT2, GZ_SQRT2, -1) * 0.25) # different rotation self.verify_non_diagonal_moments_and_axes( Vector3d(4, 4, 5), Vector3d(4.5, 4.25, 4.25), - Vector3d(IGN_SQRT2, IGN_SQRT2, 1) * 0.25) + Vector3d(GZ_SQRT2, GZ_SQRT2, 1) * 0.25) # different rotation self.verify_non_diagonal_moments_and_axes( Vector3d(4, 4, 5), Vector3d(4.5, 4.25, 4.25), - Vector3d(-IGN_SQRT2, -IGN_SQRT2, 1) * 0.25) + Vector3d(-GZ_SQRT2, -GZ_SQRT2, 1) * 0.25) # different rotation self.verify_non_diagonal_moments_and_axes( Vector3d(4, 4, 5), Vector3d(4.5, 4.25, 4.25), - Vector3d(IGN_SQRT2, -IGN_SQRT2, -1) * 0.25) + Vector3d(GZ_SQRT2, -GZ_SQRT2, -1) * 0.25) # Principal moments [4e-9, 4e-9, 5e-9] # Rotated by [45, 45, 45] degrees @@ -498,22 +498,22 @@ def test_principal_axes_offset_repeat(self): self.verify_non_diagonal_moments_and_axes( Vector3d(4, 4, 5) * 1e-9, Vector3d(4.5, 4.25, 4.25) * 1e-9, - Vector3d(-IGN_SQRT2, IGN_SQRT2, -1) * 0.25e-9, 1e-15) + Vector3d(-GZ_SQRT2, GZ_SQRT2, -1) * 0.25e-9, 1e-15) # different rotation self.verify_non_diagonal_moments_and_axes( Vector3d(4, 4, 5) * 1e-9, Vector3d(4.5, 4.25, 4.25) * 1e-9, - Vector3d(IGN_SQRT2, IGN_SQRT2, 1) * 0.25e-9) + Vector3d(GZ_SQRT2, GZ_SQRT2, 1) * 0.25e-9) # different rotation self.verify_non_diagonal_moments_and_axes( Vector3d(4, 4, 5) * 1e-9, Vector3d(4.5, 4.25, 4.25) * 1e-9, - Vector3d(-IGN_SQRT2, -IGN_SQRT2, 1) * 0.25e-9) + Vector3d(-GZ_SQRT2, -GZ_SQRT2, 1) * 0.25e-9) # different rotation self.verify_non_diagonal_moments_and_axes( Vector3d(4, 4, 5) * 1e-9, Vector3d(4.5, 4.25, 4.25) * 1e-9, - Vector3d(IGN_SQRT2, -IGN_SQRT2, -1) * 0.25e-9, 1e-15) + Vector3d(GZ_SQRT2, -GZ_SQRT2, -1) * 0.25e-9, 1e-15) # Principal moments [4, 4, 6] # rotate by 30, 60, 0 degrees @@ -587,12 +587,12 @@ def test_principal_axes_offset_no_repeat(self): # Tri-diagonal matrix with identical diagonal terms self.verify_non_diagonal_moments_and_axes( - Vector3d(4-IGN_SQRT2, 4, 4+IGN_SQRT2), + Vector3d(4-GZ_SQRT2, 4, 4+GZ_SQRT2), Vector3d(4.0, 4.0, 4.0), Vector3d(-1.0, 0, -1.0)) # small magnitude, use tolerance of 1e-15 self.verify_non_diagonal_moments_and_axes( - Vector3d(4-IGN_SQRT2, 4, 4+IGN_SQRT2) * 1e-9, + Vector3d(4-GZ_SQRT2, 4, 4+GZ_SQRT2) * 1e-9, Vector3d(4.0, 4.0, 4.0) * 1e-9, Vector3d(-1.0, 0, -1.0) * 1e-9, 1e-15) @@ -710,7 +710,7 @@ def test_equivalent_box(self): rot = Quaterniond() self.assertTrue(m.equivalent_box(size, rot, -1e-6)) self.assertEqual(size, Vector3d(9, 4, 1)) - self.assertEqual(rot, Quaterniond(0, 0, IGN_PI/2)) + self.assertEqual(rot, Quaterniond(0, 0, GZ_PI/2)) m2 = MassMatrix3d() self.assertTrue(m2.set_from_box(mass, size, rot)) @@ -726,8 +726,8 @@ def test_equivalent_box(self): self.assertTrue(m.equivalent_box(size, rot)) self.assertEqual(size, Vector3d(9, 4, 1)) # There are multiple correct rotations due to box symmetry - self.assertTrue(rot == Quaterniond(0, 0, IGN_PI/4) or - rot == Quaterniond(IGN_PI, 0, IGN_PI/4)) + self.assertTrue(rot == Quaterniond(0, 0, GZ_PI/4) or + rot == Quaterniond(GZ_PI, 0, GZ_PI/4)) m2 = MassMatrix3d() self.assertTrue(m2.set_from_box(mass, size, rot)) @@ -778,7 +778,7 @@ def test_set_from_cylinderZ(self): self.assertEqual(m.diagonal_moments(), ixxyyzz) self.assertEqual(m.off_diagonal_moments(), Vector3d.ZERO) - density = mass / (IGN_PI * radius * radius * length) + density = mass / (GZ_PI * radius * radius * length) mat = Material(density) self.assertEqual(density, mat.density()) m1 = MassMatrix3d() @@ -813,7 +813,7 @@ def test_set_from_sphere(self): self.assertEqual(m.diagonal_moments(), ixxyyzz) self.assertEqual(m.off_diagonal_moments(), Vector3d.ZERO) - density = mass / ((4.0/3.0) * IGN_PI * math.pow(radius, 3)) + density = mass / ((4.0/3.0) * GZ_PI * math.pow(radius, 3)) mat = Material(density) self.assertEqual(density, mat.density()) m1 = MassMatrix3d() diff --git a/src/ruby/Helpers.i b/src/ruby/Helpers.i index 7aabfbb17..092ee4f58 100644 --- a/src/ruby/Helpers.i +++ b/src/ruby/Helpers.i @@ -23,20 +23,25 @@ %include "std_string.i" %include "std_vector.i" -/// \brief Define IGN_PI, IGN_PI_2, and IGN_PI_4. +/// \brief Define GZ_PI, GZ_PI_2, and GZ_PI_4. /// This was put here for Windows support. #ifdef M_PI -#define IGN_PI M_PI -#define IGN_PI_2 M_PI_2 -#define IGN_PI_4 M_PI_4 -#define IGN_SQRT2 M_SQRT2 +#define GZ_PI M_PI +#define GZ_PI_2 M_PI_2 +#define GZ_PI_4 M_PI_4 +#define GZ_SQRT2 M_SQRT2 #else -#define IGN_PI 3.14159265358979323846 -#define IGN_PI_2 1.57079632679489661923 -#define IGN_PI_4 0.78539816339744830962 -#define IGN_SQRT2 1.41421356237309504880 +#define GZ_PI 3.14159265358979323846 +#define GZ_PI_2 1.57079632679489661923 +#define GZ_PI_4 0.78539816339744830962 +#define GZ_SQRT2 1.41421356237309504880 #endif +// TODO(CH3): Deprecated. Remove on tock. +#define IGN_PI GZ_PI +#define IGN_PI_2 GZ_PI_2 +#define IGN_PI_4 GZ_PI_4 +#define IGN_SQRT2 GZ_SQRT2 // The uppercase functions in the pythoncode block are defined with `#define` in cpp // but in python this may generate some issues. A workaround is to create a Python function. @@ -45,17 +50,33 @@ %pythoncode %{ import math +def gz_sphere_volume(_radius): + return (4.0*GZ_PI*math.pow(_radius, 3)/3.0) + +def gz_cylinder_volume(_r, _l): + return (_l * GZ_PI * math.pow(_r, 2)) + +def gz_box_volume(_x, _y, _z): + return (_x *_y * _z) + +def gz_box_volume_v(_v): + return (_v.x() *_v.y() * _v.z()) + +# TODO(CH3): Deprecated. Remove on tock. def ign_sphere_volume(_radius): - return (4.0*IGN_PI*math.pow(_radius, 3)/3.0) + return gz_sphere_volume(_radius) +# TODO(CH3): Deprecated. Remove on tock. def ign_cylinder_volume(_r, _l): - return (_l * IGN_PI * math.pow(_r, 2)) + return gz_cylinder_volume(_r, _l) +# TODO(CH3): Deprecated. Remove on tock. def ign_box_volume(_x, _y, _z): - return (_x *_y * _z) + return gz_box_volume(_x, _y, _z) +# TODO(CH3): Deprecated. Remove on tock. def ign_box_volume_v(_v): - return (_v.x() *_v.y() * _v.z()) + return gz_box_volume_v(_v) def sort2(_a, _b): def swap(s1, s2): From f0bec8fe9b4157349ea7a0e1f05c3efc294ce38e Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 6 Jun 2022 16:14:13 -0700 Subject: [PATCH 2/9] Update migration guide to mention header-dependent macros Signed-off-by: methylDragon --- Migration.md | 1 + 1 file changed, 1 insertion(+) diff --git a/Migration.md b/Migration.md index ffbe800b6..320debd0f 100644 --- a/Migration.md +++ b/Migration.md @@ -70,6 +70,7 @@ release will remove the deprecated code. 1. Header files under `ignition/...` are deprecated and will be removed in future versions. Use `gz/...` instead. 1. The following `IGN_` prefixed macros are deprecated and will be removed in future versions. + Additionally, they will only be available when including the corresponding `ignition/...` header. Use the `GZ_` prefix instead. 1. `IGN_RTOD`, `IGN_DTOR` 1. `IGN_NORMALIZE` From 6a0569fc2b138f2c7b84972d276f0e9922855964 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 6 Jun 2022 18:00:13 -0700 Subject: [PATCH 3/9] Fold in some unrelated comment changes Signed-off-by: methylDragon --- include/gz/math/Matrix3.hh | 2 +- include/gz/math/Quaternion.hh | 2 +- include/gz/math/Temperature.hh | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/include/gz/math/Matrix3.hh b/include/gz/math/Matrix3.hh index 2904b2441..dfdbf403c 100644 --- a/include/gz/math/Matrix3.hh +++ b/include/gz/math/Matrix3.hh @@ -50,7 +50,7 @@ namespace gz /// /// * Ruby /// \code{.rb} - /// # Modify the RUBYLIB environment variable to include the ignition math + /// # Modify the RUBYLIB environment variable to include the Gazebo Math /// # library install path. For example, if you install to /user: /// # /// # $ export RUBYLIB=/usr/lib/ruby:$RUBYLIB diff --git a/include/gz/math/Quaternion.hh b/include/gz/math/Quaternion.hh index 0ef1e38cc..635e75deb 100644 --- a/include/gz/math/Quaternion.hh +++ b/include/gz/math/Quaternion.hh @@ -51,7 +51,7 @@ namespace gz /// * Ruby /// /// \code{.rb} - /// # Modify the RUBYLIB environment variable to include the ignition math + /// # Modify the RUBYLIB environment variable to include the Gazebo Math /// # library install path. For example, if you install to /user: /// # /// # $ export RUBYLIB=/usr/lib/ruby:$RUBYLIB diff --git a/include/gz/math/Temperature.hh b/include/gz/math/Temperature.hh index 03f629a34..9d352486b 100644 --- a/include/gz/math/Temperature.hh +++ b/include/gz/math/Temperature.hh @@ -49,7 +49,7 @@ namespace gz /// /// * Ruby /// \code{.cc} - /// # Modify the RUBYLIB environment variable to include the ignition math + /// # Modify the RUBYLIB environment variable to include the Gazebo Math /// # library install path. For example, if you install to /user: /// # /// # $ export RUBYLIB=/usr/lib/ruby:$RUBYLIB From 6b34caf2ca5ea7ca7c934e4e55d76823498d34c1 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Tue, 7 Jun 2022 11:34:16 -0700 Subject: [PATCH 4/9] Tick-tock pybind methods Signed-off-by: methylDragon --- src/python_pybind11/src/Helpers.cc | 51 +++++++++++++++++++++++++++++- 1 file changed, 50 insertions(+), 1 deletion(-) diff --git a/src/python_pybind11/src/Helpers.cc b/src/python_pybind11/src/Helpers.cc index ca851aa65..b9fd0b605 100644 --- a/src/python_pybind11/src/Helpers.cc +++ b/src/python_pybind11/src/Helpers.cc @@ -15,6 +15,7 @@ * */ #include +#include #include @@ -67,6 +68,39 @@ float BoxVolumeV(const gz::math::Vector3d &_v) return GZ_BOX_VOLUME_V(_v); } +// TODO(CH3): Deprecated. Remove on tock. +float SphereVolumeDeprecated(const float _radius) +{ + std::cerr << "ign_sphere_volume is deprecated. " + << "Please use gz_sphere_volume instead" + << std::endl; + return SphereVolume(_radius); +} + +float CylinderVolumeDeprecated(const float _r, const float _l) +{ + std::cerr << "ign_cylinder_volume is deprecated. " + << "Please use gz_cylinder_volume instead" + << std::endl; + return CylinderVolume(_r, _l); +} + +float BoxVolumeDeprecated(const float _x, const float _y, const float _z) +{ + std::cerr << "ign_box_volume is deprecated. " + << "Please use gz_box_volume instead" + << std::endl; + return BoxVolume(_x, _y, _z); +} + +float BoxVolumeVDeprecated(const gz::math::Vector3d &_v) +{ + std::cerr << "ign_box_volume_v is deprecated. " + << "Please use gz_box_volume_v instead" + << std::endl; + return BoxVolumeV(_v); +} + /// \brief Sort two numbers, such that _a <= _b /// \param[out] _a the first number /// \param[out] _b the second number @@ -175,7 +209,22 @@ void defineMathHelpers(py::module &m) "Compute box volume") .def("gz_box_volume_v", &BoxVolumeV, - "Compute box volume from vector"); + "Compute box volume from vector") + + // TODO(CH3): Deprecated. Remove on tock. + .def("ign_sphere_volume", + &SphereVolumeDeprecated, + "[Deprecated] Compute sphere volume") + .def("ign_cylinder_volume", + &CylinderVolumeDeprecated, + "[Deprecated] Compute cylinder volume") + .def("ign_box_volume", + &BoxVolumeDeprecated, + "[Deprecated] Compute box volume") + .def("ign_box_volume_v", + &BoxVolumeVDeprecated, + "[Deprecated] Compute box volume from vector"); + py::class_(m, "Helpers", py::buffer_protocol(), From c1d3f68c69cbb5f6e12479f2ad47cb180dd898b4 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Tue, 7 Jun 2022 13:27:06 -0700 Subject: [PATCH 5/9] Ticktock IGN_*_SIZE_T and IGN_MASSMATRIX3_DEFAULT_TOLERANCE Signed-off-by: methylDragon --- Migration.md | 3 ++ include/gz/math/Helpers.hh | 48 +++++++++++++++++--------- include/gz/math/Inertial.hh | 2 +- include/gz/math/Line2.hh | 2 +- include/gz/math/Line3.hh | 2 +- include/gz/math/MassMatrix3.hh | 12 +++---- include/gz/math/Matrix3.hh | 12 +++---- include/gz/math/Matrix4.hh | 8 ++--- include/gz/math/Triangle.hh | 2 +- include/gz/math/Triangle3.hh | 2 +- include/gz/math/Vector2.hh | 4 +-- include/gz/math/Vector3.hh | 4 +-- include/gz/math/Vector4.hh | 4 +-- src/Helpers.i | 37 ++++++++++++++------ src/python_pybind11/src/Helpers.cc | 20 +++++------ src/python_pybind11/src/Inertial.hh | 2 +- src/python_pybind11/src/MassMatrix3.hh | 8 ++--- src/ruby/Helpers.i | 32 +++++++++++------ src/ruby/Inertial.i | 2 +- src/ruby/MassMatrix3.i | 12 +++---- 20 files changed, 133 insertions(+), 85 deletions(-) diff --git a/Migration.md b/Migration.md index 320debd0f..1e3f97e82 100644 --- a/Migration.md +++ b/Migration.md @@ -78,6 +78,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 diff --git a/include/gz/math/Helpers.hh b/include/gz/math/Helpers.hh index 28364423b..a1dfbd9d4 100644 --- a/include/gz/math/Helpers.hh +++ b/include/gz/math/Helpers.hh @@ -34,6 +34,10 @@ /// \brief The default tolerance value used by MassMatrix3::IsValid(), /// MassMatrix3::IsPositive(), and MassMatrix3::ValidMoments() template +constexpr T GZ_MASSMATRIX3_DEFAULT_TOLERANCE = T(10); + +// TODO(CH3): Deprecated. Remove on tock. +template constexpr T IGN_MASSMATRIX3_DEFAULT_TOLERANCE = T(10); /// \brief Define GZ_PI, GZ_PI_2, and GZ_PI_4. @@ -87,34 +91,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::max(); @@ -153,7 +169,7 @@ namespace gz static const uint16_t MIN_UI16 = std::numeric_limits::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::lowest(); /// \brief 16-bit unsigned integer positive infinite value @@ -166,7 +182,7 @@ namespace gz static const int16_t MIN_I16 = std::numeric_limits::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::lowest(); /// \brief 16-bit unsigned integer positive infinite value @@ -179,7 +195,7 @@ namespace gz static const uint32_t MIN_UI32 = std::numeric_limits::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::lowest(); /// \brief 32-bit unsigned integer positive infinite value @@ -192,7 +208,7 @@ namespace gz static const int32_t MIN_I32 = std::numeric_limits::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::lowest(); /// \brief 32-bit unsigned integer positive infinite value @@ -205,7 +221,7 @@ namespace gz static const uint64_t MIN_UI64 = std::numeric_limits::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::lowest(); /// \brief 64-bit unsigned integer positive infinite value @@ -218,7 +234,7 @@ namespace gz static const int64_t MIN_I64 = std::numeric_limits::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::lowest(); /// \brief 64-bit unsigned integer positive infinite value diff --git a/include/gz/math/Inertial.hh b/include/gz/math/Inertial.hh index eb24f149f..9b2b5f3b3 100644 --- a/include/gz/math/Inertial.hh +++ b/include/gz/math/Inertial.hh @@ -80,7 +80,7 @@ namespace gz /// /// \return True if the MassMatrix3 is valid. public: bool SetMassMatrix(const MassMatrix3 &_m, - const T _tolerance = IGN_MASSMATRIX3_DEFAULT_TOLERANCE) + const T _tolerance = GZ_MASSMATRIX3_DEFAULT_TOLERANCE) { this->massMatrix = _m; return this->massMatrix.IsValid(_tolerance); diff --git a/include/gz/math/Line2.hh b/include/gz/math/Line2.hh index 0b2e87b83..40179806e 100644 --- a/include/gz/math/Line2.hh +++ b/include/gz/math/Line2.hh @@ -293,7 +293,7 @@ namespace gz /// is clamped to the range [0, 1] public: math::Vector2 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 diff --git a/include/gz/math/Line3.hh b/include/gz/math/Line3.hh index 233bb41a6..836047e7b 100644 --- a/include/gz/math/Line3.hh +++ b/include/gz/math/Line3.hh @@ -382,7 +382,7 @@ namespace gz /// parameter is clamped to the range [0, 1]. public: math::Vector3 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 diff --git a/include/gz/math/MassMatrix3.hh b/include/gz/math/MassMatrix3.hh index 9c31e146d..d80f47339 100644 --- a/include/gz/math/MassMatrix3.hh +++ b/include/gz/math/MassMatrix3.hh @@ -297,7 +297,7 @@ namespace gz /// \endcode /// public: bool IsNearPositive(const T _tolerance = - IGN_MASSMATRIX3_DEFAULT_TOLERANCE) const + GZ_MASSMATRIX3_DEFAULT_TOLERANCE) const { const T epsilon = this->Epsilon(_tolerance); @@ -330,7 +330,7 @@ namespace gz /// \endcode /// public: bool IsPositive(const T _tolerance = - IGN_MASSMATRIX3_DEFAULT_TOLERANCE) const + GZ_MASSMATRIX3_DEFAULT_TOLERANCE) const { const T epsilon = this->Epsilon(_tolerance); @@ -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) const + GZ_MASSMATRIX3_DEFAULT_TOLERANCE) const { return Epsilon(this->DiagonalMoments(), _tolerance); } @@ -379,7 +379,7 @@ namespace gz /// \endcode public: static T Epsilon(const Vector3 &_moments, const T _tolerance = - IGN_MASSMATRIX3_DEFAULT_TOLERANCE) + GZ_MASSMATRIX3_DEFAULT_TOLERANCE) { // The following was borrowed heavily from: // https://github.com/RobotLocomotion/drake/blob/v0.27.0/multibody/tree/rotational_inertia.h @@ -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) const + GZ_MASSMATRIX3_DEFAULT_TOLERANCE) const { return this->IsNearPositive(_tolerance) && ValidMoments(this->PrincipalMoments(), _tolerance); @@ -444,7 +444,7 @@ namespace gz /// _moments[2] + _moments[0] + epsilon >= _moments[1]; /// \endcode public: static bool ValidMoments(const Vector3 &_moments, - const T _tolerance = IGN_MASSMATRIX3_DEFAULT_TOLERANCE) + const T _tolerance = GZ_MASSMATRIX3_DEFAULT_TOLERANCE) { T epsilon = Epsilon(_moments, _tolerance); diff --git a/include/gz/math/Matrix3.hh b/include/gz/math/Matrix3.hh index dfdbf403c..761f387a1 100644 --- a/include/gz/math/Matrix3.hh +++ b/include/gz/math/Matrix3.hh @@ -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. @@ -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. @@ -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. diff --git a/include/gz/math/Matrix4.hh b/include/gz/math/Matrix4.hh index de26018ff..d63393cba 100644 --- a/include/gz/math/Matrix4.hh +++ b/include/gz/math/Matrix4.hh @@ -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, @@ -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. diff --git a/include/gz/math/Triangle.hh b/include/gz/math/Triangle.hh index 05fecc4a3..15e8d19cf 100644 --- a/include/gz/math/Triangle.hh +++ b/include/gz/math/Triangle.hh @@ -226,7 +226,7 @@ namespace gz /// \return The point specified by _index. public: math::Vector2 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 diff --git a/include/gz/math/Triangle3.hh b/include/gz/math/Triangle3.hh index 677ae06a0..ae90171eb 100644 --- a/include/gz/math/Triangle3.hh +++ b/include/gz/math/Triangle3.hh @@ -265,7 +265,7 @@ namespace gz /// \return The triangle point at _index. public: Vector3 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 diff --git a/include/gz/math/Vector2.hh b/include/gz/math/Vector2.hh index 629768f3e..3fef1be5c 100644 --- a/include/gz/math/Vector2.hh +++ b/include/gz/math/Vector2.hh @@ -473,7 +473,7 @@ 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 @@ -481,7 +481,7 @@ namespace gz /// 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. diff --git a/include/gz/math/Vector3.hh b/include/gz/math/Vector3.hh index 8ccd50175..2e30191ec 100644 --- a/include/gz/math/Vector3.hh +++ b/include/gz/math/Vector3.hh @@ -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 @@ -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 diff --git a/include/gz/math/Vector4.hh b/include/gz/math/Vector4.hh index beae5ab70..4770c2056 100644 --- a/include/gz/math/Vector4.hh +++ b/include/gz/math/Vector4.hh @@ -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 @@ -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. diff --git a/src/Helpers.i b/src/Helpers.i index aba436ae7..b49db4893 100644 --- a/src/Helpers.i +++ b/src/Helpers.i @@ -25,6 +25,10 @@ #include %} +template +constexpr T GZ_MASSMATRIX3_DEFAULT_TOLERANCE = T(10); + +// TODO(CH3): Deprecated. Remove on tock. template constexpr T IGN_MASSMATRIX3_DEFAULT_TOLERANCE = T(10); @@ -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::max(); static const double MIN_D = std::numeric_limits::min(); static const double LOW_D = std::numeric_limits::lowest(); diff --git a/src/python_pybind11/src/Helpers.cc b/src/python_pybind11/src/Helpers.cc index b9fd0b605..643ea7e44 100644 --- a/src/python_pybind11/src/Helpers.cc +++ b/src/python_pybind11/src/Helpers.cc @@ -229,16 +229,16 @@ void defineMathHelpers(py::module &m) "Helpers", py::buffer_protocol(), py::dynamic_attr()) - .def_readonly_static("IGNZEROSIZET", &IGN_ZERO_SIZE_T, "GZ_PI") - .def_readonly_static("IGN_ONE_SIZE_T", &IGN_ONE_SIZE_T) - .def_readonly_static("IGN_TWO_SIZE_T", &IGN_TWO_SIZE_T) - .def_readonly_static("IGN_THREE_SIZE_T", &IGN_THREE_SIZE_T) - .def_readonly_static("IGN_FOUR_SIZE_T", &IGN_FOUR_SIZE_T) - .def_readonly_static("IGN_FIVE_SIZE_T", &IGN_FIVE_SIZE_T) - .def_readonly_static("IGN_SIX_SIZE_T", &IGN_SIX_SIZE_T) - .def_readonly_static("IGN_SEVEN_SIZE_T", &IGN_SEVEN_SIZE_T) - .def_readonly_static("IGN_EIGHT_SIZE_T", &IGN_EIGHT_SIZE_T) - .def_readonly_static("IGN_NINE_SIZE_T", &IGN_NINE_SIZE_T) + .def_readonly_static("IGNZEROSIZET", &GZ_ZERO_SIZE_T, "GZ_PI") + .def_readonly_static("GZ_ONE_SIZE_T", &GZ_ONE_SIZE_T) + .def_readonly_static("GZ_TWO_SIZE_T", &GZ_TWO_SIZE_T) + .def_readonly_static("GZ_THREE_SIZE_T", &GZ_THREE_SIZE_T) + .def_readonly_static("GZ_FOUR_SIZE_T", &GZ_FOUR_SIZE_T) + .def_readonly_static("GZ_FIVE_SIZE_T", &GZ_FIVE_SIZE_T) + .def_readonly_static("GZ_SIX_SIZE_T", &GZ_SIX_SIZE_T) + .def_readonly_static("GZ_SEVEN_SIZE_T", &GZ_SEVEN_SIZE_T) + .def_readonly_static("GZ_EIGHT_SIZE_T", &GZ_EIGHT_SIZE_T) + .def_readonly_static("GZ_NINE_SIZE_T", &GZ_NINE_SIZE_T) .def_readonly_static("MAX_D", &MAX_D) .def_readonly_static("MIN_D", &MIN_D) .def_readonly_static("LOW_D", &LOW_D) diff --git a/src/python_pybind11/src/Inertial.hh b/src/python_pybind11/src/Inertial.hh index 7661ce70f..b92b924c5 100644 --- a/src/python_pybind11/src/Inertial.hh +++ b/src/python_pybind11/src/Inertial.hh @@ -63,7 +63,7 @@ void defineMathInertial(py::module &m, const std::string &typestr) .def("set_mass_matrix", &Class::SetMassMatrix, py::arg("_m") = gz::math::MassMatrix3(), - py::arg("_tolerance") = IGN_MASSMATRIX3_DEFAULT_TOLERANCE, + py::arg("_tolerance") = GZ_MASSMATRIX3_DEFAULT_TOLERANCE, "Set the mass and inertia matrix.") .def("mass_matrix", &Class::MassMatrix, diff --git a/src/python_pybind11/src/MassMatrix3.hh b/src/python_pybind11/src/MassMatrix3.hh index 0b7b42815..e4d87da34 100644 --- a/src/python_pybind11/src/MassMatrix3.hh +++ b/src/python_pybind11/src/MassMatrix3.hh @@ -178,24 +178,24 @@ void helpDefineMathMassMatrix3(py::module &m, const std::string &typestr) "Verify that principal moments are positive") .def("is_valid", &Class::IsValid, - py::arg("_tolerance") = IGN_MASSMATRIX3_DEFAULT_TOLERANCE, + py::arg("_tolerance") = GZ_MASSMATRIX3_DEFAULT_TOLERANCE, "Verify that inertia values are positive semi-definite " "and satisfy the triangle inequality.") .def("epsilon", py::overload_cast&, const T> (&Class::Epsilon), - py::arg("_tolerance") = IGN_MASSMATRIX3_DEFAULT_TOLERANCE, + py::arg("_tolerance") = GZ_MASSMATRIX3_DEFAULT_TOLERANCE, "Get an epsilon value that represents the amount of " "acceptable error in a MassMatrix3. The epsilon value " "is related to machine precision multiplied by the largest possible " "moment of inertia.") .def("is_positive", &Class::IsPositive, - py::arg("_tolerance") = IGN_MASSMATRIX3_DEFAULT_TOLERANCE, + py::arg("_tolerance") = GZ_MASSMATRIX3_DEFAULT_TOLERANCE, "Verify that inertia values are positive definite") .def("is_near_positive", &Class::IsNearPositive, - py::arg("_tolerance") = IGN_MASSMATRIX3_DEFAULT_TOLERANCE, + py::arg("_tolerance") = GZ_MASSMATRIX3_DEFAULT_TOLERANCE, "Verify that inertia values are positive semidefinite") .def(py::self != py::self) .def(py::self == py::self); diff --git a/src/ruby/Helpers.i b/src/ruby/Helpers.i index 092ee4f58..8abbb6567 100644 --- a/src/ruby/Helpers.i +++ b/src/ruby/Helpers.i @@ -183,25 +183,37 @@ namespace gz { %rename("%(undercase)s", %$isfunction, notregexmatch$name="^[A-Z]*$") ""; - static const size_t IGN_ZERO_SIZE_T = 0u; + static const size_t GZ_ZERO_SIZE_T = 0u; - static const size_t IGN_ONE_SIZE_T = 1u; + static const size_t GZ_ONE_SIZE_T = 1u; - static const size_t IGN_TWO_SIZE_T = 2u; + static const size_t GZ_TWO_SIZE_T = 2u; - static const size_t IGN_THREE_SIZE_T = 3u; + static const size_t GZ_THREE_SIZE_T = 3u; - static const size_t IGN_FOUR_SIZE_T = 4u; + static const size_t GZ_FOUR_SIZE_T = 4u; - static const size_t IGN_FIVE_SIZE_T = 5u; + static const size_t GZ_FIVE_SIZE_T = 5u; - static const size_t IGN_SIX_SIZE_T = 6u; + static const size_t GZ_SIX_SIZE_T = 6u; - static const size_t IGN_SEVEN_SIZE_T = 7u; + static const size_t GZ_SEVEN_SIZE_T = 7u; - static const size_t IGN_EIGHT_SIZE_T = 8u; + static const size_t GZ_EIGHT_SIZE_T = 8u; - 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; static const double MAX_D = std::numeric_limits::max(); diff --git a/src/ruby/Inertial.i b/src/ruby/Inertial.i index 49b4c34d5..bc7e385c6 100644 --- a/src/ruby/Inertial.i +++ b/src/ruby/Inertial.i @@ -40,7 +40,7 @@ namespace gz public: ~Inertial() = default; public: bool SetMassMatrix(const MassMatrix3 &_m, - const T _tolerance = IGN_MASSMATRIX3_DEFAULT_TOLERANCE); + const T _tolerance = GZ_MASSMATRIX3_DEFAULT_TOLERANCE); public: const MassMatrix3 &MassMatrix() const; diff --git a/src/ruby/MassMatrix3.i b/src/ruby/MassMatrix3.i index 32c02a8cd..4e13f035b 100644 --- a/src/ruby/MassMatrix3.i +++ b/src/ruby/MassMatrix3.i @@ -67,18 +67,18 @@ namespace gz public: bool operator==(const MassMatrix3 &_m) const; public: bool operator!=(const MassMatrix3 &_m) const; public: bool IsNearPositive(const T _tolerance = - IGN_MASSMATRIX3_DEFAULT_TOLERANCE) const; + GZ_MASSMATRIX3_DEFAULT_TOLERANCE) const; public: bool IsPositive(const T _tolerance = - IGN_MASSMATRIX3_DEFAULT_TOLERANCE) const; + GZ_MASSMATRIX3_DEFAULT_TOLERANCE) const; public: T Epsilon(const T _tolerance = - IGN_MASSMATRIX3_DEFAULT_TOLERANCE) const; + GZ_MASSMATRIX3_DEFAULT_TOLERANCE) const; public: static T Epsilon(const Vector3 &_moments, const T _tolerance = - IGN_MASSMATRIX3_DEFAULT_TOLERANCE); + GZ_MASSMATRIX3_DEFAULT_TOLERANCE); public: bool IsValid(const T _tolerance = - IGN_MASSMATRIX3_DEFAULT_TOLERANCE) const; + GZ_MASSMATRIX3_DEFAULT_TOLERANCE) const; public: static bool ValidMoments(const Vector3 &_moments, - const T _tolerance = IGN_MASSMATRIX3_DEFAULT_TOLERANCE); + const T _tolerance = GZ_MASSMATRIX3_DEFAULT_TOLERANCE); public: Vector3 PrincipalMoments(const T _tol = 1e-6) const; public: Quaternion PrincipalAxesOffset(const T _tol = 1e-6) const; public: bool EquivalentBox(Vector3 &_size, From 2463260624c386ede20f14c93a589ccb191ab1b8 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Wed, 8 Jun 2022 15:24:19 -0700 Subject: [PATCH 6/9] Migrate forward ported macros Signed-off-by: methylDragon --- src/Pose_TEST.cc | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/Pose_TEST.cc b/src/Pose_TEST.cc index 25bced1ac..885b965b0 100644 --- a/src/Pose_TEST.cc +++ b/src/Pose_TEST.cc @@ -105,7 +105,7 @@ TEST(PoseTest, Pose) EXPECT_TRUE(math::equal( (A.Inverse() * math::Pose3d()).Rot().Euler().Z(), -IGN_PI/4)); - IGN_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION + GZ_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION // Coverage for unitary - operator // test negation operator EXPECT_TRUE(math::equal((-A).Pos().X(), -1.0/sqrt(2))); @@ -114,7 +114,7 @@ TEST(PoseTest, Pose) EXPECT_TRUE(math::equal((-A).Rot().Euler().X(), 0.0)); EXPECT_TRUE(math::equal((-A).Rot().Euler().Y(), 0.0)); EXPECT_TRUE(math::equal((-A).Rot().Euler().Z(), -IGN_PI/4.0)); - IGN_UTILS_WARN_RESUME__DEPRECATED_DECLARATION + GZ_UTILS_WARN_RESUME__DEPRECATED_DECLARATION } { // If: @@ -132,7 +132,7 @@ TEST(PoseTest, Pose) EXPECT_TRUE(math::equal((A.Inverse() * B).Rot().Euler().Y(), 0.0)); EXPECT_TRUE(math::equal((A.Inverse() * B).Rot().Euler().Z(), IGN_PI/4.0)); - IGN_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION + GZ_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION // Coverage for - operator EXPECT_EQ(A.Inverse() * B, B - A); @@ -140,7 +140,7 @@ TEST(PoseTest, Pose) math::Pose3d C(B); C -= A; EXPECT_EQ(C, A.Inverse() * B); - IGN_UTILS_WARN_RESUME__DEPRECATED_DECLARATION + GZ_UTILS_WARN_RESUME__DEPRECATED_DECLARATION } { math::Pose3d pose; From df139027f464fb836659830fe5cff424cd073573 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Wed, 8 Jun 2022 21:00:17 -0700 Subject: [PATCH 7/9] new IGN_PI Signed-off-by: Louise Poubel --- src/Pose_TEST.cc | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/Pose_TEST.cc b/src/Pose_TEST.cc index 885b965b0..8ffdbe4e3 100644 --- a/src/Pose_TEST.cc +++ b/src/Pose_TEST.cc @@ -91,7 +91,7 @@ TEST(PoseTest, Pose) // B is the transform from O to Q in frame O // then -A is transform from P to O specified in frame P math::Pose3d A(math::Vector3d(1, 0, 0), - math::Quaterniond(0, 0, IGN_PI/4.0)); + math::Quaterniond(0, 0, GZ_PI/4.0)); EXPECT_TRUE(math::equal( (A.Inverse() * math::Pose3d()).Pos().X(), -1.0/sqrt(2))); EXPECT_TRUE(math::equal( @@ -103,7 +103,7 @@ TEST(PoseTest, Pose) EXPECT_TRUE(math::equal( (A.Inverse() * math::Pose3d()).Rot().Euler().Y(), 0.0)); EXPECT_TRUE(math::equal( - (A.Inverse() * math::Pose3d()).Rot().Euler().Z(), -IGN_PI/4)); + (A.Inverse() * math::Pose3d()).Rot().Euler().Z(), -GZ_PI/4)); GZ_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION // Coverage for unitary - operator @@ -113,7 +113,7 @@ TEST(PoseTest, Pose) EXPECT_TRUE(math::equal((-A).Pos().Z(), 0.0)); EXPECT_TRUE(math::equal((-A).Rot().Euler().X(), 0.0)); EXPECT_TRUE(math::equal((-A).Rot().Euler().Y(), 0.0)); - EXPECT_TRUE(math::equal((-A).Rot().Euler().Z(), -IGN_PI/4.0)); + EXPECT_TRUE(math::equal((-A).Rot().Euler().Z(), -GZ_PI/4.0)); GZ_UTILS_WARN_RESUME__DEPRECATED_DECLARATION } { @@ -124,13 +124,13 @@ TEST(PoseTest, Pose) math::Pose3d A(math::Vector3d(1, 0, 0), math::Quaterniond(0, 0, GZ_PI/4.0)); math::Pose3d B(math::Vector3d(1, 1, 0), - math::Quaterniond(0, 0, IGN_PI/2.0)); + math::Quaterniond(0, 0, GZ_PI/2.0)); EXPECT_TRUE(math::equal((A.Inverse() * B).Pos().X(), 1.0/sqrt(2))); EXPECT_TRUE(math::equal((A.Inverse() * B).Pos().Y(), 1.0/sqrt(2))); EXPECT_TRUE(math::equal((A.Inverse() * B).Pos().Z(), 0.0)); EXPECT_TRUE(math::equal((A.Inverse() * B).Rot().Euler().X(), 0.0)); EXPECT_TRUE(math::equal((A.Inverse() * B).Rot().Euler().Y(), 0.0)); - EXPECT_TRUE(math::equal((A.Inverse() * B).Rot().Euler().Z(), IGN_PI/4.0)); + EXPECT_TRUE(math::equal((A.Inverse() * B).Rot().Euler().Z(), GZ_PI/4.0)); GZ_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION // Coverage for - operator From 4865e742bf9898555abbcba33cb52c00929d2d95 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Thu, 9 Jun 2022 10:59:07 -0700 Subject: [PATCH 8/9] Tick-tock IGNZEROSIZET python binding Signed-off-by: methylDragon --- src/python_pybind11/src/Helpers.cc | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/src/python_pybind11/src/Helpers.cc b/src/python_pybind11/src/Helpers.cc index 643ea7e44..7ebe98986 100644 --- a/src/python_pybind11/src/Helpers.cc +++ b/src/python_pybind11/src/Helpers.cc @@ -229,7 +229,7 @@ void defineMathHelpers(py::module &m) "Helpers", py::buffer_protocol(), py::dynamic_attr()) - .def_readonly_static("IGNZEROSIZET", &GZ_ZERO_SIZE_T, "GZ_PI") + .def_readonly_static("GZZEROSIZET", &GZ_ZERO_SIZE_T, "GZ_PI") .def_readonly_static("GZ_ONE_SIZE_T", &GZ_ONE_SIZE_T) .def_readonly_static("GZ_TWO_SIZE_T", &GZ_TWO_SIZE_T) .def_readonly_static("GZ_THREE_SIZE_T", &GZ_THREE_SIZE_T) @@ -239,6 +239,19 @@ void defineMathHelpers(py::module &m) .def_readonly_static("GZ_SEVEN_SIZE_T", &GZ_SEVEN_SIZE_T) .def_readonly_static("GZ_EIGHT_SIZE_T", &GZ_EIGHT_SIZE_T) .def_readonly_static("GZ_NINE_SIZE_T", &GZ_NINE_SIZE_T) + + // TODO(CH3): Deprecated. Remove on tock. + .def_readonly_static("IGNZEROSIZET", &GZ_ZERO_SIZE_T, "GZ_PI") + .def_readonly_static("IGN_ONE_SIZE_T", &GZ_ONE_SIZE_T) + .def_readonly_static("IGN_TWO_SIZE_T", &GZ_TWO_SIZE_T) + .def_readonly_static("IGN_THREE_SIZE_T", &GZ_THREE_SIZE_T) + .def_readonly_static("IGN_FOUR_SIZE_T", &GZ_FOUR_SIZE_T) + .def_readonly_static("IGN_FIVE_SIZE_T", &GZ_FIVE_SIZE_T) + .def_readonly_static("IGN_SIX_SIZE_T", &GZ_SIX_SIZE_T) + .def_readonly_static("IGN_SEVEN_SIZE_T", &GZ_SEVEN_SIZE_T) + .def_readonly_static("IGN_EIGHT_SIZE_T", &GZ_EIGHT_SIZE_T) + .def_readonly_static("IGN_NINE_SIZE_T", &GZ_NINE_SIZE_T) + .def_readonly_static("MAX_D", &MAX_D) .def_readonly_static("MIN_D", &MIN_D) .def_readonly_static("LOW_D", &LOW_D) From a52fd2cd98b907aadbdc2b0c260d5b2ec40a1fdb Mon Sep 17 00:00:00 2001 From: methylDragon Date: Thu, 16 Jun 2022 10:46:23 -0700 Subject: [PATCH 9/9] Migrate IGNITION_MATH_VISIBLE macros from rebase Signed-off-by: methylDragon --- include/gz/math/Helpers.hh | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/include/gz/math/Helpers.hh b/include/gz/math/Helpers.hh index a1dfbd9d4..a1b98049d 100644 --- a/include/gz/math/Helpers.hh +++ b/include/gz/math/Helpers.hh @@ -579,20 +579,20 @@ namespace gz /// \brief Parse string into an integer. /// \param[in] _input The input string. /// \return An integer, or NAN_I if unable to parse the input. - int IGNITION_MATH_VISIBLE parseInt(const std::string &_input); + int GZ_MATH_VISIBLE parseInt(const std::string &_input); /// \brief parse string into float. /// \param [in] _input The string. /// \return A floating point number (can be NaN) or NAN_D if the /// _input could not be parsed. - double IGNITION_MATH_VISIBLE parseFloat(const std::string &_input); + double GZ_MATH_VISIBLE parseFloat(const std::string &_input); /// \brief Convert a std::chrono::steady_clock::time_point to a seconds and /// nanoseconds pair. /// \param[in] _time The time point to convert. /// \return A pair where the first element is the number of seconds and /// the second is the number of nanoseconds. - std::pair IGNITION_MATH_VISIBLE timePointToSecNsec( + std::pair GZ_MATH_VISIBLE timePointToSecNsec( const std::chrono::steady_clock::time_point &_time); /// \brief Convert seconds and nanoseconds to @@ -601,7 +601,7 @@ namespace gz /// \param[in] _nanosec The nanoseconds to convert. /// \return A std::chrono::steady_clock::time_point based on the number of /// seconds and the number of nanoseconds. - std::chrono::steady_clock::time_point IGNITION_MATH_VISIBLE + std::chrono::steady_clock::time_point GZ_MATH_VISIBLE secNsecToTimePoint( const uint64_t &_sec, const uint64_t &_nanosec); @@ -611,7 +611,7 @@ namespace gz /// \param[in] _nanosec The nanoseconds to convert. /// \return A std::chrono::steady_clock::duration based on the number of /// seconds and the number of nanoseconds. - std::chrono::steady_clock::duration IGNITION_MATH_VISIBLE secNsecToDuration( + std::chrono::steady_clock::duration GZ_MATH_VISIBLE secNsecToDuration( const uint64_t &_sec, const uint64_t &_nanosec); /// \brief Convert a std::chrono::steady_clock::duration to a seconds and @@ -619,7 +619,7 @@ namespace gz /// \param[in] _dur The duration to convert. /// \return A pair where the first element is the number of seconds and /// the second is the number of nanoseconds. - std::pair IGNITION_MATH_VISIBLE durationToSecNsec( + std::pair GZ_MATH_VISIBLE durationToSecNsec( const std::chrono::steady_clock::duration &_dur); // TODO(anyone): Replace this with std::chrono::days.