Skip to content

Commit

Permalink
ign -> gz Macro Migration : gz-math (#437)
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
Signed-off-by: Louise Poubel <[email protected]>

Co-authored-by: Louise Poubel <[email protected]>
  • Loading branch information
methylDragon and chapulina authored Jun 17, 2022
1 parent be960a6 commit 6bb7586
Show file tree
Hide file tree
Showing 77 changed files with 622 additions and 453 deletions.
13 changes: 13 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,19 @@ 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.
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`
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`
1. `IGN_MASSMATRIX3_DEFAULT_TOLERANCE`
1. All `IGN_*_SIZE_T` variables are deprecated and will be removed in future versions.
Please use `GZ_*_SIZE_T` instead.


### Modifications

Expand Down
6 changes: 3 additions & 3 deletions examples/diff_drive_odometry.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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"
Expand All @@ -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"
Expand Down
6 changes: 3 additions & 3 deletions examples/helpers_example.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
6 changes: 3 additions & 3 deletions examples/helpers_example.rb
Original file line number Diff line number Diff line change
Expand Up @@ -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))
Expand Down
4 changes: 2 additions & 2 deletions examples/pose3_example.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion examples/pose3_example.rb
Original file line number Diff line number Diff line change
Expand Up @@ -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())

Expand Down
12 changes: 6 additions & 6 deletions examples/quaternion_from_euler.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand All @@ -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);
Expand Down
6 changes: 3 additions & 3 deletions examples/quaternion_to_euler.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down
18 changes: 9 additions & 9 deletions include/gz/math/Angle.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,23 +22,23 @@
#include <gz/math/Helpers.hh>
#include <gz/math/config.hh>

/// \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
{
Expand Down Expand Up @@ -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 &Pi;

/// \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
Expand Down
2 changes: 1 addition & 1 deletion include/gz/math/AxisAlignedBox.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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)
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/gz/math/DiffDriveOdometry.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down Expand Up @@ -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)
};
}
}
Expand Down
4 changes: 2 additions & 2 deletions include/gz/math/Filter.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}

Expand Down Expand Up @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion include/gz/math/Frustum.hh
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,7 @@ namespace gz
private: void ComputePlanes();

/// \brief Private data pointer
IGN_UTILS_IMPL_PTR(dataPtr)
GZ_UTILS_IMPL_PTR(dataPtr)
};
}
}
Expand Down
2 changes: 1 addition & 1 deletion include/gz/math/GaussMarkovProcess.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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)
};
}
}
Expand Down
Loading

0 comments on commit 6bb7586

Please sign in to comment.