From d6284a56c5510dcac2deefabb0cb9a960f0e471a Mon Sep 17 00:00:00 2001 From: methylDragon Date: Sat, 28 May 2022 09:32:50 -0700 Subject: [PATCH] ign -> gz: namespaces, docs, config.hh (#430) Signed-off-by: methylDragon --- CONTRIBUTING.md | 2 +- Changelog.md | 452 +++++++++--------- Migration.md | 79 +-- README.md | 26 +- api.md.in | 2 +- eigen3/include/gz/math/eigen3/Conversions.hh | 72 +-- eigen3/include/gz/math/eigen3/Util.hh | 4 +- eigen3/include/ignition/math/eigen3.hh | 1 + .../ignition/math/eigen3/Conversions.hh | 1 + eigen3/include/ignition/math/eigen3/Util.hh | 1 + eigen3/src/Conversions_TEST.cc | 80 ++-- eigen3/src/Util_TEST.cc | 2 +- examples/README.md | 2 +- ...itively_separable_scalar_field3_example.cc | 18 +- examples/angle_example.cc | 8 +- examples/angle_example.rb | 8 +- examples/color_example.cc | 12 +- examples/diff_drive_odometry.cc | 2 +- examples/gauss_markov_process_example.cc | 2 +- examples/gauss_markov_process_example.rb | 2 +- examples/graph_example.cc | 8 +- examples/helpers_example.cc | 8 +- examples/helpers_example.rb | 8 +- examples/interval_example.cc | 16 +- examples/kmeans.cc | 30 +- examples/matrix3_example.cc | 6 +- examples/matrix3_example.rb | 4 +- examples/piecewise_scalar_field3_example.cc | 42 +- examples/polynomial3_example.cc | 16 +- examples/pose3_example.cc | 6 +- examples/pose3_example.rb | 4 +- examples/quaternion_example.cc | 8 +- examples/quaternion_example.rb | 6 +- examples/quaternion_from_euler.cc | 4 +- examples/quaternion_to_euler.cc | 6 +- examples/rand_example.cc | 4 +- examples/region3_example.cc | 24 +- examples/temperature_example.cc | 6 +- examples/temperature_example.rb | 6 +- examples/triangle_example.cc | 28 +- examples/vector2_example.cc | 10 +- examples/vector2_example.rb | 6 +- examples/vector3_example.rb | 4 +- .../math/AdditivelySeparableScalarField3.hh | 6 +- include/gz/math/Angle.hh | 14 +- include/gz/math/AxisAlignedBox.hh | 8 +- include/gz/math/Box.hh | 14 +- include/gz/math/Capsule.hh | 4 +- include/gz/math/Color.hh | 6 +- include/gz/math/Cylinder.hh | 4 +- include/gz/math/DiffDriveOdometry.hh | 8 +- include/gz/math/Ellipsoid.hh | 4 +- include/gz/math/Filter.hh | 4 +- include/gz/math/Frustum.hh | 6 +- include/gz/math/GaussMarkovProcess.hh | 6 +- include/gz/math/Helpers.hh | 22 +- include/gz/math/Inertial.hh | 4 +- include/gz/math/Interval.hh | 6 +- include/gz/math/Kmeans.hh | 6 +- include/gz/math/Line2.hh | 4 +- include/gz/math/Line3.hh | 4 +- include/gz/math/MassMatrix3.hh | 4 +- include/gz/math/Material.hh | 10 +- include/gz/math/MaterialType.hh | 4 +- include/gz/math/Matrix3.hh | 20 +- include/gz/math/Matrix4.hh | 8 +- include/gz/math/MovingWindowFilter.hh | 6 +- include/gz/math/OrientedBox.hh | 10 +- include/gz/math/PID.hh | 6 +- include/gz/math/PiecewiseScalarField3.hh | 6 +- include/gz/math/Plane.hh | 4 +- include/gz/math/Polynomial3.hh | 6 +- include/gz/math/Pose3.hh | 16 +- include/gz/math/Quaternion.hh | 42 +- include/gz/math/Rand.hh | 6 +- include/gz/math/Region3.hh | 6 +- include/gz/math/RollingMean.hh | 6 +- include/gz/math/RotationSpline.hh | 6 +- include/gz/math/SemanticVersion.hh | 6 +- include/gz/math/SignalStats.hh | 21 +- include/gz/math/SpeedLimiter.hh | 6 +- include/gz/math/Sphere.hh | 10 +- include/gz/math/SphericalCoordinates.hh | 56 +-- include/gz/math/Spline.hh | 6 +- include/gz/math/Stopwatch.hh | 8 +- include/gz/math/Temperature.hh | 16 +- include/gz/math/Triangle.hh | 4 +- include/gz/math/Triangle3.hh | 4 +- include/gz/math/Vector2.hh | 4 +- include/gz/math/Vector3.hh | 8 +- include/gz/math/Vector3Stats.hh | 6 +- include/gz/math/Vector4.hh | 8 +- include/gz/math/VolumetricGridLookupField.hh | 8 +- include/gz/math/config.hh.in | 38 +- include/gz/math/detail/AxisIndex.hh | 8 +- include/gz/math/detail/Box.hh | 10 +- include/gz/math/detail/Capsule.hh | 2 +- include/gz/math/detail/Cylinder.hh | 2 +- include/gz/math/detail/Ellipsoid.hh | 2 +- include/gz/math/detail/InterpolationPoint.hh | 8 +- include/gz/math/detail/Sphere.hh | 8 +- include/gz/math/detail/WellOrderedVector.hh | 2 +- include/gz/math/graph/Edge.hh | 4 +- include/gz/math/graph/Graph.hh | 12 +- include/gz/math/graph/GraphAlgorithms.hh | 4 +- include/gz/math/graph/Vertex.hh | 4 +- include/ignition/math.hh | 1 + .../math/AdditivelySeparableScalarField3.hh | 1 + include/ignition/math/Angle.hh | 1 + include/ignition/math/AxisAlignedBox.hh | 1 + include/ignition/math/Box.hh | 1 + include/ignition/math/Capsule.hh | 1 + include/ignition/math/Color.hh | 1 + include/ignition/math/Cylinder.hh | 1 + include/ignition/math/DiffDriveOdometry.hh | 1 + include/ignition/math/Ellipsoid.hh | 1 + include/ignition/math/Export.hh | 1 + include/ignition/math/Filter.hh | 1 + include/ignition/math/Frustum.hh | 1 + include/ignition/math/GaussMarkovProcess.hh | 1 + include/ignition/math/Helpers.hh | 1 + include/ignition/math/Inertial.hh | 1 + include/ignition/math/Interval.hh | 1 + include/ignition/math/Kmeans.hh | 1 + include/ignition/math/Line2.hh | 1 + include/ignition/math/Line3.hh | 1 + include/ignition/math/MassMatrix3.hh | 1 + include/ignition/math/Material.hh | 1 + include/ignition/math/MaterialType.hh | 1 + include/ignition/math/Matrix3.hh | 1 + include/ignition/math/Matrix4.hh | 1 + include/ignition/math/MovingWindowFilter.hh | 1 + include/ignition/math/OrientedBox.hh | 1 + include/ignition/math/PID.hh | 1 + .../ignition/math/PiecewiseScalarField3.hh | 1 + include/ignition/math/Plane.hh | 1 + include/ignition/math/Polynomial3.hh | 1 + include/ignition/math/Pose3.hh | 1 + include/ignition/math/Quaternion.hh | 1 + include/ignition/math/Rand.hh | 1 + include/ignition/math/Region3.hh | 1 + include/ignition/math/RollingMean.hh | 1 + include/ignition/math/RotationSpline.hh | 1 + include/ignition/math/SemanticVersion.hh | 1 + include/ignition/math/SignalStats.hh | 1 + include/ignition/math/SpeedLimiter.hh | 1 + include/ignition/math/Sphere.hh | 1 + include/ignition/math/SphericalCoordinates.hh | 1 + include/ignition/math/Spline.hh | 1 + include/ignition/math/Stopwatch.hh | 1 + include/ignition/math/Temperature.hh | 1 + include/ignition/math/Triangle.hh | 1 + include/ignition/math/Triangle3.hh | 1 + include/ignition/math/Vector2.hh | 1 + include/ignition/math/Vector3.hh | 1 + include/ignition/math/Vector3Stats.hh | 1 + include/ignition/math/Vector4.hh | 1 + .../math/VolumetricGridLookupField.hh | 1 + include/ignition/math/config.hh | 28 ++ include/ignition/math/detail/AxisIndex.hh | 1 + include/ignition/math/detail/Box.hh | 1 + include/ignition/math/detail/Capsule.hh | 1 + include/ignition/math/detail/Cylinder.hh | 1 + include/ignition/math/detail/Ellipsoid.hh | 1 + include/ignition/math/detail/Export.hh | 1 + .../math/detail/InterpolationPoint.hh | 1 + include/ignition/math/detail/Sphere.hh | 1 + .../ignition/math/detail/WellOrderedVector.hh | 1 + include/ignition/math/graph/Edge.hh | 1 + include/ignition/math/graph/Graph.hh | 1 + .../ignition/math/graph/GraphAlgorithms.hh | 1 + include/ignition/math/graph/Vertex.hh | 1 + src/AdditivelySeparableScalarField3_TEST.cc | 2 +- src/Angle.cc | 2 +- src/Angle_TEST.cc | 2 +- src/AxisAlignedBox.cc | 6 +- src/AxisAlignedBox_TEST.cc | 2 +- src/Box_TEST.cc | 2 +- src/Capsule_TEST.cc | 2 +- src/Color.cc | 2 +- src/Color_TEST.cc | 2 +- src/Cylinder_TEST.cc | 2 +- src/DiffDriveOdometry.cc | 6 +- src/DiffDriveOdometry_TEST.cc | 2 +- src/Ellipsoid_TEST.cc | 2 +- src/Filter_TEST.cc | 2 +- src/Frustum.cc | 4 +- src/Frustum_TEST.cc | 2 +- src/GaussMarkovProcess.cc | 6 +- src/GaussMarkovProcess_TEST.cc | 2 +- src/Helpers.cc | 4 +- src/Helpers.i | 2 +- src/Helpers_TEST.cc | 2 +- src/Helpers_TEST.rb | 10 +- src/Inertial_TEST.cc | 12 +- src/InterpolationPoint_TEST.cc | 2 +- src/Interval_TEST.cc | 2 +- src/Kmeans.cc | 4 +- src/KmeansPrivate.hh | 8 +- src/Kmeans_TEST.cc | 2 +- src/Line2_TEST.cc | 2 +- src/Line3_TEST.cc | 2 +- src/MassMatrix3_TEST.cc | 2 +- src/Material.cc | 6 +- src/MaterialType.hh | 6 +- src/Material_TEST.cc | 2 +- src/Matrix3.i | 22 +- src/Matrix3_TEST.cc | 2 +- src/Matrix3_TEST.rb | 22 +- src/Matrix4_TEST.cc | 2 +- src/MovingWindowFilter_TEST.cc | 10 +- src/OrientedBox_TEST.cc | 2 +- src/PID.cc | 6 +- src/PID_TEST.cc | 2 +- src/PiecewiseScalarField3_TEST.cc | 2 +- src/Plane_TEST.cc | 2 +- src/Polynomial3_TEST.cc | 2 +- src/Pose3.i | 40 +- src/Pose3_TEST.rb | 34 +- src/Pose_TEST.cc | 2 +- src/Quaternion.i | 44 +- src/Quaternion_TEST.cc | 2 +- src/Quaternion_TEST.rb | 38 +- src/Rand.cc | 2 +- src/Rand_TEST.cc | 2 +- src/Region3_TEST.cc | 2 +- src/RollingMean.cc | 6 +- src/RollingMean_TEST.cc | 2 +- src/RotationSpline.cc | 4 +- src/RotationSpline_TEST.cc | 2 +- src/SemanticVersion.cc | 8 +- src/SemanticVersion_TEST.cc | 2 +- src/SignalStats.cc | 2 +- src/SignalStatsPrivate.hh | 8 +- src/SignalStats_TEST.cc | 2 +- src/SpeedLimiter.cc | 10 +- src/SpeedLimiter_TEST.cc | 2 +- src/Sphere_TEST.cc | 2 +- src/SphericalCoordinates.cc | 90 ++-- src/SphericalCoordinates_TEST.cc | 74 +-- src/Spline.cc | 4 +- src/SplinePrivate.cc | 4 +- src/SplinePrivate.hh | 10 +- src/Spline_TEST.cc | 2 +- src/Stopwatch.cc | 6 +- src/Stopwatch_TEST.cc | 16 +- src/Temperature.cc | 10 +- src/Temperature.i | 2 +- src/Temperature_TEST.cc | 2 +- src/Temperature_TEST.rb | 6 +- src/Triangle3_TEST.cc | 2 +- src/Triangle_TEST.cc | 2 +- src/Vector2_TEST.cc | 2 +- src/Vector3Stats.cc | 4 +- src/Vector3Stats_TEST.cc | 2 +- src/Vector3_TEST.cc | 2 +- src/Vector4_TEST.cc | 2 +- src/VolumetricGridLookupField_TEST.cc | 2 +- src/graph/Edge_TEST.cc | 2 +- src/graph/GraphAlgorithms_TEST.cc | 2 +- src/graph/GraphDirected_TEST.cc | 2 +- src/graph/GraphUndirected_TEST.cc | 2 +- src/graph/Graph_TEST.cc | 2 +- src/graph/Vertex_TEST.cc | 2 +- src/python_pybind11/src/Angle.cc | 6 +- src/python_pybind11/src/Angle.hh | 12 +- src/python_pybind11/src/AxisAlignedBox.cc | 14 +- src/python_pybind11/src/AxisAlignedBox.hh | 12 +- src/python_pybind11/src/Box.hh | 30 +- src/python_pybind11/src/Capsule.cc | 4 +- src/python_pybind11/src/Capsule.hh | 18 +- src/python_pybind11/src/Color.cc | 6 +- src/python_pybind11/src/Color.hh | 12 +- src/python_pybind11/src/Cylinder.hh | 26 +- src/python_pybind11/src/DiffDriveOdometry.cc | 8 +- src/python_pybind11/src/DiffDriveOdometry.hh | 14 +- src/python_pybind11/src/Ellipsoid.cc | 4 +- src/python_pybind11/src/Ellipsoid.hh | 22 +- src/python_pybind11/src/Filter.cc | 10 +- src/python_pybind11/src/Filter.hh | 34 +- src/python_pybind11/src/Frustum.cc | 32 +- src/python_pybind11/src/Frustum.hh | 12 +- src/python_pybind11/src/GaussMarkovProcess.cc | 6 +- src/python_pybind11/src/GaussMarkovProcess.hh | 12 +- src/python_pybind11/src/Helpers.cc | 54 +-- src/python_pybind11/src/Helpers.hh | 14 +- src/python_pybind11/src/Inertial.hh | 22 +- src/python_pybind11/src/Kmeans.cc | 12 +- src/python_pybind11/src/Kmeans.hh | 12 +- src/python_pybind11/src/Line2.cc | 4 +- src/python_pybind11/src/Line2.hh | 34 +- src/python_pybind11/src/Line3.cc | 4 +- src/python_pybind11/src/Line3.hh | 32 +- src/python_pybind11/src/MassMatrix3.cc | 6 +- src/python_pybind11/src/MassMatrix3.hh | 66 +-- src/python_pybind11/src/Material.cc | 40 +- src/python_pybind11/src/Material.hh | 12 +- src/python_pybind11/src/Matrix3.cc | 6 +- src/python_pybind11/src/Matrix3.hh | 20 +- src/python_pybind11/src/Matrix4.cc | 6 +- src/python_pybind11/src/Matrix4.hh | 38 +- src/python_pybind11/src/MovingWindowFilter.cc | 8 +- src/python_pybind11/src/MovingWindowFilter.hh | 16 +- src/python_pybind11/src/OrientedBox.hh | 34 +- src/python_pybind11/src/PID.cc | 6 +- src/python_pybind11/src/PID.hh | 12 +- src/python_pybind11/src/Plane.hh | 52 +- src/python_pybind11/src/Pose3.cc | 6 +- src/python_pybind11/src/Pose3.hh | 32 +- src/python_pybind11/src/Quaternion.cc | 6 +- src/python_pybind11/src/Quaternion.hh | 32 +- src/python_pybind11/src/Rand.cc | 20 +- src/python_pybind11/src/Rand.hh | 14 +- src/python_pybind11/src/RollingMean.cc | 6 +- src/python_pybind11/src/RollingMean.hh | 12 +- src/python_pybind11/src/RotationSpline.cc | 6 +- src/python_pybind11/src/RotationSpline.hh | 12 +- src/python_pybind11/src/SemanticVersion.cc | 6 +- src/python_pybind11/src/SemanticVersion.hh | 12 +- src/python_pybind11/src/SignalStats.cc | 80 ++-- src/python_pybind11/src/SignalStats.hh | 26 +- src/python_pybind11/src/Sphere.hh | 16 +- .../src/SphericalCoordinates.cc | 12 +- .../src/SphericalCoordinates.hh | 12 +- src/python_pybind11/src/Spline.cc | 6 +- src/python_pybind11/src/Spline.hh | 12 +- src/python_pybind11/src/StopWatch.cc | 6 +- src/python_pybind11/src/StopWatch.hh | 12 +- src/python_pybind11/src/Temperature.cc | 6 +- src/python_pybind11/src/Temperature.hh | 12 +- src/python_pybind11/src/Triangle.cc | 6 +- src/python_pybind11/src/Triangle.hh | 18 +- src/python_pybind11/src/Triangle3.cc | 6 +- src/python_pybind11/src/Triangle3.hh | 18 +- src/python_pybind11/src/Vector2.cc | 6 +- src/python_pybind11/src/Vector2.hh | 18 +- src/python_pybind11/src/Vector3.cc | 6 +- src/python_pybind11/src/Vector3.hh | 18 +- src/python_pybind11/src/Vector3Stats.cc | 6 +- src/python_pybind11/src/Vector3Stats.hh | 12 +- src/python_pybind11/src/Vector4.cc | 6 +- src/python_pybind11/src/Vector4.hh | 18 +- .../src/_ignition_math_pybind11.cc | 112 ++--- src/python_pybind11/test/Vector3_TEST.py | 2 +- src/ruby/Angle.i | 2 +- src/ruby/Angle_TEST.rb | 70 +-- src/ruby/AxisAlignedBox.i | 10 +- src/ruby/Box.i | 50 +- src/ruby/CMakeLists.txt | 2 +- src/ruby/Color.i | 2 +- src/ruby/Cylinder.i | 22 +- src/ruby/DiffDriveOdometry.i | 2 +- src/ruby/Filter.i | 2 +- src/ruby/Frustum.i | 20 +- src/ruby/GaussMarkovProcess.i | 2 +- src/ruby/GaussMarkovProcess_TEST.rb | 8 +- src/ruby/Helpers.i | 4 +- src/ruby/Inertial.i | 2 +- src/ruby/Kmeans.i | 6 +- src/ruby/Line2.i | 4 +- src/ruby/Line3.i | 4 +- src/ruby/MassMatrix3.i | 2 +- src/ruby/Material.i | 4 +- src/ruby/MaterialType.i | 2 +- src/ruby/Matrix3.i | 6 +- src/ruby/Matrix4.i | 2 +- src/ruby/MovingWindowFilter.i | 2 +- src/ruby/OrientedBox.i | 36 +- src/ruby/PID.i | 2 +- src/ruby/Plane.i | 6 +- src/ruby/Pose3.i | 2 +- src/ruby/Quaternion.i | 6 +- src/ruby/Rand.i | 2 +- src/ruby/Rand_TEST.rb | 8 +- src/ruby/RollingMean.i | 2 +- src/ruby/RotationSpline.i | 2 +- src/ruby/SemanticVersion.i | 2 +- src/ruby/SignalStats.i | 2 +- src/ruby/Sphere.i | 20 +- src/ruby/SphericalCoordinates.i | 52 +- src/ruby/Spline.i | 2 +- src/ruby/StopWatch.i | 2 +- src/ruby/Temperature.i | 2 +- src/ruby/Triangle.i | 4 +- src/ruby/Triangle3.i | 22 +- src/ruby/Vector2.i | 8 +- src/ruby/Vector2_TEST.rb | 156 +++--- src/ruby/Vector3.i | 14 +- src/ruby/Vector3Stats.i | 2 +- src/ruby/Vector3_TEST.rb | 248 +++++----- src/ruby/Vector4.i | 8 +- src/ruby/Vector4_TEST.rb | 150 +++--- src/ruby/ruby.i | 2 +- src/ruby/ruby_TEST.rb | 8 +- test/integration/ExamplesBuild_TEST.cc | 10 +- .../all_symbols_have_version.bash.in | 4 +- test/integration/deprecated_TEST.cc | 32 ++ tutorials/angle.md | 14 +- tutorials/color.md | 6 +- tutorials/cppgetstarted.md | 18 +- tutorials/example_angle.md | 14 +- tutorials/example_triangle.md | 6 +- tutorials/example_vector2.md | 14 +- tutorials/installation.md | 32 +- tutorials/pythongetstarted.md | 8 +- tutorials/rotation.md | 2 +- tutorials/rotation_example.md | 2 +- tutorials/triangle.md | 6 +- tutorials/vector.md | 14 +- 409 files changed, 2557 insertions(+), 2409 deletions(-) create mode 100644 test/integration/deprecated_TEST.cc diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index 147239ce5..a1c121ea4 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -1 +1 @@ -See the [Ignition Robotics contributing guide](https://ignitionrobotics.org/docs/all/contributing). +See the [Gazebo contributing guide](https://gazebosim.org/docs/all/contributing). diff --git a/Changelog.md b/Changelog.md index 44b3ea94e..4c9218aa2 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,8 +1,8 @@ -## Ignition Math 7.x +## Gazebo Math 7.x -### Ignition Math 7.x.x +### Gazebo Math 7.x.x -### Ignition Math 7.0.0 +### Gazebo Math 7.0.0 1. Deprecated `Angle::Degree(double)` and `Angle::Radian(double)`. Use `Angle::SetDegree(double)` and `Angle::SetRadian(double)` instead. * [BitBucket pull request 326](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/326) @@ -10,7 +10,7 @@ 1. Added Equal functions with a tolerance parameter to Pose3 and Quaternion. * [BitBucket pull request 319](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/319) -1. Updates per issue [#101](https://github.com/ignitionrobotics/ign-math/issues/101). +1. Updates per issue [#101](https://github.com/gazebosim/gz-math/issues/101). * Matrix3: [BitBucket pull request 328](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/328) * Pose: [BitBucket pull request 329](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/329) * Quaternion: [BitBucket pull request 327](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/327) @@ -22,435 +22,435 @@ * [BitBucket pull request 339](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/339) 1. Prevent -0 with out stream operator - * [Pull request 206](https://github.com/ignitionrobotics/ign-math/pull/206) + * [Pull request 206](https://github.com/gazebosim/gz-math/pull/206) 1. Use and narrower includes, not - * [Pull request 287](https://github.com/ignitionrobotics/ign-math/pull/287) + * [Pull request 287](https://github.com/gazebosim/gz-math/pull/287) 1. Evict large function definitions from the Helpers.hh header file. - * [Pull request 288](https://github.com/ignitionrobotics/ign-math/pull/288) + * [Pull request 288](https://github.com/gazebosim/gz-math/pull/288) 1. Defer regex construction to avoid static initialization. - * [Pull request 289](https://github.com/ignitionrobotics/ign-math/pull/289) + * [Pull request 289](https://github.com/gazebosim/gz-math/pull/289) 1. Defer Material::Predefined construction to avoid static initialization. - * [Pull request 290](https://github.com/ignitionrobotics/ign-math/pull/290) + * [Pull request 290](https://github.com/gazebosim/gz-math/pull/290) 1. Resolve cppcheck errors by adding explicit constructors and consts. - * [Pull request 291](https://github.com/ignitionrobotics/ign-math/pull/291) + * [Pull request 291](https://github.com/gazebosim/gz-math/pull/291) 1. Remove virtual from destructors of copyable classes. - * [Pull request 293](https://github.com/ignitionrobotics/ign-math/pull/293) + * [Pull request 293](https://github.com/gazebosim/gz-math/pull/293) 1. Use constexpr for simple static constants. - * [Pull request 283](https://github.com/ignitionrobotics/ign-math/pull/283) + * [Pull request 283](https://github.com/gazebosim/gz-math/pull/283) 1. Deprecated `appendToStream(std::ostream, T, int)`. Use `appendToStream(std::ostream, T)` instead. - * [Pull request 376](https://github.com/ignitionrobotics/ign-math/pull/376) + * [Pull request 376](https://github.com/gazebosim/gz-math/pull/376) -## Ignition Math 6.x +## Gazebo Math 6.x -### Ignition Math 6.x.x +### Gazebo Math 6.x.x -## Ignition Math 6.10.0 (2022-01-26) +## Gazebo Math 6.10.0 (2022-01-26) 1. Use const instead of constexpr in Ellipsoid constructor - * [Pull request #366](https://github.com/ignitionrobotics/ign-math/pull/366) + * [Pull request #366](https://github.com/gazebosim/gz-math/pull/366) 1. Refactor finding pybind11 - * [Pull request #360](https://github.com/ignitionrobotics/ign-math/pull/360) + * [Pull request #360](https://github.com/gazebosim/gz-math/pull/360) 1. Fix Focal on Jenkins - * [Pull request #364](https://github.com/ignitionrobotics/ign-math/pull/364) + * [Pull request #364](https://github.com/gazebosim/gz-math/pull/364) 1. kmeans example in C++ and Python - * [Pull request #356](https://github.com/ignitionrobotics/ign-math/pull/356) + * [Pull request #356](https://github.com/gazebosim/gz-math/pull/356) 1. Small fixed in doxygen - * [Pull request #355](https://github.com/ignitionrobotics/ign-math/pull/355) + * [Pull request #355](https://github.com/gazebosim/gz-math/pull/355) 1. Added Python Getting started tutorial - * [Pull request #362](https://github.com/ignitionrobotics/ign-math/pull/362) + * [Pull request #362](https://github.com/gazebosim/gz-math/pull/362) 1. Move SWIG interfaces from Python to Ruby - * [Pull request #354](https://github.com/ignitionrobotics/ign-math/pull/354) + * [Pull request #354](https://github.com/gazebosim/gz-math/pull/354) 1. Added pybind11 interfaces for various classes 1. SphericalCoordinates - * [Pull request #357](https://github.com/ignitionrobotics/ign-math/pull/357) + * [Pull request #357](https://github.com/gazebosim/gz-math/pull/357) 1. Vector3Stats - * [Pull request #351](https://github.com/ignitionrobotics/ign-math/pull/351) + * [Pull request #351](https://github.com/gazebosim/gz-math/pull/351) 1. SignalStats - * [Pull request #343](https://github.com/ignitionrobotics/ign-math/pull/343) + * [Pull request #343](https://github.com/gazebosim/gz-math/pull/343) 1. Sphere - * [Pull request #352](https://github.com/ignitionrobotics/ign-math/pull/352) + * [Pull request #352](https://github.com/gazebosim/gz-math/pull/352) 1. Frustum - * [Pull request #353](https://github.com/ignitionrobotics/ign-math/pull/353) + * [Pull request #353](https://github.com/gazebosim/gz-math/pull/353) 1. Plane - * [Pull request #346](https://github.com/ignitionrobotics/ign-math/pull/346) + * [Pull request #346](https://github.com/gazebosim/gz-math/pull/346) 1. Cylinder - * [Pull request #348](https://github.com/ignitionrobotics/ign-math/pull/348) + * [Pull request #348](https://github.com/gazebosim/gz-math/pull/348) 1. OrientedBox - * [Pull request #276](https://github.com/ignitionrobotics/ign-math/pull/276) - * [Pull request #350](https://github.com/ignitionrobotics/ign-math/pull/350) + * [Pull request #276](https://github.com/gazebosim/gz-math/pull/276) + * [Pull request #350](https://github.com/gazebosim/gz-math/pull/350) 1. Inertial - * [Pull request #349](https://github.com/ignitionrobotics/ign-math/pull/349) + * [Pull request #349](https://github.com/gazebosim/gz-math/pull/349) 1. Matrix4 - * [Pull request #337](https://github.com/ignitionrobotics/ign-math/pull/337) + * [Pull request #337](https://github.com/gazebosim/gz-math/pull/337) 1. PID - * [Pull request #323](https://github.com/ignitionrobotics/ign-math/pull/323) - * [Pull request #361](https://github.com/ignitionrobotics/ign-math/pull/361) + * [Pull request #323](https://github.com/gazebosim/gz-math/pull/323) + * [Pull request #361](https://github.com/gazebosim/gz-math/pull/361) 1. Temperature - * [Pull request #330](https://github.com/ignitionrobotics/ign-math/pull/330) + * [Pull request #330](https://github.com/gazebosim/gz-math/pull/330) 1. DiffDriveOdometry (with examples) - * [Pull request #314](https://github.com/ignitionrobotics/ign-math/pull/314) + * [Pull request #314](https://github.com/gazebosim/gz-math/pull/314) 1. MassMatrix3 - * [Pull request #345](https://github.com/ignitionrobotics/ign-math/pull/345) + * [Pull request #345](https://github.com/gazebosim/gz-math/pull/345) 1. AxisAlignedBox - * [Pull request #338](https://github.com/ignitionrobotics/ign-math/pull/338) - * [Pull request #281](https://github.com/ignitionrobotics/ign-math/pull/281) + * [Pull request #338](https://github.com/gazebosim/gz-math/pull/338) + * [Pull request #281](https://github.com/gazebosim/gz-math/pull/281) 1. GaussMarkovProcess (with examples) - * [Pull request #315](https://github.com/ignitionrobotics/ign-math/pull/315) + * [Pull request #315](https://github.com/gazebosim/gz-math/pull/315) 1. RotationSpline - * [Pull request #339](https://github.com/ignitionrobotics/ign-math/pull/339) + * [Pull request #339](https://github.com/gazebosim/gz-math/pull/339) 1. Material - * [Pull request #340](https://github.com/ignitionrobotics/ign-math/pull/340) + * [Pull request #340](https://github.com/gazebosim/gz-math/pull/340) 1. Kmeans - * [Pull request #341](https://github.com/ignitionrobotics/ign-math/pull/341) + * [Pull request #341](https://github.com/gazebosim/gz-math/pull/341) 1. Triangle3 - * [Pull request #335](https://github.com/ignitionrobotics/ign-math/pull/335) + * [Pull request #335](https://github.com/gazebosim/gz-math/pull/335) 1. Pose3 - * [Pull request #334](https://github.com/ignitionrobotics/ign-math/pull/334) + * [Pull request #334](https://github.com/gazebosim/gz-math/pull/334) 1. Triangle - * [Pull request #333](https://github.com/ignitionrobotics/ign-math/pull/333) + * [Pull request #333](https://github.com/gazebosim/gz-math/pull/333) 1. Spline - * [Pull request #332](https://github.com/ignitionrobotics/ign-math/pull/332) + * [Pull request #332](https://github.com/gazebosim/gz-math/pull/332) 1. Filter - * [Pull request #336](https://github.com/ignitionrobotics/ign-math/pull/336) + * [Pull request #336](https://github.com/gazebosim/gz-math/pull/336) 1. SemanticVersion - * [Pull request #331](https://github.com/ignitionrobotics/ign-math/pull/331) + * [Pull request #331](https://github.com/gazebosim/gz-math/pull/331) 1. Matrix3 - * [Pull request #325](https://github.com/ignitionrobotics/ign-math/pull/325) + * [Pull request #325](https://github.com/gazebosim/gz-math/pull/325) 1. MovingWindowFilter - * [Pull request #321](https://github.com/ignitionrobotics/ign-math/pull/321) + * [Pull request #321](https://github.com/gazebosim/gz-math/pull/321) 1. Line3 - * [Pull request #317](https://github.com/ignitionrobotics/ign-math/pull/317) + * [Pull request #317](https://github.com/gazebosim/gz-math/pull/317) 1. Quaternion - * [Pull request #324](https://github.com/ignitionrobotics/ign-math/pull/324) - * [Pull request #361](https://github.com/ignitionrobotics/ign-math/pull/361) + * [Pull request #324](https://github.com/gazebosim/gz-math/pull/324) + * [Pull request #361](https://github.com/gazebosim/gz-math/pull/361) 1. StopWatch - * [Pull request #319](https://github.com/ignitionrobotics/ign-math/pull/319) + * [Pull request #319](https://github.com/gazebosim/gz-math/pull/319) 1. RollingMean - * [Pull request #322](https://github.com/ignitionrobotics/ign-math/pull/322) + * [Pull request #322](https://github.com/gazebosim/gz-math/pull/322) 1. Line2 - * [Pull request #316](https://github.com/ignitionrobotics/ign-math/pull/316) + * [Pull request #316](https://github.com/gazebosim/gz-math/pull/316) 1. Color - * [Pull request #318](https://github.com/ignitionrobotics/ign-math/pull/318) + * [Pull request #318](https://github.com/gazebosim/gz-math/pull/318) 1. Helpers - * [Pull request #313](https://github.com/ignitionrobotics/ign-math/pull/313) + * [Pull request #313](https://github.com/gazebosim/gz-math/pull/313) 1. Rand (with examples) - * [Pull request #312](https://github.com/ignitionrobotics/ign-math/pull/312) + * [Pull request #312](https://github.com/gazebosim/gz-math/pull/312) 1. Angle - * [Pull request #311](https://github.com/ignitionrobotics/ign-math/pull/311) + * [Pull request #311](https://github.com/gazebosim/gz-math/pull/311) 1. Vector2, Vector3 and Vector4 - * [Pull request #280](https://github.com/ignitionrobotics/ign-math/pull/280) + * [Pull request #280](https://github.com/gazebosim/gz-math/pull/280) 1. Fix Color::HSV() incorrect hue output - * [Pull request #320](https://github.com/ignitionrobotics/ign-math/pull/320) + * [Pull request #320](https://github.com/gazebosim/gz-math/pull/320) 1. Add example and modify document for class Color - * [Pull request #304](https://github.com/ignitionrobotics/ign-math/pull/304) + * [Pull request #304](https://github.com/gazebosim/gz-math/pull/304) 1. Document that euler angles should be in radians for quaternion constructor - * [Pull request #298](https://github.com/ignitionrobotics/ign-math/pull/298) + * [Pull request #298](https://github.com/gazebosim/gz-math/pull/298) 1. Fix windows warnings in Vector2, 3 and 4 - * [Pull request #284](https://github.com/ignitionrobotics/ign-math/pull/284) + * [Pull request #284](https://github.com/gazebosim/gz-math/pull/284) 1. Modified cmake target name for Ruby interfaces - * [Pull request #285](https://github.com/ignitionrobotics/ign-math/pull/285) + * [Pull request #285](https://github.com/gazebosim/gz-math/pull/285) 1. Frustrum Python interface - * [Pull request #278](https://github.com/ignitionrobotics/ign-math/pull/278) + * [Pull request #278](https://github.com/gazebosim/gz-math/pull/278) 1. quaternion_from_euler example: input degrees - * [Pull request #282](https://github.com/ignitionrobotics/ign-math/pull/282) + * [Pull request #282](https://github.com/gazebosim/gz-math/pull/282) 1. Internal URL fixed (paragraph 266) - * [Pull request #279](https://github.com/ignitionrobotics/ign-math/pull/279) + * [Pull request #279](https://github.com/gazebosim/gz-math/pull/279) 1. Added tutorials for vector, angle, triangle and rotation - * [Pull request #249](https://github.com/ignitionrobotics/ign-math/pull/249) + * [Pull request #249](https://github.com/gazebosim/gz-math/pull/249) 1. Inertial Python interface - * [Pull request #275](https://github.com/ignitionrobotics/ign-math/pull/275) + * [Pull request #275](https://github.com/gazebosim/gz-math/pull/275) 1. Box Python interfaces - * [Pull request #273](https://github.com/ignitionrobotics/ign-math/pull/273) + * [Pull request #273](https://github.com/gazebosim/gz-math/pull/273) 1. DiffDriveOdometry Python interface - * [Pull request #265](https://github.com/ignitionrobotics/ign-math/pull/265) + * [Pull request #265](https://github.com/gazebosim/gz-math/pull/265) 1. Sphere Python interface - * [Pull request #277](https://github.com/ignitionrobotics/ign-math/pull/277) + * [Pull request #277](https://github.com/gazebosim/gz-math/pull/277) 1. Plane Python interfaces - * [Pull request #272](https://github.com/ignitionrobotics/ign-math/pull/272) + * [Pull request #272](https://github.com/gazebosim/gz-math/pull/272) 1. Cylinder Python interface - * [Pull request #274](https://github.com/ignitionrobotics/ign-math/pull/274) + * [Pull request #274](https://github.com/gazebosim/gz-math/pull/274) 1. Added SphericalCoordinates Python interface - * [Pull request #263](https://github.com/ignitionrobotics/ign-math/pull/263) + * [Pull request #263](https://github.com/gazebosim/gz-math/pull/263) 1. MassMatrix3 Python interface - * [Pull request #260](https://github.com/ignitionrobotics/ign-math/pull/260) + * [Pull request #260](https://github.com/gazebosim/gz-math/pull/260) 1. AxisAlignedBox Python interface - * [Pull request #262](https://github.com/ignitionrobotics/ign-math/pull/262) + * [Pull request #262](https://github.com/gazebosim/gz-math/pull/262) 1. AxisAlignedBox: deprecate unimplemented methods - * [Pull request #261](https://github.com/ignitionrobotics/ign-math/pull/261) + * [Pull request #261](https://github.com/gazebosim/gz-math/pull/261) -## Ignition Math 6.9.2 (2021-10-14) +## Gazebo Math 6.9.2 (2021-10-14) 1. Added StopWatch Python Interface - * [Pull request #264](https://github.com/ignitionrobotics/ign-math/pull/264) + * [Pull request #264](https://github.com/gazebosim/gz-math/pull/264) 1. Fix clang warnings. - * [Pull request #267](https://github.com/ignitionrobotics/ign-math/pull/267) + * [Pull request #267](https://github.com/gazebosim/gz-math/pull/267) 1. Fixed Helpers Python templates - * [Pull request #266](https://github.com/ignitionrobotics/ign-math/pull/266) + * [Pull request #266](https://github.com/gazebosim/gz-math/pull/266) 1. Add Helpers Python interface - * [Pull request #251](https://github.com/ignitionrobotics/ign-math/pull/251) + * [Pull request #251](https://github.com/gazebosim/gz-math/pull/251) 1. Add Python interface to Triangle3 - * [Pull request #247](https://github.com/ignitionrobotics/ign-math/pull/247) + * [Pull request #247](https://github.com/gazebosim/gz-math/pull/247) 1. Adds python interface to MaterialType and Material. - * [Pull request #234](https://github.com/ignitionrobotics/ign-math/pull/234) + * [Pull request #234](https://github.com/gazebosim/gz-math/pull/234) 1. Remove Cylinder::SetLength const method - * [Pull request #259](https://github.com/ignitionrobotics/ign-math/pull/259) + * [Pull request #259](https://github.com/gazebosim/gz-math/pull/259) -## Ignition Math 6.9.1 (2021-09-30) +## Gazebo Math 6.9.1 (2021-09-30) 1. Avoid assertAlmostEqual for python strings - * [Pull request #255](https://github.com/ignitionrobotics/ign-math/pull/255) + * [Pull request #255](https://github.com/gazebosim/gz-math/pull/255) 1. Pose3_TEST.py: use 0.01 (not 0) in string test - * [Pull request #257](https://github.com/ignitionrobotics/ign-math/pull/257) + * [Pull request #257](https://github.com/gazebosim/gz-math/pull/257) -## Ignition Math 6.9.0 (2021-09-28) +## Gazebo Math 6.9.0 (2021-09-28) 1. Volume below a plane for spheres and boxes - * [Pull request #219](https://github.com/ignitionrobotics/ign-math/pull/219) + * [Pull request #219](https://github.com/gazebosim/gz-math/pull/219) 1. 🌐 Spherical coordinates: bug fix, docs and sanity checks - * [Pull request #235](https://github.com/ignitionrobotics/ign-math/pull/235) + * [Pull request #235](https://github.com/gazebosim/gz-math/pull/235) 1. Add Vector(2|3|4)::NaN to easily create invalid vectors - * [Pull request #222](https://github.com/ignitionrobotics/ign-math/pull/222) + * [Pull request #222](https://github.com/gazebosim/gz-math/pull/222) 1. Add options to install python/ruby in system standard paths - * [Pull request #236](https://github.com/ignitionrobotics/ign-math/pull/236) + * [Pull request #236](https://github.com/gazebosim/gz-math/pull/236) 1. Add eigen utils to convert mesh 3d vertices to oriented box - * [Pull request #224](https://github.com/ignitionrobotics/ign-math/pull/224) + * [Pull request #224](https://github.com/gazebosim/gz-math/pull/224) 1. Python interface 1. Adds python interface to RollingMean, Color and Spline - * [Pull request #218](https://github.com/ignitionrobotics/ign-math/pull/218) + * [Pull request #218](https://github.com/gazebosim/gz-math/pull/218) 1. Adds python interface for Kmeans and Vector3Stats - * [Pull request #232](https://github.com/ignitionrobotics/ign-math/pull/232) + * [Pull request #232](https://github.com/gazebosim/gz-math/pull/232) 1. Adds python interface to PID and SemanticVersion. - * [Pull request #229](https://github.com/ignitionrobotics/ign-math/pull/229) + * [Pull request #229](https://github.com/gazebosim/gz-math/pull/229) 1. Adds python interface to triangle. - * [Pull request #231](https://github.com/ignitionrobotics/ign-math/pull/231) + * [Pull request #231](https://github.com/gazebosim/gz-math/pull/231) 1. Adds Line2, Line3, SignalStats, Temperature python interface - * [Pull request #220](https://github.com/ignitionrobotics/ign-math/pull/220) + * [Pull request #220](https://github.com/gazebosim/gz-math/pull/220) 1. Python interface: Renames methods to match PEP8 style - * [Pull request #226](https://github.com/ignitionrobotics/ign-math/pull/226) + * [Pull request #226](https://github.com/gazebosim/gz-math/pull/226) 1. Adds python interface to Filter, MovingWindowFilter, RotationSpline. - * [Pull request #230](https://github.com/ignitionrobotics/ign-math/pull/230) + * [Pull request #230](https://github.com/gazebosim/gz-math/pull/230) 1. Adds python interface to Quaternion, Pose3, Matrix3 and Matrix4 - * [Pull request #221](https://github.com/ignitionrobotics/ign-math/pull/221) + * [Pull request #221](https://github.com/gazebosim/gz-math/pull/221) 1. Basic setup for Python interface using SWIG - * [Pull request #216](https://github.com/ignitionrobotics/ign-math/pull/216) - * [Pull request #223](https://github.com/ignitionrobotics/ign-math/pull/223) - * [Pull request #208](https://github.com/ignitionrobotics/ign-math/pull/208) - * [Pull request #239](https://github.com/ignitionrobotics/ign-math/pull/239) + * [Pull request #216](https://github.com/gazebosim/gz-math/pull/216) + * [Pull request #223](https://github.com/gazebosim/gz-math/pull/223) + * [Pull request #208](https://github.com/gazebosim/gz-math/pull/208) + * [Pull request #239](https://github.com/gazebosim/gz-math/pull/239) 1. 👩‍🌾 Don't use std::pow with integers in Vectors and handle sqrt - * [Pull request #207](https://github.com/ignitionrobotics/ign-math/pull/207) + * [Pull request #207](https://github.com/gazebosim/gz-math/pull/207) 1. Relax expectations about zero in SpeedLimiter_TEST to make ARM happy - * [Pull request #204](https://github.com/ignitionrobotics/ign-math/pull/204) + * [Pull request #204](https://github.com/gazebosim/gz-math/pull/204) 1. Infrastructure - * [Pull request #242](https://github.com/ignitionrobotics/ign-math/pull/242) - * [Pull request #217](https://github.com/ignitionrobotics/ign-math/pull/217) - * [Pull request #211](https://github.com/ignitionrobotics/ign-math/pull/211) - * [Pull request #209](https://github.com/ignitionrobotics/ign-math/pull/209) - * [Pull request #227](https://github.com/ignitionrobotics/ign-math/pull/227) - * [Pull request #225](https://github.com/ignitionrobotics/ign-math/pull/225) - * [Pull request #252](https://github.com/ignitionrobotics/ign-math/pull/252) - * [Pull request #253](https://github.com/ignitionrobotics/ign-math/pull/253) + * [Pull request #242](https://github.com/gazebosim/gz-math/pull/242) + * [Pull request #217](https://github.com/gazebosim/gz-math/pull/217) + * [Pull request #211](https://github.com/gazebosim/gz-math/pull/211) + * [Pull request #209](https://github.com/gazebosim/gz-math/pull/209) + * [Pull request #227](https://github.com/gazebosim/gz-math/pull/227) + * [Pull request #225](https://github.com/gazebosim/gz-math/pull/225) + * [Pull request #252](https://github.com/gazebosim/gz-math/pull/252) + * [Pull request #253](https://github.com/gazebosim/gz-math/pull/253) -## Ignition Math 6.8.0 (2021-03-30) +## Gazebo Math 6.8.0 (2021-03-30) 1. Add speed limiter class - * [Pull request #194](https://github.com/ignitionrobotics/ign-math/pull/194) + * [Pull request #194](https://github.com/gazebosim/gz-math/pull/194) 1. Bazel Updates for math6 - * [Pull request #171](https://github.com/ignitionrobotics/ign-math/pull/171) + * [Pull request #171](https://github.com/gazebosim/gz-math/pull/171) 1. Add Equal tolerance method to Quaternion - * [Pull request #196](https://github.com/ignitionrobotics/ign-math/pull/196) + * [Pull request #196](https://github.com/gazebosim/gz-math/pull/196) 1. Fix broken link in MassMatrix3.hh - * [Pull request #197](https://github.com/ignitionrobotics/ign-math/pull/197) + * [Pull request #197](https://github.com/gazebosim/gz-math/pull/197) 1. Add instructions to build and run examples - * [Pull request #192](https://github.com/ignitionrobotics/ign-math/pull/192) + * [Pull request #192](https://github.com/gazebosim/gz-math/pull/192) 1. Infrastructure and documentation - * [Pull request #189](https://github.com/ignitionrobotics/ign-math/pull/189) - * [Pull request #193](https://github.com/ignitionrobotics/ign-math/pull/193) - * [Pull request #195](https://github.com/ignitionrobotics/ign-math/pull/195) - * [Pull request #201](https://github.com/ignitionrobotics/ign-math/pull/201) + * [Pull request #189](https://github.com/gazebosim/gz-math/pull/189) + * [Pull request #193](https://github.com/gazebosim/gz-math/pull/193) + * [Pull request #195](https://github.com/gazebosim/gz-math/pull/195) + * [Pull request #201](https://github.com/gazebosim/gz-math/pull/201) 1. Remove unnecessary copy constructor declaration from Box - * [Pull request 187](https://github.com/ignitionrobotics/ign-math/pull/187) + * [Pull request 187](https://github.com/gazebosim/gz-math/pull/187) 1. Windows installation via conda-forge - * [Pull request 185](https://github.com/ignitionrobotics/ign-math/pull/185) + * [Pull request 185](https://github.com/gazebosim/gz-math/pull/185) 1. Add rule-of-five members for Angle - * [Pull request 186](https://github.com/ignitionrobotics/ign-math/pull/186) + * [Pull request 186](https://github.com/gazebosim/gz-math/pull/186) 1. Ellipsoid: new shape class with inertia calculation method - * [Pull request 182](https://github.com/ignitionrobotics/ign-math/pull/182) + * [Pull request 182](https://github.com/gazebosim/gz-math/pull/182) 1. Avoid moving a return value, it might prevent (N)RVO - * [Pull request 183](https://github.com/ignitionrobotics/ign-math/pull/183) + * [Pull request 183](https://github.com/gazebosim/gz-math/pull/183) 1. Properly handle stream errors when reading math objects - * [Pull request 180](https://github.com/ignitionrobotics/ign-math/pull/180) - * [Pull request 181](https://github.com/ignitionrobotics/ign-math/pull/181) + * [Pull request 180](https://github.com/gazebosim/gz-math/pull/180) + * [Pull request 181](https://github.com/gazebosim/gz-math/pull/181) -## Ignition Math 6.7.0 (2020-11-23) +## Gazebo Math 6.7.0 (2020-11-23) 1. Capsule: new shape class with inertia calculation method - * [Pull request 163](https://github.com/ignitionrobotics/ign-math/pull/163) + * [Pull request 163](https://github.com/gazebosim/gz-math/pull/163) 1. Add missing header to Color.hh - * [Pull request 162](https://github.com/ignitionrobotics/ign-math/pull/162) + * [Pull request 162](https://github.com/gazebosim/gz-math/pull/162) 1. Improve tests of `Vector2`, `Vector3`, `Vector4`, `Quaternion`, and `Pose3` - * [Pull request 172](https://github.com/ignitionrobotics/ign-math/pull/172) - * [Pull request 173](https://github.com/ignitionrobotics/ign-math/pull/173) - * [Pull request 174](https://github.com/ignitionrobotics/ign-math/pull/174) - * [Issue 76](https://github.com/ignitionrobotics/ign-math/issues/76) + * [Pull request 172](https://github.com/gazebosim/gz-math/pull/172) + * [Pull request 173](https://github.com/gazebosim/gz-math/pull/173) + * [Pull request 174](https://github.com/gazebosim/gz-math/pull/174) + * [Issue 76](https://github.com/gazebosim/gz-math/issues/76) 1. Pose3: document `operator*` - * [Pull request 170](https://github.com/ignitionrobotics/ign-math/pull/170) + * [Pull request 170](https://github.com/gazebosim/gz-math/pull/170) 1. Quaternion: add Normalized() method - * [Pull request 169](https://github.com/ignitionrobotics/ign-math/pull/169) + * [Pull request 169](https://github.com/gazebosim/gz-math/pull/169) 1. Vector2: add Round(), Rounded() methods - * [Pull request 166](https://github.com/ignitionrobotics/ign-math/pull/166) - * [Issue 71](https://github.com/ignitionrobotics/ign-math/issues/71) + * [Pull request 166](https://github.com/gazebosim/gz-math/pull/166) + * [Issue 71](https://github.com/gazebosim/gz-math/issues/71) 1. Add test for printing `inf` `Vector3` - * [Pull request 168](https://github.com/ignitionrobotics/ign-math/pull/168) - * [Issue 64](https://github.com/ignitionrobotics/ign-math/issues/64) + * [Pull request 168](https://github.com/gazebosim/gz-math/pull/168) + * [Issue 64](https://github.com/gazebosim/gz-math/issues/64) -## Ignition Math 6.6.0 (2020-09-16) +## Gazebo Math 6.6.0 (2020-09-16) 1. Add chrono duration helper functions - * [Pull request 158](https://github.com/ignitionrobotics/ign-math/pull/158) + * [Pull request 158](https://github.com/gazebosim/gz-math/pull/158) -## Ignition Math 6.5.0 (2020-09-04) +## Gazebo Math 6.5.0 (2020-09-04) 1. Add string to time function - * [Pull request 152](https://github.com/ignitionrobotics/ign-math/pull/152) + * [Pull request 152](https://github.com/gazebosim/gz-math/pull/152) 1. Added functions to convert between time_point and secNsec - * [Pull request 150](https://github.com/ignitionrobotics/ign-math/pull/150) + * [Pull request 150](https://github.com/gazebosim/gz-math/pull/150) 1. Fix IGNITION_MATH_XXX_VERSION - * [Pull request 151](https://github.com/ignitionrobotics/ign-math/pull/151) + * [Pull request 151](https://github.com/gazebosim/gz-math/pull/151) 1. Add Max and Min function to Vector2.hh - * [Pull request 133](https://github.com/ignitionrobotics/ign-math/pull/133) - * [Pull request 148](https://github.com/ignitionrobotics/ign-math/pull/148) - * [Issue 71](https://github.com/ignitionrobotics/ign-math/issues/71) + * [Pull request 133](https://github.com/gazebosim/gz-math/pull/133) + * [Pull request 148](https://github.com/gazebosim/gz-math/pull/148) + * [Issue 71](https://github.com/gazebosim/gz-math/issues/71) 1. Round, Rounded, Correct, Distance(x, y, z, w) and operator< addition to Vector 4 - * [Pull request 146](https://github.com/ignitionrobotics/ign-math/pull/146) - * [Issue 71](https://github.com/ignitionrobotics/ign-math/issues/71) + * [Pull request 146](https://github.com/gazebosim/gz-math/pull/146) + * [Issue 71](https://github.com/gazebosim/gz-math/issues/71) 1. Sum and normalized functions for Vector4 - * [Pull request 140](https://github.com/ignitionrobotics/ign-math/pull/140) - * [Issue 71](https://github.com/ignitionrobotics/ign-math/issues/71) + * [Pull request 140](https://github.com/gazebosim/gz-math/pull/140) + * [Issue 71](https://github.com/gazebosim/gz-math/issues/71) 1. Vector4 Ruby tests - Vector4.i and Vector4_TEST.rb - * [Pull request 137](https://github.com/ignitionrobotics/ign-math/pull/137) - * [Issue 71](https://github.com/ignitionrobotics/ign-math/issues/71) + * [Pull request 137](https://github.com/gazebosim/gz-math/pull/137) + * [Issue 71](https://github.com/gazebosim/gz-math/issues/71) 1. Vector3 to vector4 functions - * [Pull request 132](https://github.com/ignitionrobotics/ign-math/pull/132) - * [Issue 71](https://github.com/ignitionrobotics/ign-math/issues/71) + * [Pull request 132](https://github.com/gazebosim/gz-math/pull/132) + * [Issue 71](https://github.com/gazebosim/gz-math/issues/71) 1. Update vector2 fuctions from vector3 - * [Pull request 130](https://github.com/ignitionrobotics/ign-math/pull/130) - * [Issue 71](https://github.com/ignitionrobotics/ign-math/issues/71) + * [Pull request 130](https://github.com/gazebosim/gz-math/pull/130) + * [Issue 71](https://github.com/gazebosim/gz-math/issues/71) 1. Add Abs, Dot and AbsDot and respective tests to Vector4 - * [Pull request 135](https://github.com/ignitionrobotics/ign-math/pull/135) - * [Issue 71](https://github.com/ignitionrobotics/ign-math/issues/71) + * [Pull request 135](https://github.com/gazebosim/gz-math/pull/135) + * [Issue 71](https://github.com/gazebosim/gz-math/issues/71) 1. Create abs, absDot and Correct functions for Vector2d - * [Pull request 143](https://github.com/ignitionrobotics/ign-math/pull/143) - * [Issue 71](https://github.com/ignitionrobotics/ign-math/issues/71) + * [Pull request 143](https://github.com/gazebosim/gz-math/pull/143) + * [Issue 71](https://github.com/gazebosim/gz-math/issues/71) 1. Document Ruby tests - * [Pull request 145](https://github.com/ignitionrobotics/ign-math/pull/145) + * [Pull request 145](https://github.com/gazebosim/gz-math/pull/145) 1. Add header for numeric_limits allowing build on ubuntu 16.04 - * [Pull request 119](https://github.com/ignitionrobotics/ign-math/pull/119) + * [Pull request 119](https://github.com/gazebosim/gz-math/pull/119) 1. Add setter/getter for Pose's each element - * [Pull request 125](https://github.com/ignitionrobotics/ign-math/pull/125) - * [Issue 35](https://github.com/ignitionrobotics/ign-math/issues/35) + * [Pull request 125](https://github.com/gazebosim/gz-math/pull/125) + * [Issue 35](https://github.com/gazebosim/gz-math/issues/35) 1. Implement AxisAlignedBox Volume function - * [Pull request 126](https://github.com/ignitionrobotics/ign-math/pull/126) + * [Pull request 126](https://github.com/gazebosim/gz-math/pull/126) 1. Add operator + for AxisAlignedBox and Vector3. - * [Pull request 122](https://github.com/ignitionrobotics/ign-math/pull/122) + * [Pull request 122](https://github.com/gazebosim/gz-math/pull/122) 1. Make alpha optional when parsing a Color from an input stream. - * [Pull request 106](https://github.com/ignitionrobotics/ign-math/pull/106) + * [Pull request 106](https://github.com/gazebosim/gz-math/pull/106) 1. GitHub actions CI and workflow updates - * [Pull request 117](https://github.com/ignitionrobotics/ign-math/pull/117) - * [Pull request 139](https://github.com/ignitionrobotics/ign-math/pull/139) - * [Pull request 110](https://github.com/ignitionrobotics/ign-math/pull/110) + * [Pull request 117](https://github.com/gazebosim/gz-math/pull/117) + * [Pull request 139](https://github.com/gazebosim/gz-math/pull/139) + * [Pull request 110](https://github.com/gazebosim/gz-math/pull/110) 1. Added a Gauss-Markov Process class. * [BitBucket pull request 342](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/342) @@ -470,13 +470,13 @@ instead. 1. Doxygen fixes for graph classes * [BitBucket pull request 331](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/331) -### Ignition Math 6.4.0 +### Gazebo Math 6.4.0 1. Added a function that rounds up a number to the nearest multiple of another number. * [BitBucket pull request 318](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/318) -### Ignition Math 6.3.0 +### Gazebo Math 6.3.0 1. Added Odometry class that computes odometry for a two wheeled vehicle. * [BitBucket pull request 313](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/313) @@ -484,21 +484,21 @@ instead. 1. Added RollingMean class. * [BitBucket pull request 314](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/314) -### Ignition Math 6.2.0 +### Gazebo Math 6.2.0 1. eigen3: Use linear() instead of rotation() to prevent computation of SVD * [BitBucket pull request 311](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/311) 1. Change definition of Pose3 `*` operator to fix multiplication order * [BitBucket pull request 301](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/301) - * [Issue 60](https://github.com/ignitionrobotics/ign-math/issues/60) + * [Issue 60](https://github.com/gazebosim/gz-math/issues/60) -### Ignition Math 6.1.0 +### Gazebo Math 6.1.0 1. eigen3: add conversion functions for Eigen::AlignedBox3d <=> ignition::math::AxisAlignedBox * [BitBucket pull request 302](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/302) -### Ignition Math 6.0.0 +### Gazebo Math 6.0.0 1. Helper function that converts from `std::chrono::steady_clock::duration` to {seconds, nanoseconds}. @@ -507,11 +507,11 @@ instead. 1. Upgrade to c++17. * [BitBucket pull request 268](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/268) -## Ignition Math 5.x +## Gazebo Math 5.x -### Ignition Math 5.x.x +### Gazebo Math 5.x.x -### Ignition Math 5.1.0 (2019-09-11) +### Gazebo Math 5.1.0 (2019-09-11) 1. GraphAlgorithms: add ToUndirected(DirectedGraph) that copies to an UndirectedGraph. * [BitBucket pull request 332](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/332) @@ -524,13 +524,13 @@ instead. 1. Change definition of Pose3 `*` operator to fix multiplication order * [BitBucket pull request 301](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/301) - * [Issue 60](https://github.com/ignitionrobotics/ign-math/issues/60) + * [Issue 60](https://github.com/gazebosim/gz-math/issues/60) 1. eigen3: add conversion functions for Eigen::AlignedBox3d <=> ignition::math::AxisAlignedBox * [BitBucket pull request 302](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/302) -### Ignition Math 5.0.0 (2018-12-12) +### Gazebo Math 5.0.0 (2018-12-12) 1. Added a Stopwatch class * [BitBucket pull request 279](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/279) @@ -575,9 +575,9 @@ specify a density. in MassMatrix3::ValidMoments * [BitBucket pull request 278](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/278) -## Ignition Math 4.x +## Gazebo Math 4.x -### Ignition Math 4.x.x +### Gazebo Math 4.x.x 1. Add Graph::EdgeFromVertices function that return an edge, if one exists, between two vertices. @@ -590,19 +590,19 @@ specify a density. 1. Add Plane copy constructor and fix cppcheck on artful * [BitBucket pull request 230](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/230) -1. Added MovingWindowFilter, a copy from Ignition Common. This version will - replace the version found in Ignition Common. +1. Added MovingWindowFilter, a copy from Gazebo Common. This version will + replace the version found in Gazebo Common. * [BitBucket pull request 239](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/239) 1. Added a Material class, which holds information about materials like wood, steel, and iron. * [BitBucket pull request 243](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/243) -### Ignition Math 4.0.0 (2017-12-26) +### Gazebo Math 4.0.0 (2017-12-26) 1. Use std::stoi and std::stod in math::parse* functions to reduce code * [BitBucket pull request 224](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/224) - * [Issue 50](https://github.com/ignitionrobotics/ign-math/issues/50) + * [Issue 50](https://github.com/gazebosim/gz-math/issues/50) 1. Fixing const-correctness for operator* of Pose3 * [BitBucket pull request 205](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/205) @@ -622,8 +622,8 @@ specify a density. 1. Removed the box 'extent' field. The default constructor now sets a box's corners to extrema in order to indicate an uninitialized box. * [BitBucket pull request 172](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/172) - * [Issue 72](https://github.com/ignitionrobotics/ign-math/issues/72) - * [Issue 53](https://github.com/ignitionrobotics/ign-math/issues/53) + * [Issue 72](https://github.com/gazebosim/gz-math/issues/72) + * [Issue 53](https://github.com/gazebosim/gz-math/issues/53) 1. Added graph utilites: 1. Added a Vertex class: @@ -639,22 +639,22 @@ specify a density. * [BitBucket pull request 190](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/190) 1. Improved the performance of `graph::InDegree()` and `graph::IncidentsTo()`. * [BitBucket pull request 188](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/188) - * [Issue 79](https://github.com/ignitionrobotics/ign-math/issues/79) + * [Issue 79](https://github.com/gazebosim/gz-math/issues/79) 1. Added Inline Versioned Namespace * [BitBucket pull request 216](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/216/) -## Ignition Math 3.x +## Gazebo Math 3.x -### Ignition Math 3.x.x +### Gazebo Math 3.x.x -### Ignition Math 3.3.0 (2017-11-27) +### Gazebo Math 3.3.0 (2017-11-27) 1. Fixed frustum falsely saying it contained AABB in some cases * [BitBucket pull request 193](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/193) - * [Issue 78](https://github.com/ignitionrobotics/ign-math/issues/78) + * [Issue 78](https://github.com/gazebosim/gz-math/issues/78) 1. Create consistent bracket operators across all Vector# types * [BitBucket pull request 181](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/181) @@ -674,7 +674,7 @@ specify a density. 1. Update configure.bat * [BitBucket pull request 206](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/206) -### Ignition Math 3.2.0 (2017-05-15) +### Gazebo Math 3.2.0 (2017-05-15) 1. Construct on first use in Rand class * [BitBucket pull request 165](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/165) @@ -683,13 +683,13 @@ specify a density. and tangent forcing. * [BitBucket pull request 162](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/162) -### Ignition Math 3.1.0 (2017-04-11) +### Gazebo Math 3.1.0 (2017-04-11) 1. Added signum functions to Helpers.hh. * Contribution from Martin Pecka * [BitBucket pull request 153](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/153) -### Ignition Math 3.0.0 (2017-01-05) +### Gazebo Math 3.0.0 (2017-01-05) 1. Deprecate many IGN_* macros in favor of static const variables in Helpers.hh * [BitBucket pull request 138](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/138) @@ -716,11 +716,11 @@ specify a density. Contribution from Silvio Traversaro. * [BitBucket pull request 63](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/63) -## Ignition Math 2.x +## Gazebo Math 2.x -## Ignition Math 2.9 (2017-11-22) +## Gazebo Math 2.9 (2017-11-22) 1. Fixed frustum falsely saying it contained AABB in some cases * [BitBucket pull request 193](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/193) @@ -731,9 +731,9 @@ specify a density. 1. Backport updated configure.bat to ign-math2 and fix cppcheck warnings * [BitBucket pull request 207](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/207) -### Ignition Math 2.8 +### Gazebo Math 2.8 -### Ignition Math 2.8.0 +### Gazebo Math 2.8.0 1. Added OrientedBox * [BitBucket pull request 146](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/146) @@ -741,9 +741,9 @@ specify a density. 1. Added an assignment operator to the Frustum class. * [BitBucket pull request 144](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/144) -### Ignition Math 2.7 +### Gazebo Math 2.7 -### Ignition Math 2.7.0 +### Gazebo Math 2.7.0 1. Add static const variables as alternative to macros in Helpers.hh * [BitBucket pull request 137](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/137) @@ -751,9 +751,9 @@ specify a density. 1. Add new methods for floating numbers: lessOrEqual and greaterOrEqual * [BitBucket pull request 134](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/134) -### Ignition Math 2.6 +### Gazebo Math 2.6 -### Ignition Math 2.6.0 +### Gazebo Math 2.6.0 1. Added copy constructor, equality operators and assignment operators to SphericalCoordinates class. @@ -777,9 +777,9 @@ specify a density. 1. Added SemanticVersion class * [BitBucket pull request 120](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/120) -### Ignition Math 2.5 +### Gazebo Math 2.5 -### Ignition Math 2.5.0 +### Gazebo Math 2.5.0 1. Added PID class * [BitBucket pull request 117](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/117) @@ -787,15 +787,15 @@ specify a density. 1. Added SphericalCoordinate class * [BitBucket pull request 108](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/108) -### Ignition Math 2.4 +### Gazebo Math 2.4 -#### Ignition Math 2.4.1 +#### Gazebo Math 2.4.1 1. Combine inertial properties of different objects, returning the equivalent inertial properties as if the objects were welded together. * [BitBucket pull request 115](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/115) -#### Ignition Math 2.4.0 +#### Gazebo Math 2.4.0 1. New MassMatrix3 class * [BitBucket pull request 112](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/112) @@ -805,7 +805,7 @@ specify a density. * A contribution from Shintaro Noda * [BitBucket pull request 113](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/113) -### Ignition Math 2.3.0 +### Gazebo Math 2.3.0 1. Added simple volumes formulas * [BitBucket pull request 84](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/84) diff --git a/Migration.md b/Migration.md index 44e742a80..190d11e62 100644 --- a/Migration.md +++ b/Migration.md @@ -5,7 +5,7 @@ Deprecated code produces compile-time warnings. These warning serve as notification to users that their code should be upgraded. The next major release will remove the deprecated code. -## Ignition Math 6.X to 7.X +## Gazebo Math 6.X to 7.X ### Breaking Changes @@ -61,24 +61,27 @@ release will remove the deprecated code. 1. **Helpers.hh** + **Deprecation:** template inline void appendToStream(std::ostream, T, int) + **Replacement:** template inline void appendToStream(std::ostream, T) +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. ### Modifications 1. The out stream operator is guaranteed to return always plain 0 and not to return -0, 0.0 or other instances of zero value. -## Ignition Math 6.9.2 to 6.10.0 +## Gazebo Math 6.9.2 to 6.10.0 1. **Color::HSV()**: A bug related to the hue output of this function was fixed. -## Ignition Math 6.8 to 6.9 +## Gazebo Math 6.8 to 6.9 1. **SphericalCoordinates**: A bug related to the LOCAL frame was fixed. To preserve behaviour, the `LOCAL` frame was left with the bug, and a new `LOCAL2` frame was introduced, which can be used to get the correct calculations. -## Ignition Math 4.X to 5.X +## Gazebo Math 4.X to 5.X ### Additions @@ -124,7 +127,7 @@ release will remove the deprecated code. 1. **Inertial.hh** + The MOI functions have been renamed to Moi. -## Ignition Math 3.X to 4.X +## Gazebo Math 3.X to 4.X ### Added dependencies @@ -161,7 +164,7 @@ release will remove the deprecated code. + ***Deprecation:*** public: void Translate(T _x, T _y, T _z) + ***Replacement:*** public: void SetTranslation(T _x, T _y, T _z) -## Ignition Math 2.X to 3.X +## Gazebo Math 2.X to 3.X ### Modifications @@ -181,97 +184,97 @@ release will remove the deprecated code. 1. **Helpers.hh** + ***Deprecation:*** IGN_DBL_MAX - + ***Replacement:*** ignition::math::MAX_D + + ***Replacement:*** gz::math::MAX_D + ***Deprecation:*** IGN_DBL_MIN - + ***Replacement:*** ignition::math::MIN_D + + ***Replacement:*** gz::math::MIN_D + ***Deprecation:*** IGN_DBL_LOW - + ***Replacement:*** ignition::math::LOW_D + + ***Replacement:*** gz::math::LOW_D + ***Deprecation:*** IGN_DBL_INF - + ***Replacement:*** ignition::math::INF_D + + ***Replacement:*** gz::math::INF_D + ***Deprecation:*** IGN_FLT_MAX - + ***Replacement:*** ignition::math::MAX_F + + ***Replacement:*** gz::math::MAX_F + ***Deprecation:*** IGN_FLT_MIN - + ***Replacement:*** ignition::math::MIN_F + + ***Replacement:*** gz::math::MIN_F + ***Deprecation:*** IGN_FLT_LOW - + ***Replacement:*** ignition::math::LOW_F + + ***Replacement:*** gz::math::LOW_F + ***Deprecation:*** IGN_FLT_INF - + ***Replacement:*** ignition::math::INF_F + + ***Replacement:*** gz::math::INF_F + ***Deprecation:*** IGN_UI16_MAX - + ***Replacement:*** ignition::math::MAX_UI16 + + ***Replacement:*** gz::math::MAX_UI16 + ***Deprecation:*** IGN_UI16_MIN - + ***Replacement:*** ignition::math::MIN_UI16 + + ***Replacement:*** gz::math::MIN_UI16 + ***Deprecation:*** IGN_UI16_LOW - + ***Replacement:*** ignition::math::LOW_UI16 + + ***Replacement:*** gz::math::LOW_UI16 + ***Deprecation:*** IGN_UI16_INF - + ***Replacement:*** ignition::math::INF_UI16 + + ***Replacement:*** gz::math::INF_UI16 + ***Deprecation:*** IGN_I16_MAX - + ***Replacement:*** ignition::math::MAX_I16 + + ***Replacement:*** gz::math::MAX_I16 + ***Deprecation:*** IGN_I16_MIN - + ***Replacement:*** ignition::math::MIN_I16 + + ***Replacement:*** gz::math::MIN_I16 + ***Deprecation:*** IGN_I16_LOW - + ***Replacement:*** ignition::math::LOW_I16 + + ***Replacement:*** gz::math::LOW_I16 + ***Deprecation:*** IGN_I16_INF - + ***Replacement:*** ignition::math::INF_I16 + + ***Replacement:*** gz::math::INF_I16 + ***Deprecation:*** IGN_UI32_MAX - + ***Replacement:*** ignition::math::MAX_UI32 + + ***Replacement:*** gz::math::MAX_UI32 + ***Deprecation:*** IGN_UI32_MIN - + ***Replacement:*** ignition::math::MIN_UI32 + + ***Replacement:*** gz::math::MIN_UI32 + ***Deprecation:*** IGN_UI32_LOW - + ***Replacement:*** ignition::math::LOW_UI32 + + ***Replacement:*** gz::math::LOW_UI32 + ***Deprecation:*** IGN_UI32_INF - + ***Replacement:*** ignition::math::INF_UI32 + + ***Replacement:*** gz::math::INF_UI32 + ***Deprecation:*** IGN_I32_MAX - + ***Replacement:*** ignition::math::MAX_I32 + + ***Replacement:*** gz::math::MAX_I32 + ***Deprecation:*** IGN_I32_MIN - + ***Replacement:*** ignition::math::MIN_I32 + + ***Replacement:*** gz::math::MIN_I32 + ***Deprecation:*** IGN_I32_LOW - + ***Replacement:*** ignition::math::LOW_I32 + + ***Replacement:*** gz::math::LOW_I32 + ***Deprecation:*** IGN_I32_INF - + ***Replacement:*** ignition::math::INF_I32 + + ***Replacement:*** gz::math::INF_I32 + ***Deprecation:*** IGN_UI64_MAX - + ***Replacement:*** ignition::math::MAX_UI64 + + ***Replacement:*** gz::math::MAX_UI64 + ***Deprecation:*** IGN_UI64_MIN - + ***Replacement:*** ignition::math::MIN_UI64 + + ***Replacement:*** gz::math::MIN_UI64 + ***Deprecation:*** IGN_UI64_LOW - + ***Replacement:*** ignition::math::LOW_UI64 + + ***Replacement:*** gz::math::LOW_UI64 + ***Deprecation:*** IGN_UI64_INF - + ***Replacement:*** ignition::math::INF_UI64 + + ***Replacement:*** gz::math::INF_UI64 + ***Deprecation:*** IGN_I64_MAX - + ***Replacement:*** ignition::math::MAX_I64 + + ***Replacement:*** gz::math::MAX_I64 + ***Deprecation:*** IGN_I64_MIN - + ***Replacement:*** ignition::math::MIN_I64 + + ***Replacement:*** gz::math::MIN_I64 + ***Deprecation:*** IGN_I64_LOW - + ***Replacement:*** ignition::math::LOW_I64 + + ***Replacement:*** gz::math::LOW_I64 + ***Deprecation:*** IGN_I64_INF - + ***Replacement:*** ignition::math::INF_I64 + + ***Replacement:*** gz::math::INF_I64 diff --git a/README.md b/README.md index 2c750f1be..79840c5d3 100644 --- a/README.md +++ b/README.md @@ -1,21 +1,21 @@ -# Ignition Math : Math classes and functions for robot applications +# Gazebo Math : Math classes and functions for robot applications **Maintainer:** nate AT openrobotics DOT org -[![GitHub open issues](https://img.shields.io/github/issues-raw/ignitionrobotics/ign-math.svg)](https://github.com/ignitionrobotics/ign-math/issues) -[![GitHub open pull requests](https://img.shields.io/github/issues-pr-raw/ignitionrobotics/ign-math.svg)](https://github.com/ignitionrobotics/ign-math/pulls) +[![GitHub open issues](https://img.shields.io/github/issues-raw/gazebosim/gz-math.svg)](https://github.com/gazebosim/gz-math/issues) +[![GitHub open pull requests](https://img.shields.io/github/issues-pr-raw/gazebosim/gz-math.svg)](https://github.com/gazebosim/gz-math/pulls) [![Discourse topics](https://img.shields.io/discourse/https/community.gazebosim.org/topics.svg)](https://community.gazebosim.org) [![Hex.pm](https://img.shields.io/hexpm/l/plug.svg)](https://www.apache.org/licenses/LICENSE-2.0) Build | Status -- | -- -Test coverage | [![codecov](https://codecov.io/gh/ignitionrobotics/ign-math/branch/ign-math7/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-math) +Test coverage | [![codecov](https://codecov.io/gh/gazebosim/gz-math/branch/ign-math7/graph/badge.svg)](https://codecov.io/gh/gazebosim/gz-math) Ubuntu Focal | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_math-ci-ign-math7-focal-amd64)](https://build.osrfoundation.org/job/ignition_math-ci-ign-math7-focal-amd64) Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_math-ci-ign-math7-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_math-ci-ign-math7-homebrew-amd64) Windows | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ign_math-ign-7-win)](https://build.osrfoundation.org/job/ign_math-ign-7-win) -Ignition Math, a component of [Ignition -Robotics](https://ignitionrobotics.org), provides general purpose math +Gazebo Math, a component of [Ignition +Robotics](https://gazebosim.org), provides general purpose math classes and functions designed for robotic applications. # Table of Contents @@ -38,7 +38,7 @@ classes and functions designed for robotic applications. # Features -Ignition Math provides a wide range of functionality, including: +Gazebo Math provides a wide range of functionality, including: * Type-templated pose, matrix, vector, and quaternion classes. * Shape representations along with operators to compute volume, density, size and other properties. @@ -48,11 +48,11 @@ Math types. # Install -See the [installation tutorial](https://ignitionrobotics.org/api/math/6.8/install.html). +See the [installation tutorial](https://gazebosim.org/api/math/6.8/install.html). # Usage -Please refer to the [examples directory](https://github.com/ignitionrobotics/ign-math/raw/ign-math7/examples/). +Please refer to the [examples directory](https://github.com/gazebosim/gz-math/raw/ign-math7/examples/). # Folder Structure @@ -78,17 +78,17 @@ ign-math # Contributing Please see -[CONTRIBUTING.md](https://github.com/ignitionrobotics/ign-gazebo/blob/main/CONTRIBUTING.md). +[CONTRIBUTING.md](https://github.com/gazebosim/gz-sim/blob/main/CONTRIBUTING.md). # Code of Conduct Please see -[CODE_OF_CONDUCT.md](https://github.com/ignitionrobotics/ign-gazebo/blob/main/CODE_OF_CONDUCT.md). +[CODE_OF_CONDUCT.md](https://github.com/gazebosim/gz-sim/blob/main/CODE_OF_CONDUCT.md). # Versioning -This library uses [Semantic Versioning](https://semver.org/). Additionally, this library is part of the [Ignition Robotics project](https://ignitionrobotics.org) which periodically releases a versioned set of compatible and complimentary libraries. See the [Ignition Robotics website](https://ignitionrobotics.org) for version and release information. +This library uses [Semantic Versioning](https://semver.org/). Additionally, this library is part of the [Gazebo project](https://gazebosim.org) which periodically releases a versioned set of compatible and complimentary libraries. See the [Gazebo website](https://gazebosim.org) for version and release information. # License -This library is licensed under [Apache 2.0](https://www.apache.org/licenses/LICENSE-2.0). See also the [LICENSE](https://github.com/ignitionrobotics/ign-math/blob/main/LICENSE) file. +This library is licensed under [Apache 2.0](https://www.apache.org/licenses/LICENSE-2.0). See also the [LICENSE](https://github.com/gazebosim/gz-math/blob/main/LICENSE) file. diff --git a/api.md.in b/api.md.in index ae69b7a96..bb43c0772 100644 --- a/api.md.in +++ b/api.md.in @@ -1,6 +1,6 @@ ## Ignition @IGN_DESIGNATION_CAP@ -Ignition @IGN_DESIGNATION_CAP@ is a component in Ignition Robotics, a set of +Ignition @IGN_DESIGNATION_CAP@ is a component in Gazebo, a set of libraries designed to rapidly develop robot and simulation applications. This library defines a general set of math classes and functions with an eye toward simulation and robotics. diff --git a/eigen3/include/gz/math/eigen3/Conversions.hh b/eigen3/include/gz/math/eigen3/Conversions.hh index ac8e27cf9..4d7a16b40 100644 --- a/eigen3/include/gz/math/eigen3/Conversions.hh +++ b/eigen3/include/gz/math/eigen3/Conversions.hh @@ -25,34 +25,34 @@ #include #include -namespace ignition +namespace gz { namespace math { namespace eigen3 { - /// \brief Convert from ignition::math::Vector3d to Eigen::Vector3d. - /// \param[in] _v ignition::math::Vector3d to convert + /// \brief Convert from gz::math::Vector3d to Eigen::Vector3d. + /// \param[in] _v gz::math::Vector3d to convert /// \return The equivalent Eigen::Vector3d. - inline Eigen::Vector3d convert(const ignition::math::Vector3d &_v) + inline Eigen::Vector3d convert(const gz::math::Vector3d &_v) { return Eigen::Vector3d(_v[0], _v[1], _v[2]); } - /// \brief Convert from ignition::math::AxisAlignedBox to + /// \brief Convert from gz::math::AxisAlignedBox to /// Eigen::AlignedBox3d. - /// \param[in] _b ignition::math::AxisAlignedBox to convert + /// \param[in] _b gz::math::AxisAlignedBox to convert /// \return The equivalent Eigen::AlignedBox3d. inline Eigen::AlignedBox3d convert( - const ignition::math::AxisAlignedBox &_b) + const gz::math::AxisAlignedBox &_b) { return Eigen::AlignedBox3d(convert(_b.Min()), convert(_b.Max())); } - /// \brief Convert from ignition::math::Matrix3d to Eigen::Matrix3d. - /// \param[in] _m ignition::math::Matrix3d to convert. + /// \brief Convert from gz::math::Matrix3d to Eigen::Matrix3d. + /// \param[in] _m gz::math::Matrix3d to convert. /// \return The equivalent Eigen::Matrix3d. - inline Eigen::Matrix3d convert(const ignition::math::Matrix3d &_m) + inline Eigen::Matrix3d convert(const gz::math::Matrix3d &_m) { Eigen::Matrix3d matrix; for (std::size_t i=0; i < 3; ++i) @@ -66,10 +66,10 @@ namespace ignition return matrix; } - /// \brief Convert ignition::math::Quaterniond to Eigen::Quaterniond. - /// \param[in] _q ignition::math::Quaterniond to convert. + /// \brief Convert gz::math::Quaterniond to Eigen::Quaterniond. + /// \param[in] _q gz::math::Quaterniond to convert. /// \return The equivalent Eigen::Quaterniond. - inline Eigen::Quaterniond convert(const ignition::math::Quaterniond &_q) + inline Eigen::Quaterniond convert(const gz::math::Quaterniond &_q) { Eigen::Quaterniond quat; quat.w() = _q.W(); @@ -80,10 +80,10 @@ namespace ignition return quat; } - /// \brief Convert ignition::math::Pose3d to Eigen::Isometry3d. - /// \param[in] _pose ignition::math::Pose3d to convert. + /// \brief Convert gz::math::Pose3d to Eigen::Isometry3d. + /// \param[in] _pose gz::math::Pose3d to convert. /// \return The equivalent Eigen::Isometry3d. - inline Eigen::Isometry3d convert(const ignition::math::Pose3d &_pose) + inline Eigen::Isometry3d convert(const gz::math::Pose3d &_pose) { Eigen::Isometry3d tf = Eigen::Isometry3d::Identity(); tf.translation() = convert(_pose.Pos()); @@ -92,12 +92,12 @@ namespace ignition return tf; } - /// \brief Convert Eigen::Vector3d to ignition::math::Vector3d. + /// \brief Convert Eigen::Vector3d to gz::math::Vector3d. /// \param[in] _v Eigen::Vector3d to convert. - /// \return The equivalent ignition::math::Vector3d. - inline ignition::math::Vector3d convert(const Eigen::Vector3d &_v) + /// \return The equivalent gz::math::Vector3d. + inline gz::math::Vector3d convert(const Eigen::Vector3d &_v) { - ignition::math::Vector3d vec; + gz::math::Vector3d vec; vec.X() = _v[0]; vec.Y() = _v[1]; vec.Z() = _v[2]; @@ -105,25 +105,25 @@ namespace ignition return vec; } - /// \brief Convert Eigen::AlignedBox3d to ignition::math::AxisAlignedBox. + /// \brief Convert Eigen::AlignedBox3d to gz::math::AxisAlignedBox. /// \param[in] _b Eigen::AlignedBox3d to convert. - /// \return The equivalent ignition::math::AxisAlignedBox. - inline ignition::math::AxisAlignedBox convert( + /// \return The equivalent gz::math::AxisAlignedBox. + inline gz::math::AxisAlignedBox convert( const Eigen::AlignedBox3d &_b) { - ignition::math::AxisAlignedBox box; + gz::math::AxisAlignedBox box; box.Min() = convert(_b.min()); box.Max() = convert(_b.max()); return box; } - /// \brief Convert Eigen::Matrix3d to ignition::math::Matrix3d. + /// \brief Convert Eigen::Matrix3d to gz::math::Matrix3d. /// \param[in] _m Eigen::Matrix3d to convert. - /// \return The equivalent ignition::math::Matrix3d. - inline ignition::math::Matrix3d convert(const Eigen::Matrix3d &_m) + /// \return The equivalent gz::math::Matrix3d. + inline gz::math::Matrix3d convert(const Eigen::Matrix3d &_m) { - ignition::math::Matrix3d matrix; + gz::math::Matrix3d matrix; for (std::size_t i=0; i < 3; ++i) { for (std::size_t j=0; j < 3; ++j) @@ -135,12 +135,12 @@ namespace ignition return matrix; } - /// \brief Convert Eigen::Quaterniond to ignition::math::Quaterniond. + /// \brief Convert Eigen::Quaterniond to gz::math::Quaterniond. /// \param[in] _q Eigen::Quaterniond to convert. - /// \return The equivalent ignition::math::Quaterniond. - inline ignition::math::Quaterniond convert(const Eigen::Quaterniond &_q) + /// \return The equivalent gz::math::Quaterniond. + inline gz::math::Quaterniond convert(const Eigen::Quaterniond &_q) { - ignition::math::Quaterniond quat; + gz::math::Quaterniond quat; quat.W() = _q.w(); quat.X() = _q.x(); quat.Y() = _q.y(); @@ -149,12 +149,12 @@ namespace ignition return quat; } - /// \brief Convert Eigen::Isometry3d to ignition::math::Pose3d. + /// \brief Convert Eigen::Isometry3d to gz::math::Pose3d. /// \param[in] _tf Eigen::Isometry3d to convert. - /// \return The equivalent ignition::math::Pose3d. - inline ignition::math::Pose3d convert(const Eigen::Isometry3d &_tf) + /// \return The equivalent gz::math::Pose3d. + inline gz::math::Pose3d convert(const Eigen::Isometry3d &_tf) { - ignition::math::Pose3d pose; + gz::math::Pose3d pose; pose.Pos() = convert(Eigen::Vector3d(_tf.translation())); pose.Rot() = convert(Eigen::Quaterniond(_tf.linear())); diff --git a/eigen3/include/gz/math/eigen3/Util.hh b/eigen3/include/gz/math/eigen3/Util.hh index bfc49c7f8..e4b25642f 100644 --- a/eigen3/include/gz/math/eigen3/Util.hh +++ b/eigen3/include/gz/math/eigen3/Util.hh @@ -31,7 +31,7 @@ #include #include -namespace ignition +namespace gz { namespace math { @@ -84,7 +84,7 @@ namespace ignition /// http://codextechnicanum.blogspot.com/2015/04/find-minimum-oriented-bounding-box-of.html /// \param[in] _vertices a vector of 3d vertices /// \return Oriented 3D box - inline ignition::math::OrientedBoxd verticesToOrientedBox( + inline gz::math::OrientedBoxd verticesToOrientedBox( const std::vector &_vertices) { math::OrientedBoxd box; diff --git a/eigen3/include/ignition/math/eigen3.hh b/eigen3/include/ignition/math/eigen3.hh index 518f8fb7f..f0a14b78e 100644 --- a/eigen3/include/ignition/math/eigen3.hh +++ b/eigen3/include/ignition/math/eigen3.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/eigen3/include/ignition/math/eigen3/Conversions.hh b/eigen3/include/ignition/math/eigen3/Conversions.hh index 3931146f5..d794ec1c4 100644 --- a/eigen3/include/ignition/math/eigen3/Conversions.hh +++ b/eigen3/include/ignition/math/eigen3/Conversions.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/eigen3/include/ignition/math/eigen3/Util.hh b/eigen3/include/ignition/math/eigen3/Util.hh index 8e1172782..0807839e2 100644 --- a/eigen3/include/ignition/math/eigen3/Util.hh +++ b/eigen3/include/ignition/math/eigen3/Util.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/eigen3/src/Conversions_TEST.cc b/eigen3/src/Conversions_TEST.cc index 763df6e19..bf58686b7 100644 --- a/eigen3/src/Conversions_TEST.cc +++ b/eigen3/src/Conversions_TEST.cc @@ -25,22 +25,22 @@ TEST(EigenConversions, ConvertVector3) { { - ignition::math::Vector3d iVec, iVec2; - Eigen::Vector3d eVec = ignition::math::eigen3::convert(iVec); + gz::math::Vector3d iVec, iVec2; + Eigen::Vector3d eVec = gz::math::eigen3::convert(iVec); EXPECT_DOUBLE_EQ(0, eVec[0]); EXPECT_DOUBLE_EQ(0, eVec[1]); EXPECT_DOUBLE_EQ(0, eVec[2]); - iVec2 = ignition::math::eigen3::convert(eVec); + iVec2 = gz::math::eigen3::convert(eVec); EXPECT_EQ(iVec, iVec2); } { - ignition::math::Vector3d iVec(100.5, -2.314, 42), iVec2; - Eigen::Vector3d eVec = ignition::math::eigen3::convert(iVec); + gz::math::Vector3d iVec(100.5, -2.314, 42), iVec2; + Eigen::Vector3d eVec = gz::math::eigen3::convert(iVec); EXPECT_DOUBLE_EQ(iVec[0], eVec[0]); EXPECT_DOUBLE_EQ(iVec[1], eVec[1]); EXPECT_DOUBLE_EQ(iVec[2], eVec[2]); - iVec2 = ignition::math::eigen3::convert(eVec); + iVec2 = gz::math::eigen3::convert(eVec); EXPECT_EQ(iVec, iVec2); } } @@ -50,31 +50,31 @@ TEST(EigenConversions, ConvertVector3) TEST(EigenConversions, ConvertAxisAlignedBox) { { - ignition::math::AxisAlignedBox iBox, iBox2; - Eigen::AlignedBox3d eBox = ignition::math::eigen3::convert(iBox); - EXPECT_DOUBLE_EQ(ignition::math::MAX_D, eBox.min()[0]); - EXPECT_DOUBLE_EQ(ignition::math::MAX_D, eBox.min()[1]); - EXPECT_DOUBLE_EQ(ignition::math::MAX_D, eBox.min()[2]); - EXPECT_DOUBLE_EQ(ignition::math::LOW_D, eBox.max()[0]); - EXPECT_DOUBLE_EQ(ignition::math::LOW_D, eBox.max()[1]); - EXPECT_DOUBLE_EQ(ignition::math::LOW_D, eBox.max()[2]); - iBox2 = ignition::math::eigen3::convert(eBox); + gz::math::AxisAlignedBox iBox, iBox2; + Eigen::AlignedBox3d eBox = gz::math::eigen3::convert(iBox); + EXPECT_DOUBLE_EQ(gz::math::MAX_D, eBox.min()[0]); + EXPECT_DOUBLE_EQ(gz::math::MAX_D, eBox.min()[1]); + EXPECT_DOUBLE_EQ(gz::math::MAX_D, eBox.min()[2]); + EXPECT_DOUBLE_EQ(gz::math::LOW_D, eBox.max()[0]); + EXPECT_DOUBLE_EQ(gz::math::LOW_D, eBox.max()[1]); + EXPECT_DOUBLE_EQ(gz::math::LOW_D, eBox.max()[2]); + iBox2 = gz::math::eigen3::convert(eBox); EXPECT_EQ(iBox, iBox2); } { - ignition::math::AxisAlignedBox iBox( - ignition::math::Vector3d(100.5, -2.314, 42), - ignition::math::Vector3d(305, 2.314, 142)); - ignition::math::AxisAlignedBox iBox2; - Eigen::AlignedBox3d eBox = ignition::math::eigen3::convert(iBox); + gz::math::AxisAlignedBox iBox( + gz::math::Vector3d(100.5, -2.314, 42), + gz::math::Vector3d(305, 2.314, 142)); + gz::math::AxisAlignedBox iBox2; + Eigen::AlignedBox3d eBox = gz::math::eigen3::convert(iBox); EXPECT_DOUBLE_EQ(iBox.Min()[0], eBox.min()[0]); EXPECT_DOUBLE_EQ(iBox.Min()[1], eBox.min()[1]); EXPECT_DOUBLE_EQ(iBox.Min()[2], eBox.min()[2]); EXPECT_DOUBLE_EQ(iBox.Max()[0], eBox.max()[0]); EXPECT_DOUBLE_EQ(iBox.Max()[1], eBox.max()[1]); EXPECT_DOUBLE_EQ(iBox.Max()[2], eBox.max()[2]); - iBox2 = ignition::math::eigen3::convert(eBox); + iBox2 = gz::math::eigen3::convert(eBox); EXPECT_EQ(iBox, iBox2); } } @@ -84,24 +84,24 @@ TEST(EigenConversions, ConvertAxisAlignedBox) TEST(EigenConversions, ConvertQuaternion) { { - ignition::math::Quaterniond iQuat, iQuat2; - Eigen::Quaterniond eQuat = ignition::math::eigen3::convert(iQuat); + gz::math::Quaterniond iQuat, iQuat2; + Eigen::Quaterniond eQuat = gz::math::eigen3::convert(iQuat); EXPECT_DOUBLE_EQ(1, eQuat.w()); EXPECT_DOUBLE_EQ(0, eQuat.x()); EXPECT_DOUBLE_EQ(0, eQuat.y()); EXPECT_DOUBLE_EQ(0, eQuat.z()); - iQuat2 = ignition::math::eigen3::convert(eQuat); + iQuat2 = gz::math::eigen3::convert(eQuat); EXPECT_EQ(iQuat, iQuat2); } { - ignition::math::Quaterniond iQuat(0.1, 0.2, 0.3), iQuat2; - Eigen::Quaterniond eQuat = ignition::math::eigen3::convert(iQuat); + gz::math::Quaterniond iQuat(0.1, 0.2, 0.3), iQuat2; + Eigen::Quaterniond eQuat = gz::math::eigen3::convert(iQuat); EXPECT_DOUBLE_EQ(iQuat.W(), eQuat.w()); EXPECT_DOUBLE_EQ(iQuat.X(), eQuat.x()); EXPECT_DOUBLE_EQ(iQuat.Y(), eQuat.y()); EXPECT_DOUBLE_EQ(iQuat.Z(), eQuat.z()); - iQuat2 = ignition::math::eigen3::convert(eQuat); + iQuat2 = gz::math::eigen3::convert(eQuat); EXPECT_EQ(iQuat, iQuat2); } } @@ -111,8 +111,8 @@ TEST(EigenConversions, ConvertQuaternion) TEST(EigenConversions, ConvertMatrix3) { { - ignition::math::Matrix3d iMat, iMat2; - Eigen::Matrix3d eMat = ignition::math::eigen3::convert(iMat); + gz::math::Matrix3d iMat, iMat2; + Eigen::Matrix3d eMat = gz::math::eigen3::convert(iMat); EXPECT_DOUBLE_EQ(0, eMat(0, 0)); EXPECT_DOUBLE_EQ(0, eMat(0, 1)); EXPECT_DOUBLE_EQ(0, eMat(0, 2)); @@ -122,14 +122,14 @@ TEST(EigenConversions, ConvertMatrix3) EXPECT_DOUBLE_EQ(0, eMat(2, 0)); EXPECT_DOUBLE_EQ(0, eMat(2, 1)); EXPECT_DOUBLE_EQ(0, eMat(2, 2)); - iMat2 = ignition::math::eigen3::convert(eMat); + iMat2 = gz::math::eigen3::convert(eMat); EXPECT_EQ(iMat, iMat2); } { - ignition::math::Matrix3d iMat(1, 2, 3, 4, 5, 6, 7, 8, 9), iMat2; - Eigen::Matrix3d eMat = ignition::math::eigen3::convert(iMat); + gz::math::Matrix3d iMat(1, 2, 3, 4, 5, 6, 7, 8, 9), iMat2; + Eigen::Matrix3d eMat = gz::math::eigen3::convert(iMat); EXPECT_DOUBLE_EQ(iMat(0, 0), eMat(0, 0)); EXPECT_DOUBLE_EQ(iMat(0, 1), eMat(0, 1)); EXPECT_DOUBLE_EQ(iMat(0, 2), eMat(0, 2)); @@ -139,7 +139,7 @@ TEST(EigenConversions, ConvertMatrix3) EXPECT_DOUBLE_EQ(iMat(2, 0), eMat(2, 0)); EXPECT_DOUBLE_EQ(iMat(2, 1), eMat(2, 1)); EXPECT_DOUBLE_EQ(iMat(2, 2), eMat(2, 2)); - iMat2 = ignition::math::eigen3::convert(eMat); + iMat2 = gz::math::eigen3::convert(eMat); EXPECT_EQ(iMat, iMat2); } } @@ -149,8 +149,8 @@ TEST(EigenConversions, ConvertMatrix3) TEST(EigenConversions, ConvertPose3) { { - ignition::math::Pose3d iPose, iPose2; - Eigen::Isometry3d ePose = ignition::math::eigen3::convert(iPose); + gz::math::Pose3d iPose, iPose2; + Eigen::Isometry3d ePose = gz::math::eigen3::convert(iPose); Eigen::Vector3d eVec = ePose.translation(); EXPECT_DOUBLE_EQ(0, eVec[0]); EXPECT_DOUBLE_EQ(0, eVec[1]); @@ -160,14 +160,14 @@ TEST(EigenConversions, ConvertPose3) EXPECT_DOUBLE_EQ(0, eQuat.x()); EXPECT_DOUBLE_EQ(0, eQuat.y()); EXPECT_DOUBLE_EQ(0, eQuat.z()); - iPose2 = ignition::math::eigen3::convert(ePose); + iPose2 = gz::math::eigen3::convert(ePose); EXPECT_EQ(iPose, iPose2); } { - ignition::math::Pose3d iPose(105.4, 3.1, -0.34, 3.14/8, 3.14/16, -3.14/2); - ignition::math::Pose3d iPose2; - Eigen::Isometry3d ePose = ignition::math::eigen3::convert(iPose); + gz::math::Pose3d iPose(105.4, 3.1, -0.34, 3.14/8, 3.14/16, -3.14/2); + gz::math::Pose3d iPose2; + Eigen::Isometry3d ePose = gz::math::eigen3::convert(iPose); Eigen::Vector3d eVec = ePose.translation(); EXPECT_DOUBLE_EQ(iPose.Pos()[0], eVec[0]); EXPECT_DOUBLE_EQ(iPose.Pos()[1], eVec[1]); @@ -177,7 +177,7 @@ TEST(EigenConversions, ConvertPose3) EXPECT_DOUBLE_EQ(iPose.Rot().X(), eQuat.x()); EXPECT_DOUBLE_EQ(iPose.Rot().Y(), eQuat.y()); EXPECT_DOUBLE_EQ(iPose.Rot().Z(), eQuat.z()); - iPose2 = ignition::math::eigen3::convert(ePose); + iPose2 = gz::math::eigen3::convert(ePose); EXPECT_EQ(iPose, iPose2); } } diff --git a/eigen3/src/Util_TEST.cc b/eigen3/src/Util_TEST.cc index 0e095f84f..a4281ecc3 100644 --- a/eigen3/src/Util_TEST.cc +++ b/eigen3/src/Util_TEST.cc @@ -19,7 +19,7 @@ #include -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// /// \brief Test the oriented box converted from a set of vertices diff --git a/examples/README.md b/examples/README.md index 6d3492519..4462ce264 100644 --- a/examples/README.md +++ b/examples/README.md @@ -1,6 +1,6 @@ ## Examples -Example programs using Ignition Math. +Example programs using Gazebo Math. ## Build diff --git a/examples/additively_separable_scalar_field3_example.cc b/examples/additively_separable_scalar_field3_example.cc index 6197d5480..20670c59a 100644 --- a/examples/additively_separable_scalar_field3_example.cc +++ b/examples/additively_separable_scalar_field3_example.cc @@ -22,15 +22,15 @@ int main(int argc, char **argv) { const double kConstant = 1.; - const ignition::math::Polynomial3d xPoly( - ignition::math::Vector4d(0., 1., 0., 1.)); - const ignition::math::Polynomial3d yPoly( - ignition::math::Vector4d(1., 0., 1., 0.)); - const ignition::math::Polynomial3d zPoly( - ignition::math::Vector4d(1., 0., 0., -1.)); + const gz::math::Polynomial3d xPoly( + gz::math::Vector4d(0., 1., 0., 1.)); + const gz::math::Polynomial3d yPoly( + gz::math::Vector4d(1., 0., 1., 0.)); + const gz::math::Polynomial3d zPoly( + gz::math::Vector4d(1., 0., 0., -1.)); using AdditivelySeparableScalarField3dT = - ignition::math::AdditivelySeparableScalarField3d< - ignition::math::Polynomial3d>; + gz::math::AdditivelySeparableScalarField3d< + gz::math::Polynomial3d>; const AdditivelySeparableScalarField3dT scalarField( kConstant, xPoly, yPoly, zPoly); @@ -41,7 +41,7 @@ int main(int argc, char **argv) // An additively separable scalar field can be evaluated. std::cout << "Evaluating F(x, y, z) at (0, 1, 0) yields " - << scalarField(ignition::math::Vector3d::UnitY) + << scalarField(gz::math::Vector3d::UnitY) << std::endl; // An additively separable scalar field can be queried for its diff --git a/examples/angle_example.cc b/examples/angle_example.cc index 635499714..e0390e529 100644 --- a/examples/angle_example.cc +++ b/examples/angle_example.cc @@ -22,14 +22,14 @@ int main(int argc, char **argv) { //! [Create an angle] - ignition::math::Angle a; + gz::math::Angle a; //! [Create an angle] // A default constructed angle should be zero. std::cout << "The angle 'a' should be zero: " << a << std::endl; //! [constant pi] - a = ignition::math::Angle::HalfPi; - a = ignition::math::Angle::Pi; + a = gz::math::Angle::HalfPi; + a = gz::math::Angle::Pi; //! [constant pi] //! [Output the angle in radians and degrees.] @@ -38,7 +38,7 @@ int main(int argc, char **argv) //! [Output the angle in radians and degrees.] //! [The Angle class overloads the +=, and many other, math operators.] - a += ignition::math::Angle::HalfPi; + a += gz::math::Angle::HalfPi; //! [The Angle class overloads the +=, and many other, math operators.] std::cout << "Pi + PI/2 in radians: " << a << std::endl; //! [normalized] diff --git a/examples/angle_example.rb b/examples/angle_example.rb index e3b594d80..d68e087b0 100644 --- a/examples/angle_example.rb +++ b/examples/angle_example.rb @@ -23,18 +23,18 @@ require 'ignition/math' #! [constant] -printf("PI in degrees = %f\n", Ignition::Math::Angle.Pi.Degree) +printf("PI in degrees = %f\n", Gz::Math::Angle.Pi.Degree) #! [constant] -a1 = Ignition::Math::Angle.new(1.5707) -a2 = Ignition::Math::Angle.new(0.7854) +a1 = Gz::Math::Angle.new(1.5707) +a2 = Gz::Math::Angle.new(0.7854) printf("a1 = %f radians, %f degrees\n", a1.Radian, a1.Degree) printf("a2 = %f radians, %f degrees\n", a2.Radian, a2.Degree) printf("a1 * a2 = %f radians, %f degrees\n", (a1 * a2).Radian, (a1 * a2).Degree) printf("a1 + a2 = %f radians, %f degrees\n", (a1 + a2).Radian, (a1 + a2).Degree) printf("a1 - a2 = %f radians, %f degrees\n", (a1 - a2).Radian, (a1 - a2).Degree) -a3 = Ignition::Math::Angle.new(15.707) +a3 = Gz::Math::Angle.new(15.707) printf("a3 = %f radians, %f degrees\n", a3.Radian, a3.Degree) a3.Normalize printf("a3.Normalize = %f radians, %f degrees\n", a3.Radian, a3.Degree) diff --git a/examples/color_example.cc b/examples/color_example.cc index d7c340acf..8d0419234 100644 --- a/examples/color_example.cc +++ b/examples/color_example.cc @@ -22,25 +22,25 @@ int main(int argc, char **argv) { //! [Create a color] - ignition::math::Color a = ignition::math::Color(0.3, 0.4, 0.5); + gz::math::Color a = gz::math::Color(0.3, 0.4, 0.5); //! [Create a color] // The channel order is R, G, B, A and the default alpha value of a should be 1.0 std::cout << "The alpha value of a should be 1: " << a.A() << std::endl; //! [Set a new color value] - a.ignition::math::Color::Set(0.6, 0.7, 0.8, 1.0); + a.gz::math::Color::Set(0.6, 0.7, 0.8, 1.0); //! [Set a new color value] std::cout << "The RGBA value of a: " << a << std::endl; //! [Set value from BGRA] // 0xFF0000FF is blue in BGRA. Convert it to RGBA. - ignition::math::Color::BGRA blue = 0xFF0000FF; - a.ignition::math::Color::SetFromBGRA(blue); + gz::math::Color::BGRA blue = 0xFF0000FF; + a.gz::math::Color::SetFromBGRA(blue); //! [Set value from BGRA] //! [Math operator] - std::cout << "Check if a is Blue: " << (a == ignition::math::Color::Blue) << std::endl; + std::cout << "Check if a is Blue: " << (a == gz::math::Color::Blue) << std::endl; std::cout << "The RGB value of a should be (0, 0, 1): " << a[0] << ", " << a[1] << ", " << a[2] << std::endl; @@ -48,7 +48,7 @@ int main(int argc, char **argv) //! [Set value from HSV] // Initialize with HSV. (240, 1.0, 1.0) is blue in HSV. - a.ignition::math::Color::SetFromHSV(240.0, 1.0, 1.0); + a.gz::math::Color::SetFromHSV(240.0, 1.0, 1.0); std::cout << "The HSV value of a: " << a.HSV() << std::endl; std::cout << "The RGBA value of a should be (0, 0, 1, 1): " << a << std::endl; //! [Set value from HSV] diff --git a/examples/diff_drive_odometry.cc b/examples/diff_drive_odometry.cc index f244ace8d..7b0a2be06 100644 --- a/examples/diff_drive_odometry.cc +++ b/examples/diff_drive_odometry.cc @@ -26,7 +26,7 @@ int main(int argc, char **argv) { //! [Create a DiffDriveOdometry] - ignition::math::DiffDriveOdometry odom; + gz::math::DiffDriveOdometry odom; //! [Create an DiffDriveOdometry] double wheelSeparation = 2.0; diff --git a/examples/gauss_markov_process_example.cc b/examples/gauss_markov_process_example.cc index 027ea5136..1b0bf03fc 100644 --- a/examples/gauss_markov_process_example.cc +++ b/examples/gauss_markov_process_example.cc @@ -33,7 +33,7 @@ int main(int argc, char **argv) // * Theta (rate at which the process should approach the mean) of 0.1 // * Mu (mean value) 0. // * Sigma (volatility) of 0.5. - ignition::math::GaussMarkovProcess gmp(20.2, 0.1, 0, 0.5); + gz::math::GaussMarkovProcess gmp(20.2, 0.1, 0, 0.5); std::chrono::steady_clock::duration dt = std::chrono::milliseconds(100); diff --git a/examples/gauss_markov_process_example.rb b/examples/gauss_markov_process_example.rb index b6944dc8c..727a4d725 100644 --- a/examples/gauss_markov_process_example.rb +++ b/examples/gauss_markov_process_example.rb @@ -32,7 +32,7 @@ # * Theta (rate at which the process should approach the mean) of 0.1 # * Mu (mean value) 0. # * Sigma (volatility) of 0.5. -gmp = Ignition::Math::GaussMarkovProcess.new(20.2, 0.1, 0, 0.5); +gmp = Gz::Math::GaussMarkovProcess.new(20.2, 0.1, 0, 0.5); # This process should decrease toward the mean value of 0. # With noise of 0.5, the process will walk a bit. diff --git a/examples/graph_example.cc b/examples/graph_example.cc index 968a4513a..6552ecc0c 100644 --- a/examples/graph_example.cc +++ b/examples/graph_example.cc @@ -22,7 +22,7 @@ int main(int argc, char **argv) { // Create a directed graph that is capable of storing integer data in the // vertices and double data on the edges. - ignition::math::graph::DirectedGraph graph( + gz::math::graph::DirectedGraph graph( // Create the vertices, with default data and vertex ids. { {"vertex1"}, {"vertex2"}, {"vertex3"} @@ -40,7 +40,7 @@ int main(int argc, char **argv) << graph << std::endl; // You can assign data to vertices. - ignition::math::graph::DirectedGraph graph2( + gz::math::graph::DirectedGraph graph2( // Create the vertices, with custom data and default vertex ids. { {"vertex1", 1}, {"vertex2", 2}, {"vertex3", 10} @@ -58,7 +58,7 @@ int main(int argc, char **argv) << graph2 << std::endl; // It's also possible to specify vertex ids. - ignition::math::graph::DirectedGraph graph3( + gz::math::graph::DirectedGraph graph3( // Create the vertices with custom data and vertex ids. { {"vertex1", 1, 2}, {"vertex2", 2, 3}, {"vertex3", 10, 4} @@ -73,7 +73,7 @@ int main(int argc, char **argv) << graph3 << std::endl; // Finally, you can also assign weights to the edges. - ignition::math::graph::DirectedGraph graph4( + gz::math::graph::DirectedGraph graph4( // Create the vertices with custom data and vertex ids. { {"vertex1", 1, 2}, {"vertex2", 2, 3}, {"vertex3", 10, 4} diff --git a/examples/helpers_example.cc b/examples/helpers_example.cc index f3858b7a6..a7ae27632 100644 --- a/examples/helpers_example.cc +++ b/examples/helpers_example.cc @@ -30,17 +30,17 @@ int main(int argc, char **argv) << IGN_BOX_VOLUME(1, 2, 3) << std::endl; std::cout << "The result of clamping 2.4 to the range [1,2] is " - << ignition::math::clamp(2.4f, 1.0f, 2.0f) << std::endl; + << gz::math::clamp(2.4f, 1.0f, 2.0f) << std::endl; std::vector v{1, 2, 3, 4, 5}; std::cout << "The mean of a vector containing {1, 2, 3, 4, 5} is " - << ignition::math::mean(v) << std::endl; + << gz::math::mean(v) << std::endl; std::cout << "The variance of a vector containing {1, 2, 3, 4, 5} is " - << ignition::math::variance(v) << std::endl; + << gz::math::variance(v) << std::endl; std::cout << "The result of rounding up 3 to the next power of two is " - << ignition::math::roundUpPowerOfTwo(3) << std::endl; + << gz::math::roundUpPowerOfTwo(3) << std::endl; } //! [complete] diff --git a/examples/helpers_example.rb b/examples/helpers_example.rb index 9de113c58..be3100514 100644 --- a/examples/helpers_example.rb +++ b/examples/helpers_example.rb @@ -31,16 +31,16 @@ IGN_BOX_VOLUME(1, 2, 3)) printf("The result of clamping 2.4 to the range [1,2] is %f.\n", - Ignition::Math::Clamp(2.4, 1, 2)) + Gz::Math::Clamp(2.4, 1, 2)) std::vector v{1, 2, 3, 4, 5}; printf("The mean of a vector containing {1, 2, 3, 4, 5} is %f.\n", - Ignition::Math::mean(v)) + Gz::Math::mean(v)) printf("The variance of a vector containing {1, 2, 3, 4, 5} is %f.\n", - Ignition::Math::variance(v)) + Gz::Math::variance(v)) printf("The result of rounding up 3 to the next power of two is %f.\n", - << ignition::math::roundUpPowerOfTwo(3) << std::endl; + << gz::math::roundUpPowerOfTwo(3) << std::endl; diff --git a/examples/interval_example.cc b/examples/interval_example.cc index 9b1a4fea2..18f95fb47 100644 --- a/examples/interval_example.cc +++ b/examples/interval_example.cc @@ -22,21 +22,21 @@ int main(int argc, char **argv) { std::cout << std::boolalpha; - const ignition::math::Intervald defaultInterval; + const gz::math::Intervald defaultInterval; // A default constructed interval should be empty. std::cout << "The " << defaultInterval << " interval is empty: " << defaultInterval.Empty() << std::endl; - const ignition::math::Intervald openInterval = - ignition::math::Intervald::Open(-1., 1.); + const gz::math::Intervald openInterval = + gz::math::Intervald::Open(-1., 1.); // An open interval should exclude its endpoints. std::cout << "The " << openInterval << " interval contains its endpoints: " << (openInterval.Contains(openInterval.LeftValue()) || openInterval.Contains(openInterval.RightValue())) << std::endl; - const ignition::math::Intervald closedInterval = - ignition::math::Intervald::Closed(0., 1.); + const gz::math::Intervald closedInterval = + gz::math::Intervald::Closed(0., 1.); // A closed interval should include its endpoints. std::cout << "The " << closedInterval << " interval contains its endpoints: " @@ -50,10 +50,10 @@ int main(int argc, char **argv) << std::endl; // The unbounded interval should include all non-empty intervals. - std::cout << "The " << ignition::math::Intervald::Unbounded + std::cout << "The " << gz::math::Intervald::Unbounded << " interval contains all previous non-empty intervals: " - << (ignition::math::Intervald::Unbounded.Contains(openInterval) || - ignition::math::Intervald::Unbounded.Contains(closedInterval)) + << (gz::math::Intervald::Unbounded.Contains(openInterval) || + gz::math::Intervald::Unbounded.Contains(closedInterval)) << std::endl; } diff --git a/examples/kmeans.cc b/examples/kmeans.cc index 209948551..868d9f938 100644 --- a/examples/kmeans.cc +++ b/examples/kmeans.cc @@ -23,32 +23,32 @@ int main(int argc, char **argv) { // Create some observations. - std::vector obs; - obs.push_back(ignition::math::Vector3d(1.0, 1.0, 0.0)); - obs.push_back(ignition::math::Vector3d(1.1, 1.0, 0.0)); - obs.push_back(ignition::math::Vector3d(1.2, 1.0, 0.0)); - obs.push_back(ignition::math::Vector3d(1.3, 1.0, 0.0)); - obs.push_back(ignition::math::Vector3d(1.4, 1.0, 0.0)); - obs.push_back(ignition::math::Vector3d(5.0, 1.0, 0.0)); - obs.push_back(ignition::math::Vector3d(5.1, 1.0, 0.0)); - obs.push_back(ignition::math::Vector3d(5.2, 1.0, 0.0)); - obs.push_back(ignition::math::Vector3d(5.3, 1.0, 0.0)); - obs.push_back(ignition::math::Vector3d(5.4, 1.0, 0.0)); + std::vector obs; + obs.push_back(gz::math::Vector3d(1.0, 1.0, 0.0)); + obs.push_back(gz::math::Vector3d(1.1, 1.0, 0.0)); + obs.push_back(gz::math::Vector3d(1.2, 1.0, 0.0)); + obs.push_back(gz::math::Vector3d(1.3, 1.0, 0.0)); + obs.push_back(gz::math::Vector3d(1.4, 1.0, 0.0)); + obs.push_back(gz::math::Vector3d(5.0, 1.0, 0.0)); + obs.push_back(gz::math::Vector3d(5.1, 1.0, 0.0)); + obs.push_back(gz::math::Vector3d(5.2, 1.0, 0.0)); + obs.push_back(gz::math::Vector3d(5.3, 1.0, 0.0)); + obs.push_back(gz::math::Vector3d(5.4, 1.0, 0.0)); // Initialize Kmeans with two partitions. - ignition::math::Kmeans kmeans(obs); + gz::math::Kmeans kmeans(obs); - std::vector obsCopy; + std::vector obsCopy; obsCopy = kmeans.Observations(); for (auto &elem : obsCopy) - elem += ignition::math::Vector3d(0.1, 0.2, 0.0); + elem += gz::math::Vector3d(0.1, 0.2, 0.0); // append more observations kmeans.AppendObservations(obsCopy); // cluster - std::vector centroids; + std::vector centroids; std::vector labels; auto result = kmeans.Cluster(2, centroids, labels); diff --git a/examples/matrix3_example.cc b/examples/matrix3_example.cc index 60fd32b69..6fc3e341c 100644 --- a/examples/matrix3_example.cc +++ b/examples/matrix3_example.cc @@ -21,17 +21,17 @@ int main(int argc, char **argv) { // Construct a default matrix3. - ignition::math::Matrix3d m; + gz::math::Matrix3d m; std::cout << "The default constructed matrix m has the following values.\n\t" << m << std::endl; // Set the first column of the matrix. - m.SetCol(0, ignition::math::Vector3d(3, 4, 5)); + m.SetCol(0, gz::math::Vector3d(3, 4, 5)); std::cout << "Setting the first column of the matrix m to 3, 4, 5.\n\t" << m << std::endl; // Transpose the matrix. - ignition::math::Matrix3d t = m.Transposed(); + gz::math::Matrix3d t = m.Transposed(); std::cout << "The transposed matrix t has the values.\n\t" << t << std::endl; diff --git a/examples/matrix3_example.rb b/examples/matrix3_example.rb index 977473c36..16fbbae33 100644 --- a/examples/matrix3_example.rb +++ b/examples/matrix3_example.rb @@ -23,7 +23,7 @@ require 'ignition/math' # Construct a default matrix3. -m = Ignition::Math::Matrix3d.new +m = Gz::Math::Matrix3d.new printf("The default constructed matrix m has the following values.\n\t" + "%2.1f %2.1f %2.1f %2.1f %2.1f %2.1f %2.1f %2.1f %2.1f\n", m.(0, 0), m.(0, 1), m.(0, 2), @@ -31,7 +31,7 @@ m.(2, 0), m.(2, 1), m.(2, 2)) # Set the first column of the matrix. -m.SetCol(0, Ignition::Math::Vector3d.new(3, 4, 5)) +m.SetCol(0, Gz::Math::Vector3d.new(3, 4, 5)) printf("Setting the first column of the matrix m to 3, 4, 5.\n\t" + "%2.1f %2.1f %2.1f %2.1f %2.1f %2.1f %2.1f %2.1f %2.1f\n", m.(0, 0), m.(0, 1), m.(0, 2), diff --git a/examples/piecewise_scalar_field3_example.cc b/examples/piecewise_scalar_field3_example.cc index 1da7144f8..47bfdf92b 100644 --- a/examples/piecewise_scalar_field3_example.cc +++ b/examples/piecewise_scalar_field3_example.cc @@ -24,31 +24,31 @@ int main(int argc, char **argv) { const double kConstant = 1.; - const ignition::math::Polynomial3d xPoly( - ignition::math::Vector4d(0., 1., 0., 1.)); - const ignition::math::Polynomial3d yPoly( - ignition::math::Vector4d(1., 0., 1., 0.)); - const ignition::math::Polynomial3d zPoly( - ignition::math::Vector4d(1., 0., 0., -1.)); + const gz::math::Polynomial3d xPoly( + gz::math::Vector4d(0., 1., 0., 1.)); + const gz::math::Polynomial3d yPoly( + gz::math::Vector4d(1., 0., 1., 0.)); + const gz::math::Polynomial3d zPoly( + gz::math::Vector4d(1., 0., 0., -1.)); using AdditivelySeparableScalarField3dT = - ignition::math::AdditivelySeparableScalarField3d< - ignition::math::Polynomial3d>; + gz::math::AdditivelySeparableScalarField3d< + gz::math::Polynomial3d>; using PiecewiseScalarField3dT = - ignition::math::PiecewiseScalarField3d< + gz::math::PiecewiseScalarField3d< AdditivelySeparableScalarField3dT>; const PiecewiseScalarField3dT scalarField({ - {ignition::math::Region3d( // x < 0 halfspace - ignition::math::Intervald::Open( - -ignition::math::INF_D, 0.), - ignition::math::Intervald::Unbounded, - ignition::math::Intervald::Unbounded), + {gz::math::Region3d( // x < 0 halfspace + gz::math::Intervald::Open( + -gz::math::INF_D, 0.), + gz::math::Intervald::Unbounded, + gz::math::Intervald::Unbounded), AdditivelySeparableScalarField3dT( kConstant, xPoly, yPoly, zPoly)}, - {ignition::math::Region3d( // x >= 0 halfspace - ignition::math::Intervald::LeftClosed( - 0., ignition::math::INF_D), - ignition::math::Intervald::Unbounded, - ignition::math::Intervald::Unbounded), + {gz::math::Region3d( // x >= 0 halfspace + gz::math::Intervald::LeftClosed( + 0., gz::math::INF_D), + gz::math::Intervald::Unbounded, + gz::math::Intervald::Unbounded), AdditivelySeparableScalarField3dT( -kConstant, xPoly, yPoly, zPoly)}}); @@ -59,10 +59,10 @@ int main(int argc, char **argv) // A piecewise scalar field can be evaluated. std::cout << "Evaluating P(x, y, z) at (1, 0, 0) yields " - << scalarField(ignition::math::Vector3d::UnitX) + << scalarField(gz::math::Vector3d::UnitX) << std::endl; std::cout << "Evaluating P(x, y, z) at (-1, 0, 0) yields " - << scalarField(-ignition::math::Vector3d::UnitX) + << scalarField(-gz::math::Vector3d::UnitX) << std::endl; // A piecewise scalar field can be queried for its minimum diff --git a/examples/polynomial3_example.cc b/examples/polynomial3_example.cc index 8323c24bd..6862b5876 100644 --- a/examples/polynomial3_example.cc +++ b/examples/polynomial3_example.cc @@ -23,15 +23,15 @@ int main(int argc, char **argv) { // A default constructed polynomial should have zero coefficients. std::cout << "A default constructed polynomial is always: " - << ignition::math::Polynomial3d() << std::endl; + << gz::math::Polynomial3d() << std::endl; // A constant polynomial only has an independent term. std::cout << "A constant polynomial only has an independent term: " - << ignition::math::Polynomial3d::Constant(-1.) << std::endl; + << gz::math::Polynomial3d::Constant(-1.) << std::endl; // A cubic polynomial may be incomplete. - const ignition::math::Polynomial3d p( - ignition::math::Vector4d(1., 0., -1., 2.)); + const gz::math::Polynomial3d p( + gz::math::Vector4d(1., 0., -1., 2.)); std::cout << "A cubic polynomial may be incomplete: " << p << std::endl; // A polynomial can be evaluated. @@ -41,15 +41,15 @@ int main(int argc, char **argv) // A polynomial can be queried for its minimum in a given interval, // as well as for its global minimum (which may not always be finite). - const ignition::math::Intervald interval = - ignition::math::Intervald::Closed(-1, 1.); + const gz::math::Intervald interval = + gz::math::Intervald::Closed(-1, 1.); std::cout << "The minimum of " << p << " in the " << interval << " interval is " << p.Minimum(interval) << std::endl; std::cout << "The global minimum of " << p << " is " << p.Minimum() << std::endl; - const ignition::math::Polynomial3d q( - ignition::math::Vector4d(0., 1., 2., 1.)); + const gz::math::Polynomial3d q( + gz::math::Vector4d(0., 1., 2., 1.)); std::cout << "The minimum of " << q << " in the " << interval << " interval is " << q.Minimum(interval) << std::endl; std::cout << "The global minimum of " << q diff --git a/examples/pose3_example.cc b/examples/pose3_example.cc index 9a3d830f0..cb010eeb0 100644 --- a/examples/pose3_example.cc +++ b/examples/pose3_example.cc @@ -21,12 +21,12 @@ int main(int argc, char **argv) { // Construct a default Pose3d. - ignition::math::Pose3d p; + gz::math::Pose3d p; std::cout << "A default Pose3d has the following values\n" << p << std::endl; // Construct a pose at position 1, 2, 3 with a yaw of PI radians. - ignition::math::Pose3d p1(1, 2, 3, 0, 0, IGN_PI); + 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" << p1 << std::endl; @@ -34,7 +34,7 @@ int main(int argc, char **argv) p.Pos().Set(10, 20, 30); // Combine two poses, and store the result in a new pose - ignition::math::Pose3d p3 = p * p1; + gz::math::Pose3d p3 = p * p1; std::cout << "Result of adding two poses together is\n" << p3 << std::endl; } diff --git a/examples/pose3_example.rb b/examples/pose3_example.rb index 6e633d28a..b8465c167 100644 --- a/examples/pose3_example.rb +++ b/examples/pose3_example.rb @@ -23,13 +23,13 @@ require 'ignition/math' # Construct a default Pose3d. -p = Ignition::Math::Pose3d.new +p = Gz::Math::Pose3d.new printf("A default Pose3d has the following values\n" + "%f %f %f %f %f %f\n", p.Pos().X(), p.Pos().Y(), p.Pos().Z(), p.Rot().Euler().X(), p.Rot().Euler().Y(), p.Rot().Euler().Z()) # Construct a pose at position 1, 2, 3 with a yaw of PI radians. -p1 = Ignition::Math::Pose3d.new(1, 2, 3, 0, 0, Math::PI) +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" + "%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_example.cc b/examples/quaternion_example.cc index 682e75575..4d8399f18 100644 --- a/examples/quaternion_example.cc +++ b/examples/quaternion_example.cc @@ -21,23 +21,23 @@ int main(int argc, char **argv) { // Construct a default quaternion. - ignition::math::Quaterniond q; + gz::math::Quaterniond q; printf("A default quaternion has the following values\n" \ "\tW=%f X=%f Y=%f Z=%f\n", q.W(), q.X(), q.Y(), q.Z()); // Set the quaternion to [1, 0, 0, 0], the identity. - q = ignition::math::Quaterniond::Identity; + q = gz::math::Quaterniond::Identity; printf("The identity quaternion has the following values\n" \ "\tW=%f X=%f Y=%f Z=%f\n", q.W(), q.X(), q.Y(), q.Z()); // Create a new quaternion using Euler angles. - ignition::math::Quaterniond q2(0, 0, 3.14); + gz::math::Quaterniond q2(0, 0, 3.14); printf("A quaternion initialized from roll=0, pitch=0, and yaw=3.14 has"\ "the following values\n" \ "\tW=%f X=%f Y=%f Z=%f\n", q2.W(), q2.X(), q2.Y(), q2.Z()); // Get the Euler angles back from the quaternion. - ignition::math::Vector3d euler = q2.Euler(); + gz::math::Vector3d euler = q2.Euler(); printf("Getting back the euler angles from the quaternion\n"\ "\troll=%f pitch=%f yaw=%f\n", euler.X(), euler.Y(), euler.Z()); } diff --git a/examples/quaternion_example.rb b/examples/quaternion_example.rb index ee201739b..c093fc6f1 100644 --- a/examples/quaternion_example.rb +++ b/examples/quaternion_example.rb @@ -23,17 +23,17 @@ require 'ignition/math' # Construct a default quaternion. -q = Ignition::Math::Quaterniond.new +q = Gz::Math::Quaterniond.new printf("A default quaternion has the following values\n"+ "\tW=%f X=%f Y=%f Z=%f\n", q.W(), q.X(), q.Y(), q.Z()) # Set the quaternion to [1, 0, 0, 0], the identity. -q = Ignition::Math::Quaterniond.Identity +q = Gz::Math::Quaterniond.Identity printf("The identity quaternion has the following values\n" + "\tW=%f X=%f Y=%f Z=%f\n", q.W(), q.X(), q.Y(), q.Z()) # Create a new quaternion using Euler angles. -q2 = Ignition::Math::Quaterniond.new(0, 0, 3.14) +q2 = Gz::Math::Quaterniond.new(0, 0, 3.14) printf("A quaternion initialized from roll=0, pitch=0, and yaw=3.14 " + "has the following values\n" + "\tW=%f X=%f Y=%f Z=%f\n", q2.W(), q2.X(), q2.Y(), q2.Z()) diff --git a/examples/quaternion_from_euler.cc b/examples/quaternion_from_euler.cc index 4c1d5cb52..b1353c0b5 100644 --- a/examples/quaternion_from_euler.cc +++ b/examples/quaternion_from_euler.cc @@ -70,8 +70,8 @@ int main(int argc, char **argv) IGN_RTOD(yaw)); //![constructor] - ignition::math::Quaterniond q(roll, pitch, yaw); - ignition::math::Matrix3d m(q); + gz::math::Quaterniond q(roll, pitch, yaw); + gz::math::Matrix3d m(q); //![constructor] std::cout << "\nto Quaternion\n"; diff --git a/examples/quaternion_to_euler.cc b/examples/quaternion_to_euler.cc index eb2f18c12..42886a4bf 100644 --- a/examples/quaternion_to_euler.cc +++ b/examples/quaternion_to_euler.cc @@ -65,7 +65,7 @@ int main(int argc, char **argv) << "\n Y " << y << "\n Z " << z << std::endl; - ignition::math::Quaterniond q(w, x, y, z); + gz::math::Quaterniond q(w, x, y, z); q.Normalize(); std::cout << "to" << "\n W " << q.W() @@ -74,9 +74,9 @@ int main(int argc, char **argv) << "\n Z " << q.Z() << std::endl; - ignition::math::Matrix3d m(q); + gz::math::Matrix3d m(q); //![constructor] - ignition::math::Vector3d euler(q.Euler()); + gz::math::Vector3d euler(q.Euler()); //![constructor] std::cout << "\nConverting to Euler angles\n"; diff --git a/examples/rand_example.cc b/examples/rand_example.cc index 6374c7d42..08dbd9c11 100644 --- a/examples/rand_example.cc +++ b/examples/rand_example.cc @@ -40,11 +40,11 @@ int main(int argc, char **argv) double value; if (std::string(argv[1]) == "normal") { - value = ignition::math::Rand::DblNormal(0, 100); + value = gz::math::Rand::DblNormal(0, 100); } else if (std::string(argv[1]) == "uniform") { - value = ignition::math::Rand::DblUniform(0, 1000); + value = gz::math::Rand::DblUniform(0, 1000); } std::cout << value << std::endl; } diff --git a/examples/region3_example.cc b/examples/region3_example.cc index 92a6a78a5..97af405c7 100644 --- a/examples/region3_example.cc +++ b/examples/region3_example.cc @@ -23,26 +23,26 @@ int main(int argc, char **argv) { std::cout << std::boolalpha; - const ignition::math::Region3d defaultRegion; + const gz::math::Region3d defaultRegion; // A default constructed region should be empty. std::cout << "The " << defaultRegion << " region is empty: " << defaultRegion.Empty() << std::endl; - const ignition::math::Region3d openRegion = - ignition::math::Region3d::Open(-1., -1., -1., 1., 1., 1.); + const gz::math::Region3d openRegion = + gz::math::Region3d::Open(-1., -1., -1., 1., 1., 1.); // An open region should exclude points on its boundary. std::cout << "The " << openRegion << " region contains the " - << ignition::math::Vector3d::UnitX << " point: " - << openRegion.Contains(ignition::math::Vector3d::UnitX) + << gz::math::Vector3d::UnitX << " point: " + << openRegion.Contains(gz::math::Vector3d::UnitX) << std::endl; - const ignition::math::Region3d closedRegion = - ignition::math::Region3d::Closed(0., 0., 0., 1., 1., 1.); + const gz::math::Region3d closedRegion = + gz::math::Region3d::Closed(0., 0., 0., 1., 1., 1.); // A closed region should include points on its boundary. std::cout << "The " << closedRegion << " region contains the " - << ignition::math::Vector3d::UnitX << " point: " - << closedRegion.Contains(ignition::math::Vector3d::UnitX) + << gz::math::Vector3d::UnitX << " point: " + << closedRegion.Contains(gz::math::Vector3d::UnitX) << std::endl; // Closed and open regions may intersect. @@ -51,10 +51,10 @@ int main(int argc, char **argv) << std::endl; // The unbounded region should include all non-empty regions. - std::cout << "The " << ignition::math::Region3d::Unbounded + std::cout << "The " << gz::math::Region3d::Unbounded << " region contains all previous non-empty intervals: " - << (ignition::math::Region3d::Unbounded.Contains(openRegion) || - ignition::math::Region3d::Unbounded.Contains(closedRegion)) + << (gz::math::Region3d::Unbounded.Contains(openRegion) || + gz::math::Region3d::Unbounded.Contains(closedRegion)) << std::endl; } diff --git a/examples/temperature_example.cc b/examples/temperature_example.cc index 9c6892b80..c5157a6e7 100644 --- a/examples/temperature_example.cc +++ b/examples/temperature_example.cc @@ -21,17 +21,17 @@ int main(int argc, char **argv) { /// Convert from Kelvin to Celsius - double celsius = ignition::math::Temperature::KelvinToCelsius(2.5); + double celsius = gz::math::Temperature::KelvinToCelsius(2.5); printf("2.5Kelvin to Celsius is %f\n", celsius); - ignition::math::Temperature temp(123.5); + gz::math::Temperature temp(123.5); printf("Constructed a Temperature object with %f Kelvin\n", temp()); printf("Same temperature in Celsius %f\n", temp.Celsius()); temp += 100.0; printf("Temperature + 100.0 is %fK\n", temp()); - ignition::math::Temperature newTemp(temp); + gz::math::Temperature newTemp(temp); newTemp += temp + 23.5; printf("Copied the temp object and added 23.5K. The new tempurature is %fF\n", newTemp.Fahrenheit()); diff --git a/examples/temperature_example.rb b/examples/temperature_example.rb index fd0435d3f..7ae6ccc6c 100644 --- a/examples/temperature_example.rb +++ b/examples/temperature_example.rb @@ -22,10 +22,10 @@ # require 'ignition/math' -celsius = Ignition::Math::Temperature::KelvinToCelsius(2.5); +celsius = Gz::Math::Temperature::KelvinToCelsius(2.5); printf("2.5Kelvin to Celsius is %f\n", celsius) -temp = Ignition::Math::Temperature.new(123.5) +temp = Gz::Math::Temperature.new(123.5) printf("Constructed a Temperature object with %f Kelvin\n", temp.Kelvin()) @@ -34,7 +34,7 @@ temp += 100.0 printf("Temperature + 100.0 is %fK", temp.Kelvin()) -newTemp = Ignition::Math::Temperature.new(temp.Kelvin()) +newTemp = Gz::Math::Temperature.new(temp.Kelvin()) newTemp += temp + 23.5; printf("Copied temp and added 23.5K. The new tempurature is %fF\n", newTemp.Fahrenheit()); diff --git a/examples/triangle_example.cc b/examples/triangle_example.cc index e8e4acd06..d59948e0d 100644 --- a/examples/triangle_example.cc +++ b/examples/triangle_example.cc @@ -25,10 +25,10 @@ int main(int argc, char **argv) // 2: x = 0, y = 1 // 3: x = 1, y = 0 //! [constructor] - ignition::math::Triangled tri( - ignition::math::Vector2d(-1, 0), - ignition::math::Vector2d(0, 1), - ignition::math::Vector2d(1, 0)); + gz::math::Triangled tri( + gz::math::Vector2d(-1, 0), + gz::math::Vector2d(0, 1), + gz::math::Vector2d(1, 0)); //! [constructor] // The individual vertices are accessible through the [] operator @@ -48,16 +48,16 @@ int main(int argc, char **argv) // It's also possible to set each vertex individually. //! [vertex1] - tri.Set(0, ignition::math::Vector2d(-10, 0)); - tri.Set(1, ignition::math::Vector2d(0, 20)); - tri.Set(2, ignition::math::Vector2d(10, 2)); + tri.Set(0, gz::math::Vector2d(-10, 0)); + tri.Set(1, gz::math::Vector2d(0, 20)); + tri.Set(2, gz::math::Vector2d(10, 2)); //! [vertex1] // Or set all the vertices at once. //! [vertex2] - tri.Set(ignition::math::Vector2d(-1, 0), - ignition::math::Vector2d(0, 1), - ignition::math::Vector2d(1, 0)); + tri.Set(gz::math::Vector2d(-1, 0), + gz::math::Vector2d(0, 1), + gz::math::Vector2d(1, 0)); //! [vertex2] // You can get the perimeter length and area of the triangle @@ -68,7 +68,7 @@ int main(int argc, char **argv) // The Contains functions check if a line or point is inside the triangle //! [contains] - if (tri.Contains(ignition::math::Vector2d(0, 0.5))) + if (tri.Contains(gz::math::Vector2d(0, 0.5))) std::cout << "Triangle contains the point 0, 0.5\n"; else std::cout << "Triangle does not contain the point 0, 0.5\n"; @@ -77,8 +77,8 @@ int main(int argc, char **argv) // The Intersect function check if a line segment intersects the triangle. // It also returns the points of intersection //! [intersect] - ignition::math::Vector2d pt1, pt2; - if (tri.Intersects(ignition::math::Line2d(-2, 0.5, 2, 0.5), pt1, pt2)) + gz::math::Vector2d pt1, pt2; + if (tri.Intersects(gz::math::Line2d(-2, 0.5, 2, 0.5), pt1, pt2)) { std::cout << "A line from (-2, 0.5) to (2, 0.5) intersects " << "the triangle at the\nfollowing points:\n" @@ -93,5 +93,5 @@ int main(int argc, char **argv) //! [intersect] // There are more functions in Triangle. Take a look at the API; - // http://ignitionrobotics.org/libraries/ign_mat/api + // http://gazebosim.org/libraries/ign_mat/api } diff --git a/examples/vector2_example.cc b/examples/vector2_example.cc index 3238135b0..e6f9df1d1 100644 --- a/examples/vector2_example.cc +++ b/examples/vector2_example.cc @@ -24,14 +24,14 @@ int main(int argc, char **argv) // The initial x any y values are zero.\n\n"; // The x and y component of vec2 can be set at anytime. //! [constructor] - ignition::math::Vector2d vec2; + gz::math::Vector2d vec2; vec2.Set(2.0, 4.0); //! [constructor] // The Vector2 class is a template, so you can also create a Vector2 using - // ignition::math::Vector2 + // gz::math::Vector2 //! [constructor2] - ignition::math::Vector2 vec2a; + gz::math::Vector2 vec2a; vec2a.Set(1.0, 2.0); //! [constructor2] @@ -39,7 +39,7 @@ int main(int argc, char **argv) // It's also possible to set initial values. This time we are using // a Vector2 of floats //! [constructor3] - ignition::math::Vector2f vec2b(1.2f, 3.4f); + gz::math::Vector2f vec2b(1.2f, 3.4f); //! [constructor3] // We can output the contents of each vector using std::cout @@ -75,6 +75,6 @@ int main(int argc, char **argv) //! [distance] // There are more functions in Vector2. Take a look at the API: - // https://ignitionrobotics.org/libs/math + // https://gazebosim.org/libs/math } //! [complete] diff --git a/examples/vector2_example.rb b/examples/vector2_example.rb index bc5b1e4d1..c722f7b27 100644 --- a/examples/vector2_example.rb +++ b/examples/vector2_example.rb @@ -22,9 +22,9 @@ # require 'ignition/math' -va = Ignition::Math::Vector2d.new(1, 2) -vb = Ignition::Math::Vector2d.new(3, 4) -vc = Ignition::Math::Vector2d.new(vb) +va = Gz::Math::Vector2d.new(1, 2) +vb = Gz::Math::Vector2d.new(3, 4) +vc = Gz::Math::Vector2d.new(vb) printf("va = %f %f\n", va.X(), va.Y()) printf("vb = %f %f\n", vb.X(), vb.Y()) diff --git a/examples/vector3_example.rb b/examples/vector3_example.rb index ca0c9ca2e..343807f6e 100644 --- a/examples/vector3_example.rb +++ b/examples/vector3_example.rb @@ -22,10 +22,10 @@ # require 'ignition/math' -v1 = Ignition::Math::Vector3d.new(0, 0, 0) +v1 = Gz::Math::Vector3d.new(0, 0, 0) printf("v =: %f %f %f\n", v1.X(), v1.Y(), v1.Z()) -v2 = Ignition::Math::Vector3d.new(1, 0, 0) +v2 = Gz::Math::Vector3d.new(1, 0, 0) printf("v2 = %f %f %f\n", v2.X(), v2.Y(), v2.Z()) v3 = v1 + v2 diff --git a/include/gz/math/AdditivelySeparableScalarField3.hh b/include/gz/math/AdditivelySeparableScalarField3.hh index 6ddf17cfb..e3c31bd3f 100644 --- a/include/gz/math/AdditivelySeparableScalarField3.hh +++ b/include/gz/math/AdditivelySeparableScalarField3.hh @@ -24,12 +24,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /** \class AdditivelySeparableScalarField3\ * AdditivelySeparableScalarField3.hh\ @@ -145,7 +145,7 @@ namespace ignition /// \return the stream public: friend std::ostream &operator<<( std::ostream &_out, - const ignition::math::AdditivelySeparableScalarField3< + const gz::math::AdditivelySeparableScalarField3< ScalarFunctionT, ScalarT> &_field) { using std::abs; // enable ADL diff --git a/include/gz/math/Angle.hh b/include/gz/math/Angle.hh index 3348f7dd3..2025c03af 100644 --- a/include/gz/math/Angle.hh +++ b/include/gz/math/Angle.hh @@ -40,12 +40,12 @@ /// \return the angle, in range #define IGN_NORMALIZE(a) (atan2(sin(a), cos(a))) -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Angle Angle.hh gz/math/Angle.hh /// \brief The Angle class is used to simplify and clarify the use of @@ -59,7 +59,7 @@ namespace ignition /// ## Example /// /// \snippet examples/angle_example.cc complete - class IGNITION_MATH_VISIBLE Angle + class GZ_MATH_VISIBLE Angle { /// \brief An angle with a value of zero. /// Equivalent to math::Angle(0). @@ -99,7 +99,7 @@ namespace ignition /// \brief Set the value from an angle in radians. /// \param[in] _radian Radian value. /// \deprecated Use void SetRadian(double) - public: void IGN_DEPRECATED(7) Radian(double _radian); + public: void GZ_DEPRECATED(7) Radian(double _radian); /// \brief Set the value from an angle in radians. /// \param[in] _radian Radian value. @@ -108,7 +108,7 @@ namespace ignition /// \brief Set the value from an angle in degrees /// \param[in] _degree Degree value /// \deprecated Use void SetDegree(double) - public: void IGN_DEPRECATED(7) Degree(double _degree); + public: void GZ_DEPRECATED(7) Degree(double _degree); /// \brief Set the value from an angle in degrees /// \param[in] _degree Degree value @@ -218,7 +218,7 @@ namespace ignition /// \param[in] _a Angle to output. /// \return The output stream. public: friend std::ostream &operator<<(std::ostream &_out, - const ignition::math::Angle &_a) + const gz::math::Angle &_a) { _out << _a.Radian(); return _out; @@ -229,7 +229,7 @@ namespace ignition /// \param[out] _a Angle to read value into. /// \return The input stream. public: friend std::istream &operator>>(std::istream &_in, - ignition::math::Angle &_a) + gz::math::Angle &_a) { // Skip white spaces _in.setf(std::ios_base::skipws); diff --git a/include/gz/math/AxisAlignedBox.hh b/include/gz/math/AxisAlignedBox.hh index a59bc5f04..7609c75f1 100644 --- a/include/gz/math/AxisAlignedBox.hh +++ b/include/gz/math/AxisAlignedBox.hh @@ -27,16 +27,16 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { /// \class AxisAlignedBox AxisAlignedBox.hh gz/math/AxisAlignedBox.hh /// \brief Mathematical representation of a box that is aligned along /// an X,Y,Z axis. - class IGNITION_MATH_VISIBLE AxisAlignedBox + class GZ_MATH_VISIBLE AxisAlignedBox { /// \brief Default constructor. This constructor will set the box's /// minimum and maximum corners to the highest (max) and lowest @@ -132,7 +132,7 @@ namespace ignition /// \param[in] _b AxisAlignedBox to output to the stream /// \return The stream public: friend std::ostream &operator<<(std::ostream &_out, - const ignition::math::AxisAlignedBox &_b) + const gz::math::AxisAlignedBox &_b) { _out << "Min[" << _b.Min() << "] Max[" << _b.Max() << "]"; return _out; diff --git a/include/gz/math/Box.hh b/include/gz/math/Box.hh index c0f8e69fb..9412ca800 100644 --- a/include/gz/math/Box.hh +++ b/include/gz/math/Box.hh @@ -27,12 +27,12 @@ #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { /// \brief This is the type used for deduplicating and returning the set of /// intersections. template @@ -68,7 +68,7 @@ namespace ignition /// \param[in] _mat Material property for the box. public: Box(const Precision _length, const Precision _width, const Precision _height, - const ignition::math::Material &_mat); + const gz::math::Material &_mat); /// \brief Construct a box with specified dimensions, in vector form. /// \param[in] _size Size of the box. The vector _size has the following @@ -89,7 +89,7 @@ namespace ignition /// * _size[2] == height in meters /// \param[in] _mat Material property for the box. public: Box(const Vector3 &_size, - const ignition::math::Material &_mat); + const gz::math::Material &_mat); /// \brief Get the size of the box. /// \return Size of the box in meters. @@ -124,11 +124,11 @@ namespace ignition /// \brief Get the material associated with this box. /// \return The material assigned to this box. - public: const ignition::math::Material &Material() const; + public: const gz::math::Material &Material() const; /// \brief Set the material associated with this box. /// \param[in] _mat The material assigned to this box. - public: void SetMaterial(const ignition::math::Material &_mat); + public: void SetMaterial(const gz::math::Material &_mat); /// \brief Get the volume of the box in m^3. /// \return Volume of the box in m^3. @@ -201,7 +201,7 @@ namespace ignition private: Vector3 size = Vector3::Zero; /// \brief The box's material. - private: ignition::math::Material material; + private: gz::math::Material material; }; /// \typedef Box Boxi diff --git a/include/gz/math/Capsule.hh b/include/gz/math/Capsule.hh index 513f8f743..960f22a68 100644 --- a/include/gz/math/Capsule.hh +++ b/include/gz/math/Capsule.hh @@ -21,7 +21,7 @@ #include "gz/math/MassMatrix3.hh" #include "gz/math/Material.hh" -namespace ignition +namespace gz { namespace math { @@ -29,7 +29,7 @@ namespace ignition class CapsulePrivate; // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Capsule Capsule.hh gz/math/Capsule.hh /// \brief A representation of a capsule or sphere-capped cylinder. diff --git a/include/gz/math/Color.hh b/include/gz/math/Color.hh index fd4355d83..22d8c92fd 100644 --- a/include/gz/math/Color.hh +++ b/include/gz/math/Color.hh @@ -25,12 +25,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Color Color.hh gz/math/Color.hh /// \brief Defines a color using a red (R), green (G), blue (B), and alpha @@ -39,7 +39,7 @@ namespace ignition /// ## Example /// /// \snippet examples/color_example.cc complete - class IGNITION_MATH_VISIBLE Color + class GZ_MATH_VISIBLE Color { /// \brief (1, 1, 1) public: static const Color &White; diff --git a/include/gz/math/Cylinder.hh b/include/gz/math/Cylinder.hh index 69e6d88d3..fe3cae477 100644 --- a/include/gz/math/Cylinder.hh +++ b/include/gz/math/Cylinder.hh @@ -21,7 +21,7 @@ #include "gz/math/Material.hh" #include "gz/math/Quaternion.hh" -namespace ignition +namespace gz { namespace math { @@ -29,7 +29,7 @@ namespace ignition class CylinderPrivate; // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Cylinder Cylinder.hh gz/math/Cylinder.hh /// \brief A representation of a cylinder. diff --git a/include/gz/math/DiffDriveOdometry.hh b/include/gz/math/DiffDriveOdometry.hh index 398358a85..26efd9fbe 100644 --- a/include/gz/math/DiffDriveOdometry.hh +++ b/include/gz/math/DiffDriveOdometry.hh @@ -23,7 +23,7 @@ #include #include -namespace ignition +namespace gz { namespace math { @@ -31,7 +31,7 @@ namespace ignition using clock = std::chrono::steady_clock; // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { /** \class DiffDriveOdometry DiffDriveOdometry.hh \ * gz/math/DiffDriveOdometry.hh **/ @@ -60,7 +60,7 @@ namespace ignition /// **Example Usage** /// /// \code{.cpp} - /// ignition::math::DiffDriveOdometry odom; + /// gz::math::DiffDriveOdometry odom; /// odom.SetWheelParams(2.0, 0.5, 0.5); /// odom.Init(std::chrono::steady_clock::now()); /// @@ -74,7 +74,7 @@ namespace ignition /// // The left wheel has rotated, the right wheel did not rotate /// odom.Update(IGN_DTOR(4), IGN_DTOR(2), std::chrono::steady_clock::now()); /// \endcode - class IGNITION_MATH_VISIBLE DiffDriveOdometry + class GZ_MATH_VISIBLE DiffDriveOdometry { /// \brief Constructor. /// \param[in] _windowSize Rolling window size used to compute the diff --git a/include/gz/math/Ellipsoid.hh b/include/gz/math/Ellipsoid.hh index a2e2a1e52..867091ca3 100644 --- a/include/gz/math/Ellipsoid.hh +++ b/include/gz/math/Ellipsoid.hh @@ -21,12 +21,12 @@ #include "gz/math/MassMatrix3.hh" #include "gz/math/Material.hh" -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Ellipsoid Ellipsoid.hh gz/math/Ellipsoid.hh /// \brief A representation of a general ellipsoid. diff --git a/include/gz/math/Filter.hh b/include/gz/math/Filter.hh index 5e35befd2..bf81484ee 100644 --- a/include/gz/math/Filter.hh +++ b/include/gz/math/Filter.hh @@ -22,12 +22,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Filter Filter.hh gz/math/Filter.hh /// \brief Filter base class diff --git a/include/gz/math/Frustum.hh b/include/gz/math/Frustum.hh index 4a4884fee..7b715d91c 100644 --- a/include/gz/math/Frustum.hh +++ b/include/gz/math/Frustum.hh @@ -24,16 +24,16 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { /// \brief Mathematical representation of a frustum and related functions. /// This is also known as a view frustum. - class IGNITION_MATH_VISIBLE Frustum + class GZ_MATH_VISIBLE Frustum { /// \brief Planes that define the boundaries of the frustum. public: enum FrustumPlane diff --git a/include/gz/math/GaussMarkovProcess.hh b/include/gz/math/GaussMarkovProcess.hh index 83173ef71..51e62e5b0 100644 --- a/include/gz/math/GaussMarkovProcess.hh +++ b/include/gz/math/GaussMarkovProcess.hh @@ -22,7 +22,7 @@ #include #include -namespace ignition +namespace gz { namespace math { @@ -30,7 +30,7 @@ namespace ignition using clock = std::chrono::steady_clock; // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { /** \class GaussMarkovProcess GaussMarkovProcess.hh\ * gz/math/GaussMarkovProcess.hh **/ @@ -43,7 +43,7 @@ namespace ignition /// ## Example usage /// /// \snippet examples/gauss_markov_process_example.cc complete - class IGNITION_MATH_VISIBLE GaussMarkovProcess + class GZ_MATH_VISIBLE GaussMarkovProcess { // Default constructor. This sets all the parameters to zero. public: GaussMarkovProcess(); diff --git a/include/gz/math/Helpers.hh b/include/gz/math/Helpers.hh index 85de8b08d..401fc1016 100644 --- a/include/gz/math/Helpers.hh +++ b/include/gz/math/Helpers.hh @@ -79,13 +79,13 @@ constexpr T IGN_MASSMATRIX3_DEFAULT_TOLERANCE = T(10); /// \param[in] _v Vector3d that contains the box's dimensions. #define IGN_BOX_VOLUME_V(_v) (_v.X() *_v.Y() * _v.Z()) -namespace ignition +namespace gz { /// \brief Math classes and function useful in robot applications. namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \brief size_t type with a value of 0 static const size_t IGN_ZERO_SIZE_T = 0u; @@ -466,7 +466,7 @@ namespace ignition /// \param[in] _precision Precision for floating point numbers. /// \deprecated Use appendToStream(std::ostream, T) instead. template - inline void IGN_DEPRECATED(7) appendToStream( + inline void GZ_DEPRECATED(7) appendToStream( std::ostream &_out, T _number, int _precision) { if (std::fpclassify(_number) == FP_ZERO) @@ -485,7 +485,7 @@ namespace ignition /// _precision Not used for int. /// \deprecated Use appendToStream(std::ostream, int) instead. template<> - inline void IGN_DEPRECATED(7) appendToStream( + inline void GZ_DEPRECATED(7) appendToStream( std::ostream &_out, int _number, int) { _out << _number; @@ -714,13 +714,13 @@ namespace ignition /// \brief Convert a std::chrono::steady_clock::time_point to a string /// \param[in] _point The std::chrono::steady_clock::time_point to convert. /// \return A string formatted with the time_point - std::string IGNITION_MATH_VISIBLE timePointToString( + std::string GZ_MATH_VISIBLE timePointToString( const std::chrono::steady_clock::time_point &_point); /// \brief Convert a std::chrono::steady_clock::duration to a string /// \param[in] _duration The std::chrono::steady_clock::duration to convert. /// \return A string formatted with the duration - std::string IGNITION_MATH_VISIBLE durationToString( + std::string GZ_MATH_VISIBLE durationToString( const std::chrono::steady_clock::duration &_duration); /// \brief Check if the given string represents a time. @@ -800,7 +800,7 @@ namespace ignition /// \param[out] numberSeconds number of seconds in the string /// \param[out] numberMilliseconds number of milliseconds in the string /// \return True if the regex was able to split the string otherwise False - bool IGNITION_MATH_VISIBLE splitTimeBasedOnTimeRegex( + bool GZ_MATH_VISIBLE splitTimeBasedOnTimeRegex( const std::string &_timeString, uint64_t & numberDays, uint64_t & numberHours, uint64_t & numberMinutes, uint64_t & numberSeconds, @@ -812,7 +812,7 @@ namespace ignition /// \return A std::chrono::steady_clock::duration containing the /// string's time value. If it isn't possible to convert, the duration will /// be zero. - std::chrono::steady_clock::duration IGNITION_MATH_VISIBLE stringToDuration( + std::chrono::steady_clock::duration GZ_MATH_VISIBLE stringToDuration( const std::string &_timeString); /// \brief Convert a string to a std::chrono::steady_clock::time_point @@ -822,7 +822,7 @@ namespace ignition /// string's time value. If it isn't possible to convert, the time will /// be negative 1 second. std::chrono::steady_clock::time_point - IGNITION_MATH_VISIBLE stringToTimePoint(const std::string &_timeString); + GZ_MATH_VISIBLE stringToTimePoint(const std::string &_timeString); // Degrade precision on Windows, which cannot handle 'long double' // values properly. See the implementation of Unpair. @@ -845,7 +845,7 @@ namespace ignition /// \return A unique non-negative integer value. On Windows the return /// value is uint32_t. On Linux/OSX the return value is uint64_t /// \sa Unpair - PairOutput IGNITION_MATH_VISIBLE Pair( + PairOutput GZ_MATH_VISIBLE Pair( const PairInput _a, const PairInput _b); /// \brief The reverse of the Pair function. Accepts a key, produced @@ -859,7 +859,7 @@ namespace ignition /// tuple contains two uint16_t values. On Linux/OSX the tuple contains /// two uint32_t values. /// \sa Pair - std::tuple IGNITION_MATH_VISIBLE Unpair( + std::tuple GZ_MATH_VISIBLE Unpair( const PairOutput _key); } } diff --git a/include/gz/math/Inertial.hh b/include/gz/math/Inertial.hh index 31a01f6dc..232fb9354 100644 --- a/include/gz/math/Inertial.hh +++ b/include/gz/math/Inertial.hh @@ -21,12 +21,12 @@ #include "gz/math/MassMatrix3.hh" #include "gz/math/Pose3.hh" -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Inertial Inertial.hh gz/math/Inertial.hh /// \brief The Inertial object provides a representation for the mass and diff --git a/include/gz/math/Interval.hh b/include/gz/math/Interval.hh index c804887f1..a3f8ae9fc 100644 --- a/include/gz/math/Interval.hh +++ b/include/gz/math/Interval.hh @@ -25,12 +25,12 @@ #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Interval Interval.hh gz/math/Interval.hh /// \brief The Interval class represents a range of real numbers. @@ -264,7 +264,7 @@ namespace ignition /// \param _interval Interval to output /// \return the stream public: friend std::ostream &operator<<( - std::ostream &_out, const ignition::math::Interval &_interval) + std::ostream &_out, const gz::math::Interval &_interval) { return _out << (_interval.leftClosed ? "[" : "(") << _interval.leftValue << ", " << _interval.rightValue diff --git a/include/gz/math/Kmeans.hh b/include/gz/math/Kmeans.hh index 438a2af5a..ff93ea53d 100644 --- a/include/gz/math/Kmeans.hh +++ b/include/gz/math/Kmeans.hh @@ -24,19 +24,19 @@ #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { /// \class Kmeans Kmeans.hh math/gzmath.hh /// \brief K-Means clustering algorithm. Given a set of observations, /// k-means partitions the observations into k sets so as to minimize the /// within-cluster sum of squares. /// Description based on http://en.wikipedia.org/wiki/K-means_clustering. - class IGNITION_MATH_VISIBLE Kmeans + class GZ_MATH_VISIBLE Kmeans { /// \brief constructor /// \param[in] _obs Set of observations to cluster. diff --git a/include/gz/math/Line2.hh b/include/gz/math/Line2.hh index a7203916f..0b2e87b83 100644 --- a/include/gz/math/Line2.hh +++ b/include/gz/math/Line2.hh @@ -21,12 +21,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Line2 Line2.hh gz/math/Line2.hh /// \brief A two dimensional line segment. The line is defined by a diff --git a/include/gz/math/Line3.hh b/include/gz/math/Line3.hh index 911c29e59..233bb41a6 100644 --- a/include/gz/math/Line3.hh +++ b/include/gz/math/Line3.hh @@ -21,12 +21,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Line3 Line3.hh gz/math/Line3.hh /// \brief A three dimensional line segment. The line is defined by a diff --git a/include/gz/math/MassMatrix3.hh b/include/gz/math/MassMatrix3.hh index 6559dd20c..e629a0b0a 100644 --- a/include/gz/math/MassMatrix3.hh +++ b/include/gz/math/MassMatrix3.hh @@ -30,12 +30,12 @@ #include "gz/math/Vector3.hh" #include "gz/math/Matrix3.hh" -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class MassMatrix3 MassMatrix3.hh gz/math/MassMatrix3.hh /// \brief A class for inertial information about a rigid body diff --git a/include/gz/math/Material.hh b/include/gz/math/Material.hh index 7fd6a82a2..e3e2f8ac7 100644 --- a/include/gz/math/Material.hh +++ b/include/gz/math/Material.hh @@ -25,12 +25,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { /// \brief Contains information about a single material. /// @@ -40,8 +40,8 @@ namespace ignition /// enum. /// /// This class will replace the - /// [MaterialDensity class](https://github.com/ignitionrobotics/ign-common/blob/ign-common1/include/gz/common/MaterialDensity.hh) - /// found in the Ignition Common library, which was at version 1 at the + /// [MaterialDensity class](https://github.com/gazebosim/gz-common/blob/main/include/gz/common/MaterialDensity.hh) + /// found in the Gazebo Common library, which was at version 1 at the /// time of this writing. /// /// **How to create a wood material:** @@ -61,7 +61,7 @@ namespace ignition /// std::cout << "The density of " << mat.Name() is " /// << mat.Density() << std::endl; /// ~~~ - class IGNITION_MATH_VISIBLE Material + class GZ_MATH_VISIBLE Material { /// \brief Constructor. public: Material(); diff --git a/include/gz/math/MaterialType.hh b/include/gz/math/MaterialType.hh index 5a1355252..31fadb585 100644 --- a/include/gz/math/MaterialType.hh +++ b/include/gz/math/MaterialType.hh @@ -20,12 +20,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \enum MaterialType /// \brief This enum lists the supported material types. A value can be diff --git a/include/gz/math/Matrix3.hh b/include/gz/math/Matrix3.hh index 680d88f7b..2904b2441 100644 --- a/include/gz/math/Matrix3.hh +++ b/include/gz/math/Matrix3.hh @@ -25,12 +25,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // template class Quaternion; @@ -58,7 +58,7 @@ namespace ignition /// require 'gz/math' /// /// # Construct a default matrix3. - /// m = Ignition::Math::Matrix3d.new + /// m = Gz::Math::Matrix3d.new /// printf("The default constructed matrix m has the following "+ /// "values.\n\t" + /// "%2.1f %2.1f %2.1f %2.1f %2.1f %2.1f %2.1f %2.1f %2.1f\n", @@ -67,7 +67,7 @@ namespace ignition /// m.(2, 0), m.(2, 1), m.(2, 2)) /// /// # Set the first column of the matrix. - /// m.SetCol(0, Ignition::Math::Vector3d.new(3, 4, 5)) + /// m.SetCol(0, Gz::Math::Vector3d.new(3, 4, 5)) /// printf("Setting the first column of the matrix m to 3, 4, 5.\n\t" + /// "%2.1f %2.1f %2.1f %2.1f %2.1f %2.1f %2.1f %2.1f %2.1f\n", /// m.(0, 0), m.(0, 1), m.(0, 2), @@ -191,7 +191,7 @@ namespace ignition /// \param[in] _zAxis The z axis, the third column of the matrix. /// \deprecated Use SetAxes(const Vector3 &, const Vector3 &, /// const Vector3 &,) - public: void IGN_DEPRECATED(7) Axes(const Vector3 &_xAxis, + public: void GZ_DEPRECATED(7) Axes(const Vector3 &_xAxis, const Vector3 &_yAxis, const Vector3 &_zAxis) { @@ -215,7 +215,7 @@ namespace ignition /// \param[in] _axis the axis /// \param[in] _angle ccw rotation around the axis in radians /// \deprecated Use SetFromAxisAngle(const Vector3 &, T) - public: void IGN_DEPRECATED(7) Axis(const Vector3 &_axis, T _angle) + public: void GZ_DEPRECATED(7) Axis(const Vector3 &_axis, T _angle) { this->SetFromAxisAngle(_axis, _angle); } @@ -249,7 +249,7 @@ namespace ignition /// \param[in] _v1 The first vector /// \param[in] _v2 The second vector /// \deprecated Use SetFrom2Axes(const Vector3 &, const Vector3 &) - public: void IGN_DEPRECATED(7) From2Axes( + public: void GZ_DEPRECATED(7) From2Axes( const Vector3 &_v1, const Vector3 &_v2) { this->SetFrom2Axes(_v1, _v2); @@ -303,7 +303,7 @@ namespace ignition /// range [0, 2]. /// \param[in] _v The value to set in each row of the column. /// \deprecated Use SetCol(unsigned int _c, const Vector3 &_v) - public: void IGN_DEPRECATED(7) Col(unsigned int _c, const Vector3 &_v) + public: void GZ_DEPRECATED(7) Col(unsigned int _c, const Vector3 &_v) { this->SetCol(_c, _v); } @@ -595,7 +595,7 @@ namespace ignition /// \param[in] _m Matrix to output. /// \return The stream. public: friend std::ostream &operator<<( - std::ostream &_out, const ignition::math::Matrix3 &_m) + std::ostream &_out, const gz::math::Matrix3 &_m) { for (auto i : {0, 1, 2}) { @@ -617,7 +617,7 @@ namespace ignition /// \param [out] _m Matrix3 to read values into. /// \return The stream. public: friend std::istream &operator>>( - std::istream &_in, ignition::math::Matrix3 &_m) + std::istream &_in, gz::math::Matrix3 &_m) { // Skip white spaces _in.setf(std::ios_base::skipws); diff --git a/include/gz/math/Matrix4.hh b/include/gz/math/Matrix4.hh index 5a6b6b2f1..13ffc592f 100644 --- a/include/gz/math/Matrix4.hh +++ b/include/gz/math/Matrix4.hh @@ -25,12 +25,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Matrix4 Matrix4.hh gz/math/Matrix4.hh /// \brief A 4x4 matrix class @@ -750,7 +750,7 @@ namespace ignition /// \param _m Matrix to output /// \return the stream public: friend std::ostream &operator<<( - std::ostream &_out, const ignition::math::Matrix4 &_m) + std::ostream &_out, const gz::math::Matrix4 &_m) { for (auto i : {0, 1, 2, 3}) { @@ -771,7 +771,7 @@ namespace ignition /// \param[out] _m Matrix4 to read values into /// \return the stream public: friend std::istream &operator>>( - std::istream &_in, ignition::math::Matrix4 &_m) + std::istream &_in, gz::math::Matrix4 &_m) { // Skip white spaces _in.setf(std::ios_base::skipws); diff --git a/include/gz/math/MovingWindowFilter.hh b/include/gz/math/MovingWindowFilter.hh index a0d6be5f3..1082cd09c 100644 --- a/include/gz/math/MovingWindowFilter.hh +++ b/include/gz/math/MovingWindowFilter.hh @@ -21,12 +21,12 @@ #include #include "gz/math/Export.hh" -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \cond @@ -66,7 +66,7 @@ namespace ignition /// \endcond /// \brief Base class for MovingWindowFilter. This replaces the - /// version of MovingWindowFilter in the Ignition Common library. + /// version of MovingWindowFilter in the Gazebo Common library. /// /// The default window size is 4. template< typename T> diff --git a/include/gz/math/OrientedBox.hh b/include/gz/math/OrientedBox.hh index 63795c4ff..367643943 100644 --- a/include/gz/math/OrientedBox.hh +++ b/include/gz/math/OrientedBox.hh @@ -26,12 +26,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \brief Mathematical representation of a box which can be arbitrarily /// positioned and rotated. @@ -190,14 +190,14 @@ namespace ignition /// \brief Get the material associated with this box. /// \return The material assigned to this box. - public: const ignition::math::Material &Material() const + public: const gz::math::Material &Material() const { return this->material; } /// \brief Set the material associated with this box. /// \param[in] _mat The material assigned to this box. - public: void SetMaterial(const ignition::math::Material &_mat) + public: void SetMaterial(const gz::math::Material &_mat) { this->material = _mat; } @@ -263,7 +263,7 @@ namespace ignition private: Pose3 pose; /// \brief The box's material. - private: ignition::math::Material material; + private: gz::math::Material material; }; typedef OrientedBox OrientedBoxd; diff --git a/include/gz/math/PID.hh b/include/gz/math/PID.hh index e913d2beb..7092cc77f 100644 --- a/include/gz/math/PID.hh +++ b/include/gz/math/PID.hh @@ -22,12 +22,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class PID PID.hh gz/math/PID.hh /// \brief Generic PID controller class. @@ -36,7 +36,7 @@ namespace ignition /// the state of a system and a user specified target state. /// It includes a user-adjustable command offset term (feed-forward). // cppcheck-suppress class_X_Y - class IGNITION_MATH_VISIBLE PID + class GZ_MATH_VISIBLE PID { /// \brief Constructor, zeros out Pid values when created and /// initialize Pid-gains and integral term limits:[iMax:iMin]-[I1:I2]. diff --git a/include/gz/math/PiecewiseScalarField3.hh b/include/gz/math/PiecewiseScalarField3.hh index 615a1e733..993d87e3f 100644 --- a/include/gz/math/PiecewiseScalarField3.hh +++ b/include/gz/math/PiecewiseScalarField3.hh @@ -27,12 +27,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /** \class PiecewiseScalarField3 PiecewiseScalarField3.hh\ * gz/math/PiecewiseScalarField3.hh @@ -187,7 +187,7 @@ namespace ignition /// \return the stream public: friend std::ostream &operator<<( std::ostream &_out, - const ignition::math::PiecewiseScalarField3< + const gz::math::PiecewiseScalarField3< ScalarField3T, ScalarT> &_field) { if (_field.pieces.empty()) diff --git a/include/gz/math/Plane.hh b/include/gz/math/Plane.hh index e5d547527..908dc238f 100644 --- a/include/gz/math/Plane.hh +++ b/include/gz/math/Plane.hh @@ -25,12 +25,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Plane Plane.hh gz/math/Plane.hh /// \brief A plane and related functions. diff --git a/include/gz/math/Polynomial3.hh b/include/gz/math/Polynomial3.hh index 2eea5ae32..ac64439d4 100644 --- a/include/gz/math/Polynomial3.hh +++ b/include/gz/math/Polynomial3.hh @@ -27,12 +27,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Polynomial3 Polynomial3.hh gz/math/Polynomial3.hh /// \brief The Polynomial3 class represents a cubic polynomial @@ -277,7 +277,7 @@ namespace ignition /// \param _p Polynomial3 to output /// \return the stream public: friend std::ostream &operator<<( - std::ostream &_out, const ignition::math::Polynomial3 &_p) + std::ostream &_out, const gz::math::Polynomial3 &_p) { _p.Print(_out, "x"); return _out; diff --git a/include/gz/math/Pose3.hh b/include/gz/math/Pose3.hh index 1053c67e1..b70125bbe 100644 --- a/include/gz/math/Pose3.hh +++ b/include/gz/math/Pose3.hh @@ -21,12 +21,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Pose3 Pose3.hh gz/math/Pose3.hh /// \brief The Pose3 class represents a 3D position and rotation. The @@ -50,13 +50,13 @@ namespace ignition /// require 'gz/math' /// /// # Construct a default Pose3d. - /// p = Ignition::Math::Pose3d.new + /// p = Gz::Math::Pose3d.new /// printf("A default Pose3d has the following values\n" + /// "%f %f %f %f %f %f\n", p.Pos().X(), p.Pos().Y(), p.Pos().Z(), /// p.Rot().Euler().X(), p.Rot().Euler().Y(), p.Rot().Euler().Z()) /// /// # Construct a pose at position 1, 2, 3 with a yaw of PI radians. - /// p1 = Ignition::Math::Pose3d.new(1, 2, 3, 0, 0, Math::PI) + /// 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" + /// "%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()) @@ -183,7 +183,7 @@ namespace ignition /// then, B + A is the transform from O to Q specified in frame O /// \param[in] _pose Pose3 to add to this pose. /// \return The resulting pose. - public: IGN_DEPRECATED(7) Pose3 operator+(const Pose3 &_pose) const + public: GZ_DEPRECATED(7) Pose3 operator+(const Pose3 &_pose) const { Pose3 result; @@ -197,7 +197,7 @@ namespace ignition /// \param[in] _pose Pose3 to add to this pose. /// \sa operator+(const Pose3 &_pose) const. /// \return The resulting pose. - public: IGN_DEPRECATED(7) const Pose3 & + public: GZ_DEPRECATED(7) const Pose3 & operator+=(const Pose3 &_pose) { this->p = this->CoordPositionAdd(_pose); @@ -501,7 +501,7 @@ namespace ignition /// \param[in] _pose pose to output /// \return the stream public: friend std::ostream &operator<<( - std::ostream &_out, const ignition::math::Pose3 &_pose) + std::ostream &_out, const gz::math::Pose3 &_pose) { _out << _pose.Pos() << " " << _pose.Rot(); return _out; @@ -512,7 +512,7 @@ namespace ignition /// \param[in] _pose the pose /// \return the stream public: friend std::istream &operator>>( - std::istream &_in, ignition::math::Pose3 &_pose) + std::istream &_in, gz::math::Pose3 &_pose) { // Skip white spaces _in.setf(std::ios_base::skipws); diff --git a/include/gz/math/Quaternion.hh b/include/gz/math/Quaternion.hh index fb9ad29b8..3aecf73c2 100644 --- a/include/gz/math/Quaternion.hh +++ b/include/gz/math/Quaternion.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // template class Matrix3; @@ -58,15 +58,15 @@ namespace ignition /// # /// require 'gz/math' /// - /// q = Ignition::Math::Quaterniond.new + /// q = Gz::Math::Quaterniond.new /// printf("A default quaternion has the following values\n"+ /// "\tW=%f X=%f Y=%f Z=%f\n", q.W(), q.X(), q.Y(), q.Z()) /// - /// q = Ignition::Math::Quaterniond.Identity + /// q = Gz::Math::Quaterniond.Identity /// printf("The identity quaternion has the following values\n" + /// "\tW=%f X=%f Y=%f Z=%f\n", q.W(), q.X(), q.Y(), q.Z()) /// - /// q2 = Ignition::Math::Quaterniond.new(0, 0, 3.14) + /// q2 = Gz::Math::Quaterniond.new(0, 0, 3.14) /// printf("A quaternion initialized from roll=0, pitch=0, and yaw=3.14 " + /// "has the following values\n" + /// "\tW=%f X=%f Y=%f Z=%f\n", q2.W(), q2.X(), q2.Y(), q2.Z()) @@ -301,7 +301,7 @@ namespace ignition /// \param[in] _az Z axis /// \param[in] _aa Angle in radians /// \deprecated Use SetFromAxisAngle(T, T, T, T) - public: void IGN_DEPRECATED(7) Axis(T _ax, T _ay, T _az, T _aa) + public: void GZ_DEPRECATED(7) Axis(T _ax, T _ay, T _az, T _aa) { this->SetFromAxisAngle(_ax, _ay, _az, _aa); } @@ -341,7 +341,7 @@ namespace ignition /// \param[in] _axis Axis /// \param[in] _a Angle in radians /// \deprecated Use SetFromAxisAngle(const Vector3 &_axis, T _a) - public: void IGN_DEPRECATED(7) Axis(const Vector3 &_axis, T _a) + public: void GZ_DEPRECATED(7) Axis(const Vector3 &_axis, T _a) { this->SetFromAxisAngle(_axis, _a); } @@ -373,7 +373,7 @@ namespace ignition /// Roll is a rotation about x, pitch is about y, yaw is about z. /// \param[in] _vec Euler angle /// \deprecated Use SetFromEuler(const Vector3 &) - public: void IGN_DEPRECATED(7) Euler(const Vector3 &_vec) + public: void GZ_DEPRECATED(7) Euler(const Vector3 &_vec) { this->SetFromEuler(_vec); } @@ -393,7 +393,7 @@ namespace ignition /// \param[in] _pitch Pitch angle (radians). /// \param[in] _yaw Yaw angle (radians). /// \deprecated Use SetFromEuler(T, T, T) - public: void IGN_DEPRECATED(7) Euler(T _roll, T _pitch, T _yaw) + public: void GZ_DEPRECATED(7) Euler(T _roll, T _pitch, T _yaw) { this->SetFromEuler(_roll, _pitch, _yaw); } @@ -535,7 +535,7 @@ namespace ignition /// \param[out] _axis rotation axis /// \param[out] _angle ccw angle in radians /// \deprecated Use AxisAngle(Vector3 &_axis, T &_angle) const - public: void IGN_DEPRECATED(7) ToAxis(Vector3 &_axis, T &_angle) const + public: void GZ_DEPRECATED(7) ToAxis(Vector3 &_axis, T &_angle) const { this->AxisAngle(_axis, _angle); } @@ -567,7 +567,7 @@ namespace ignition /// http://www.euclideanspace.com/maths/geometry/rotations/ /// conversions/matrixToQuaternion/ /// \deprecated Use SetFromMatrix(const Matrix3&) - public: void IGN_DEPRECATED(7) Matrix(const Matrix3 &_mat) + public: void GZ_DEPRECATED(7) Matrix(const Matrix3 &_mat) { this->SetFromMatrix(_mat); } @@ -626,7 +626,7 @@ namespace ignition /// Implementation inspired by /// http://stackoverflow.com/a/11741520/1076564 /// \deprecated Use SetFrom2Axes(const Vector3 &, const Vector3 &) - public: void IGN_DEPRECATED(7) From2Axes( + public: void GZ_DEPRECATED(7) From2Axes( const Vector3 &_v1, const Vector3 &_v2) { this->SetFrom2Axes(_v1, _v2); @@ -811,7 +811,7 @@ namespace ignition } /// \brief Equality comparison operator. A tolerance of 0.001 is used - /// with the ignition::math::equal function for each component of the + /// with the gz::math::equal function for each component of the /// quaternions. /// \param[in] _qt Quaternion for comparison. /// \return True if each component of both quaternions is within the @@ -822,7 +822,7 @@ namespace ignition } /// \brief Not equal to operator. A tolerance of 0.001 is used - /// with the ignition::math::equal function for each component of the + /// with the gz::math::equal function for each component of the /// quaternions. /// \param[in] _qt Quaternion for comparison. /// \return True if any component of both quaternions is not within @@ -1134,7 +1134,7 @@ namespace ignition /// \brief Set the x component. /// \param[in] _v The new value for the x quaternion component. /// \deprecated Use SetX(T) - public: inline void IGN_DEPRECATED(7) X(T _v) + public: inline void GZ_DEPRECATED(7) X(T _v) { this->SetX(_v); } @@ -1149,7 +1149,7 @@ namespace ignition /// \brief Set the y component. /// \param[in] _v The new value for the y quaternion component. /// \deprecated Use SetY(T) - public: inline void IGN_DEPRECATED(7) Y(T _v) + public: inline void GZ_DEPRECATED(7) Y(T _v) { this->SetY(_v); } @@ -1165,7 +1165,7 @@ namespace ignition /// \brief Set the z component. /// \param[in] _v The new value for the z quaternion component. /// \deprecated Use SetZ(T) - public: inline void IGN_DEPRECATED(7) Z(T _v) + public: inline void GZ_DEPRECATED(7) Z(T _v) { this->SetZ(_v); } @@ -1180,7 +1180,7 @@ namespace ignition /// \brief Set the w component. /// \param[in] _v The new value for the w quaternion component. /// \deprecated Use SetW(T) - public: inline void IGN_DEPRECATED(7) W(T _v) + public: inline void GZ_DEPRECATED(7) W(T _v) { this->SetW(_v); } @@ -1197,7 +1197,7 @@ namespace ignition /// \param[in] _q quaternion to output /// \return the stream public: friend std::ostream &operator<<(std::ostream &_out, - const ignition::math::Quaternion &_q) + const gz::math::Quaternion &_q) { Vector3 v(_q.Euler()); _out << v; @@ -1209,7 +1209,7 @@ namespace ignition /// \param[out] _q Quaternion to read values into /// \return The istream public: friend std::istream &operator>>(std::istream &_in, - ignition::math::Quaternion &_q) + gz::math::Quaternion &_q) { Angle roll, pitch, yaw; @@ -1226,7 +1226,7 @@ namespace ignition } /// \brief Equality comparison test with a tolerance parameter. - /// The tolerance is used with the ignition::math::equal function for + /// The tolerance is used with the gz::math::equal function for /// each component of the quaternions. /// \param[in] _q The quaternion to compare against. /// \param[in] _tol equality tolerance. diff --git a/include/gz/math/Rand.hh b/include/gz/math/Rand.hh index cf0898259..f94824b96 100644 --- a/include/gz/math/Rand.hh +++ b/include/gz/math/Rand.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \def GeneratorType /// \brief std::mt19937 @@ -45,7 +45,7 @@ namespace ignition /// \class Rand Rand.hh gz/math/Rand.hh /// \brief Random number generator class - class IGNITION_MATH_VISIBLE Rand + class GZ_MATH_VISIBLE Rand { /// \brief Set the seed value. /// \param[in] _seed The seed used to initialize the randon number diff --git a/include/gz/math/Region3.hh b/include/gz/math/Region3.hh index 1847b2df9..1236b9a74 100644 --- a/include/gz/math/Region3.hh +++ b/include/gz/math/Region3.hh @@ -26,12 +26,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Region3 Region3.hh gz/math/Region3.hh /// \brief The Region3 class represents the cartesian product @@ -174,7 +174,7 @@ namespace ignition /// \param _r Region3 to output /// \return the stream public: friend std::ostream &operator<<( - std::ostream &_out, const ignition::math::Region3 &_r) + std::ostream &_out, const gz::math::Region3 &_r) { return _out <<_r.ix << " x " << _r.iy << " x " << _r.iz; } diff --git a/include/gz/math/RollingMean.hh b/include/gz/math/RollingMean.hh index a4744396b..6b5ce5865 100644 --- a/include/gz/math/RollingMean.hh +++ b/include/gz/math/RollingMean.hh @@ -21,17 +21,17 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { /// \brief A class that computes the mean over a series of data points. /// The window size determines the maximum number of data points. The /// oldest value is popped off when the window size is reached and /// a new value is pushed in. - class IGNITION_MATH_VISIBLE RollingMean + class GZ_MATH_VISIBLE RollingMean { /// \brief Constructor /// \param[in] _windowSize The window size to use. This value will be diff --git a/include/gz/math/RotationSpline.hh b/include/gz/math/RotationSpline.hh index f92fa3603..a45deff91 100644 --- a/include/gz/math/RotationSpline.hh +++ b/include/gz/math/RotationSpline.hh @@ -21,15 +21,15 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { /// \class RotationSpline RotationSpline.hh gz/math/RotationSpline.hh /// \brief Spline for rotations - class IGNITION_MATH_VISIBLE RotationSpline + class GZ_MATH_VISIBLE RotationSpline { /// \brief Constructor. Sets the autoCalc to true public: RotationSpline(); diff --git a/include/gz/math/SemanticVersion.hh b/include/gz/math/SemanticVersion.hh index 393223a13..a246a114e 100644 --- a/include/gz/math/SemanticVersion.hh +++ b/include/gz/math/SemanticVersion.hh @@ -24,18 +24,18 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { /// \class SemanticVersion SemanticVersion.hh /// gz/math/SemanticVersion.hh /// \brief Version comparison class based on Semantic Versioning 2.0.0 /// http://semver.org/ /// Compares versions and converts versions from string. - class IGNITION_MATH_VISIBLE SemanticVersion + class GZ_MATH_VISIBLE SemanticVersion { /// \brief Default constructor. Use the Parse function to populate /// an instance with version information. diff --git a/include/gz/math/SignalStats.hh b/include/gz/math/SignalStats.hh index 0bd6903c7..be6dc19af 100644 --- a/include/gz/math/SignalStats.hh +++ b/include/gz/math/SignalStats.hh @@ -23,19 +23,19 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \brief Forward declare private data class. class SignalStatisticPrivate; /// \class SignalStatistic SignalStats.hh gz/math/SignalStats.hh /// \brief Statistical properties of a discrete time scalar signal. - class IGNITION_MATH_VISIBLE SignalStatistic + class GZ_MATH_VISIBLE SignalStatistic { /// \brief Constructor public: SignalStatistic(); @@ -81,7 +81,7 @@ namespace ignition /// \class SignalMaximum SignalStats.hh gz/math/SignalStats.hh /// \brief Computing the maximum value of a discretely sampled signal. - class IGNITION_MATH_VISIBLE SignalMaximum : public SignalStatistic + class GZ_MATH_VISIBLE SignalMaximum : public SignalStatistic { // Documentation inherited. public: virtual double Value() const override; @@ -96,7 +96,7 @@ namespace ignition /// \class SignalMean SignalStats.hh gz/math/SignalStats.hh /// \brief Computing the mean value of a discretely sampled signal. - class IGNITION_MATH_VISIBLE SignalMean : public SignalStatistic + class GZ_MATH_VISIBLE SignalMean : public SignalStatistic { // Documentation inherited. public: virtual double Value() const override; @@ -111,7 +111,7 @@ namespace ignition /// \class SignalMinimum SignalStats.hh gz/math/SignalStats.hh /// \brief Computing the minimum value of a discretely sampled signal. - class IGNITION_MATH_VISIBLE SignalMinimum : public SignalStatistic + class GZ_MATH_VISIBLE SignalMinimum : public SignalStatistic { // Documentation inherited. public: virtual double Value() const override; @@ -127,7 +127,7 @@ namespace ignition /// \class SignalRootMeanSquare SignalStats.hh gz/math/SignalStats.hh /// \brief Computing the square root of the mean squared value /// of a discretely sampled signal. - class IGNITION_MATH_VISIBLE SignalRootMeanSquare : public SignalStatistic + class GZ_MATH_VISIBLE SignalRootMeanSquare : public SignalStatistic { // Documentation inherited. public: virtual double Value() const override; @@ -145,7 +145,7 @@ namespace ignition /// \brief Computing the maximum of the absolute value /// of a discretely sampled signal. /// Also known as the maximum norm, infinity norm, or supremum norm. - class IGNITION_MATH_VISIBLE SignalMaxAbsoluteValue : public SignalStatistic + class GZ_MATH_VISIBLE SignalMaxAbsoluteValue : public SignalStatistic { // Documentation inherited. public: virtual double Value() const override; @@ -161,7 +161,7 @@ namespace ignition /// \class SignalVariance SignalStats.hh gz/math/SignalStats.hh /// \brief Computing the incremental variance /// of a discretely sampled signal. - class IGNITION_MATH_VISIBLE SignalVariance : public SignalStatistic + class GZ_MATH_VISIBLE SignalVariance : public SignalStatistic { // Documentation inherited. public: virtual double Value() const override; @@ -179,7 +179,7 @@ namespace ignition /// \class SignalStats SignalStats.hh gz/math/SignalStats.hh /// \brief Collection of statistics for a scalar signal. - class IGNITION_MATH_VISIBLE SignalStats + class GZ_MATH_VISIBLE SignalStats { /// \brief Constructor public: SignalStats(); @@ -252,4 +252,3 @@ namespace ignition } } #endif - diff --git a/include/gz/math/SpeedLimiter.hh b/include/gz/math/SpeedLimiter.hh index e90ce8f20..b77b81a0b 100644 --- a/include/gz/math/SpeedLimiter.hh +++ b/include/gz/math/SpeedLimiter.hh @@ -23,17 +23,17 @@ #include #include "gz/math/Helpers.hh" -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_MATH_VERSION_NAMESPACE { +inline namespace GZ_MATH_VERSION_NAMESPACE { // Forward declaration. class SpeedLimiterPrivate; /// \brief Class to limit velocity, acceleration and jerk. - class IGNITION_MATH_VISIBLE SpeedLimiter + class GZ_MATH_VISIBLE SpeedLimiter { /// \brief Constructor. /// There are no limits by default. diff --git a/include/gz/math/Sphere.hh b/include/gz/math/Sphere.hh index bd2fba583..4ab73d681 100644 --- a/include/gz/math/Sphere.hh +++ b/include/gz/math/Sphere.hh @@ -22,7 +22,7 @@ #include "gz/math/Quaternion.hh" #include "gz/math/Plane.hh" -namespace ignition +namespace gz { namespace math { @@ -30,7 +30,7 @@ namespace ignition class SpherePrivate; // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Sphere Sphere.hh gz/math/Sphere.hh /// \brief A representation of a sphere. @@ -63,11 +63,11 @@ namespace ignition /// \brief Get the material associated with this sphere. /// \return The material assigned to this sphere - public: const ignition::math::Material &Material() const; + public: const gz::math::Material &Material() const; /// \brief Set the material associated with this sphere. /// \param[in] _mat The material assigned to this sphere - public: void SetMaterial(const ignition::math::Material &_mat); + public: void SetMaterial(const gz::math::Material &_mat); /// \brief Get the mass matrix for this sphere. This function /// is only meaningful if the sphere's radius and material have been set. @@ -134,7 +134,7 @@ namespace ignition private: Precision radius = 0.0; /// \brief the sphere's material. - private: ignition::math::Material material; + private: gz::math::Material material; }; /// \typedef Sphere Spherei diff --git a/include/gz/math/SphericalCoordinates.hh b/include/gz/math/SphericalCoordinates.hh index fa3481000..755a6f83e 100644 --- a/include/gz/math/SphericalCoordinates.hh +++ b/include/gz/math/SphericalCoordinates.hh @@ -25,15 +25,15 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { /// \brief Convert spherical coordinates for planetary surfaces. - class IGNITION_MATH_VISIBLE SphericalCoordinates + class GZ_MATH_VISIBLE SphericalCoordinates { /// \enum SurfaceType /// \brief Unique identifiers for planetary surface models. @@ -80,10 +80,10 @@ namespace ignition /// \param[in] _elevation Reference elevation. /// \param[in] _heading Heading offset. public: SphericalCoordinates(const SurfaceType _type, - const ignition::math::Angle &_latitude, - const ignition::math::Angle &_longitude, + const gz::math::Angle &_latitude, + const gz::math::Angle &_longitude, const double _elevation, - const ignition::math::Angle &_heading); + const gz::math::Angle &_heading); /// \brief Convert a Cartesian position vector to geodetic coordinates. @@ -99,8 +99,8 @@ namespace ignition /// world frame. /// \return Cooordinates: geodetic latitude (deg), longitude (deg), /// altitude above sea level (m). - public: ignition::math::Vector3d SphericalFromLocalPosition( - const ignition::math::Vector3d &_xyz) const; + public: gz::math::Vector3d SphericalFromLocalPosition( + const gz::math::Vector3d &_xyz) const; /// \brief Convert a Cartesian velocity vector in the local frame /// to a global Cartesian frame with components East, North, Up. @@ -113,8 +113,8 @@ namespace ignition /// \param[in] _xyz Cartesian velocity vector in the heading-adjusted /// world frame. /// \return Rotated vector with components (x,y,z): (East, North, Up). - public: ignition::math::Vector3d GlobalFromLocalVelocity( - const ignition::math::Vector3d &_xyz) const; + public: gz::math::Vector3d GlobalFromLocalVelocity( + const gz::math::Vector3d &_xyz) const; /// \brief Convert a string to a SurfaceType. /// Allowed values: ["EARTH_WGS84"]. @@ -136,10 +136,10 @@ namespace ignition /// \param[in] _latB Latitude of point B. /// \param[in] _lonB Longitude of point B. /// \return Distance in meters. - public: static double Distance(const ignition::math::Angle &_latA, - const ignition::math::Angle &_lonA, - const ignition::math::Angle &_latB, - const ignition::math::Angle &_lonB); + public: static double Distance(const gz::math::Angle &_latA, + const gz::math::Angle &_lonA, + const gz::math::Angle &_latB, + const gz::math::Angle &_lonB); /// \brief Get SurfaceType currently in use. /// \return Current SurfaceType value. @@ -147,11 +147,11 @@ namespace ignition /// \brief Get reference geodetic latitude. /// \return Reference geodetic latitude. - public: ignition::math::Angle LatitudeReference() const; + public: gz::math::Angle LatitudeReference() const; /// \brief Get reference longitude. /// \return Reference longitude. - public: ignition::math::Angle LongitudeReference() const; + public: gz::math::Angle LongitudeReference() const; /// \brief Get reference elevation in meters. /// \return Reference elevation. @@ -161,7 +161,7 @@ namespace ignition /// angle from East to x-axis, or equivalently /// from North to y-axis. /// \return Heading offset of reference frame. - public: ignition::math::Angle HeadingOffset() const; + public: gz::math::Angle HeadingOffset() const; /// \brief Set SurfaceType for planetary surface model. /// \param[in] _type SurfaceType value. @@ -169,11 +169,11 @@ namespace ignition /// \brief Set reference geodetic latitude. /// \param[in] _angle Reference geodetic latitude. - public: void SetLatitudeReference(const ignition::math::Angle &_angle); + public: void SetLatitudeReference(const gz::math::Angle &_angle); /// \brief Set reference longitude. /// \param[in] _angle Reference longitude. - public: void SetLongitudeReference(const ignition::math::Angle &_angle); + public: void SetLongitudeReference(const gz::math::Angle &_angle); /// \brief Set reference elevation above sea level in meters. /// \param[in] _elevation Reference elevation. @@ -181,23 +181,23 @@ namespace ignition /// \brief Set heading angle offset for the frame. /// \param[in] _angle Heading offset for the frame. - public: void SetHeadingOffset(const ignition::math::Angle &_angle); + public: void SetHeadingOffset(const gz::math::Angle &_angle); /// \brief Convert a geodetic position vector to Cartesian coordinates. /// This performs a `PositionTransform` from SPHERICAL to LOCAL. /// \param[in] _latLonEle Geodetic position in the planetary frame of /// reference. X: latitude (deg), Y: longitude (deg), X: altitude. /// \return Cartesian position vector in the heading-adjusted world frame. - public: ignition::math::Vector3d LocalFromSphericalPosition( - const ignition::math::Vector3d &_latLonEle) const; + public: gz::math::Vector3d LocalFromSphericalPosition( + const gz::math::Vector3d &_latLonEle) const; /// \brief Convert a Cartesian velocity vector with components East, /// North, Up to a local cartesian frame vector XYZ. /// This is a wrapper around `VelocityTransform(_xyz, GLOBAL, LOCAL)` /// \param[in] _xyz Vector with components (x,y,z): (East, North, Up). /// \return Cartesian vector in the world frame. - public: ignition::math::Vector3d LocalFromGlobalVelocity( - const ignition::math::Vector3d &_xyz) const; + public: gz::math::Vector3d LocalFromGlobalVelocity( + const gz::math::Vector3d &_xyz) const; /// \brief Update coordinate transformation matrix with reference location public: void UpdateTransformationMatrix(); @@ -208,8 +208,8 @@ namespace ignition /// \param[in] _in CoordinateType for input /// \param[in] _out CoordinateType for output /// \return Transformed coordinate using cached origin. - public: ignition::math::Vector3d - PositionTransform(const ignition::math::Vector3d &_pos, + public: gz::math::Vector3d + PositionTransform(const gz::math::Vector3d &_pos, const CoordinateType &_in, const CoordinateType &_out) const; /// \brief Convert between velocity in SPHERICAL/ECEF/LOCAL/GLOBAL frame @@ -218,8 +218,8 @@ namespace ignition /// \param[in] _in CoordinateType for input /// \param[in] _out CoordinateType for output /// \return Transformed velocity vector - public: ignition::math::Vector3d VelocityTransform( - const ignition::math::Vector3d &_vel, + public: gz::math::Vector3d VelocityTransform( + const gz::math::Vector3d &_vel, const CoordinateType &_in, const CoordinateType &_out) const; /// \brief Equality operator, result = this == _sc diff --git a/include/gz/math/Spline.hh b/include/gz/math/Spline.hh index dc3cb057d..c9d6650a0 100644 --- a/include/gz/math/Spline.hh +++ b/include/gz/math/Spline.hh @@ -24,19 +24,19 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // // Forward declare private classes class ControlPoint; /// \class Spline Spline.hh gz/math/Spline.hh /// \brief Splines - class IGNITION_MATH_VISIBLE Spline + class GZ_MATH_VISIBLE Spline { /// \brief constructor public: Spline(); diff --git a/include/gz/math/Stopwatch.hh b/include/gz/math/Stopwatch.hh index 75289aa8e..c52cf1845 100644 --- a/include/gz/math/Stopwatch.hh +++ b/include/gz/math/Stopwatch.hh @@ -23,7 +23,7 @@ #include #include -namespace ignition +namespace gz { namespace math { @@ -31,7 +31,7 @@ namespace ignition using clock = std::chrono::steady_clock; // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { /// \class Stopwatch Stopwatch.hh gz/math/Stopwatch.hh /// \brief The Stopwatch keeps track of time spent in the run state, /// accessed through ElapsedRunTime(), and time spent in the stop state, @@ -43,7 +43,7 @@ namespace ignition /// # Example usage /// /// ```{.cpp} - /// ignition::math::Stopwatch watch; + /// gz::math::Stopwatch watch; /// watch.Start(); /// /// // do something... @@ -53,7 +53,7 @@ namespace ignition /// timeSys.ElapsedRunTime()).count() << " ms\n"; /// watch.Stop(); /// ``` - class IGNITION_MATH_VISIBLE Stopwatch + class GZ_MATH_VISIBLE Stopwatch { /// \brief Constructor. public: Stopwatch(); diff --git a/include/gz/math/Temperature.hh b/include/gz/math/Temperature.hh index e5c53ed6c..54a2f7ccc 100644 --- a/include/gz/math/Temperature.hh +++ b/include/gz/math/Temperature.hh @@ -25,12 +25,12 @@ #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { /// \brief A class that stores temperature information, and allows /// conversion between different units. /// @@ -56,10 +56,10 @@ namespace ignition /// # /// require 'gz/math' /// - /// celsius = Ignition::Math::Temperature::KelvinToCelsius(2.5); + /// celsius = Gz::Math::Temperature::KelvinToCelsius(2.5); /// printf("2.5Kelvin to Celsius is %f\n", celsius) /// - /// temp = Ignition::Math::Temperature.new(123.5) + /// temp = Gz::Math::Temperature.new(123.5) /// printf("Constructed a Temperature object with %f Kelvin\n", /// temp.Kelvin()) /// @@ -68,12 +68,12 @@ namespace ignition /// temp += 100.0 /// printf("Temperature + 100.0 is %fK", temp.Kelvin()) /// - /// newTemp = Ignition::Math::Temperature.new(temp.Kelvin()) + /// newTemp = Gz::Math::Temperature.new(temp.Kelvin()) /// newTemp += temp + 23.5; /// printf("Copied temp and added 23.5K. The new tempurature is %fF\n", /// newTemp.Fahrenheit()); /// \endcode - class IGNITION_MATH_VISIBLE Temperature + class GZ_MATH_VISIBLE Temperature { /// \brief Default constructor. public: Temperature(); @@ -335,7 +335,7 @@ namespace ignition /// \param[in] _temp Temperature to write to the stream. /// \return The output stream. public: friend std::ostream &operator<<(std::ostream &_out, - const ignition::math::Temperature &_temp) + const gz::math::Temperature &_temp) { _out << _temp.Kelvin(); return _out; @@ -347,7 +347,7 @@ namespace ignition /// temperature value is in Kelvin. /// \return The input stream. public: friend std::istream &operator>>(std::istream &_in, - ignition::math::Temperature &_temp) + gz::math::Temperature &_temp) { // Skip white spaces _in.setf(std::ios_base::skipws); diff --git a/include/gz/math/Triangle.hh b/include/gz/math/Triangle.hh index b9ff2c138..05fecc4a3 100644 --- a/include/gz/math/Triangle.hh +++ b/include/gz/math/Triangle.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Triangle Triangle.hh gz/math/Triangle.hh /// \brief Triangle class and related functions. diff --git a/include/gz/math/Triangle3.hh b/include/gz/math/Triangle3.hh index 6e5013b4e..677ae06a0 100644 --- a/include/gz/math/Triangle3.hh +++ b/include/gz/math/Triangle3.hh @@ -23,12 +23,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Triangle3 Triangle3.hh gz/math/Triangle3.hh /// \brief A 3-dimensional triangle and related functions. diff --git a/include/gz/math/Vector2.hh b/include/gz/math/Vector2.hh index 4c445ea21..629768f3e 100644 --- a/include/gz/math/Vector2.hh +++ b/include/gz/math/Vector2.hh @@ -26,12 +26,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Vector2 Vector2.hh gz/math/Vector2.hh /// \brief Two dimensional (x, y) vector. diff --git a/include/gz/math/Vector3.hh b/include/gz/math/Vector3.hh index 0ed433696..8ccd50175 100644 --- a/include/gz/math/Vector3.hh +++ b/include/gz/math/Vector3.hh @@ -26,12 +26,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Vector3 Vector3.hh gz/math/Vector3.hh /// \brief The Vector3 class represents the generic vector containing 3 @@ -729,7 +729,7 @@ namespace ignition /// \param _pt Vector3 to output /// \return the stream public: friend std::ostream &operator<<( - std::ostream &_out, const ignition::math::Vector3 &_pt) + std::ostream &_out, const gz::math::Vector3 &_pt) { for (auto i : {0, 1, 2}) { @@ -747,7 +747,7 @@ namespace ignition /// \param _pt vector3 to read values into /// \return the stream public: friend std::istream &operator>>( - std::istream &_in, ignition::math::Vector3 &_pt) + std::istream &_in, gz::math::Vector3 &_pt) { // Skip white spaces _in.setf(std::ios_base::skipws); diff --git a/include/gz/math/Vector3Stats.hh b/include/gz/math/Vector3Stats.hh index 90f2da5a4..bb62c260a 100644 --- a/include/gz/math/Vector3Stats.hh +++ b/include/gz/math/Vector3Stats.hh @@ -24,15 +24,15 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { /// \class Vector3Stats Vector3Stats.hh gz/math/Vector3Stats.hh /// \brief Collection of statistics for a Vector3 signal. - class IGNITION_MATH_VISIBLE Vector3Stats + class GZ_MATH_VISIBLE Vector3Stats { /// \brief Constructor public: Vector3Stats(); diff --git a/include/gz/math/Vector4.hh b/include/gz/math/Vector4.hh index a4c251569..beae5ab70 100644 --- a/include/gz/math/Vector4.hh +++ b/include/gz/math/Vector4.hh @@ -25,12 +25,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { // /// \class Vector4 Vector4.hh gz/math/Vector4.hh /// \brief T Generic x, y, z, w vector @@ -689,7 +689,7 @@ namespace ignition /// \param[in] _pt Vector4 to output /// \return The stream public: friend std::ostream &operator<<( - std::ostream &_out, const ignition::math::Vector4 &_pt) + std::ostream &_out, const gz::math::Vector4 &_pt) { for (auto i : {0, 1, 2, 3}) { @@ -706,7 +706,7 @@ namespace ignition /// \param[in] _pt Vector4 to read values into /// \return the stream public: friend std::istream &operator>>( - std::istream &_in, ignition::math::Vector4 &_pt) + std::istream &_in, gz::math::Vector4 &_pt) { T x, y, z, w; diff --git a/include/gz/math/VolumetricGridLookupField.hh b/include/gz/math/VolumetricGridLookupField.hh index b2b0d6399..661a240ee 100644 --- a/include/gz/math/VolumetricGridLookupField.hh +++ b/include/gz/math/VolumetricGridLookupField.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_VOLUMETRIC_GRID_LOOKUP_FIELD_HH_ -#define IGNITION_MATH_VOLUMETRIC_GRID_LOOKUP_FIELD_HH_ +#ifndef GZ_MATH_VOLUMETRIC_GRID_LOOKUP_FIELD_HH_ +#define GZ_MATH_VOLUMETRIC_GRID_LOOKUP_FIELD_HH_ #include #include @@ -26,12 +26,12 @@ #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { template /// \brief Lookup table for a volumetric dataset. This class is used to /// lookup indices for a large dataset that's organized in a grid. This diff --git a/include/gz/math/config.hh.in b/include/gz/math/config.hh.in index 6666cb962..fab14233b 100644 --- a/include/gz/math/config.hh.in +++ b/include/gz/math/config.hh.in @@ -1,17 +1,35 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + /* Config.hh. Generated by CMake for @PROJECT_NAME_NO_VERSION@. */ +#ifndef GZ_MATH_CONFIG_HH_ +#define GZ_MATH_CONFIG_HH_ + /* Version number */ -#define IGNITION_MATH_MAJOR_VERSION ${PROJECT_VERSION_MAJOR} -#define IGNITION_MATH_MINOR_VERSION ${PROJECT_VERSION_MINOR} -#define IGNITION_MATH_PATCH_VERSION ${PROJECT_VERSION_PATCH} +#define GZ_MATH_MAJOR_VERSION ${PROJECT_VERSION_MAJOR} +#define GZ_MATH_MINOR_VERSION ${PROJECT_VERSION_MINOR} +#define GZ_MATH_PATCH_VERSION ${PROJECT_VERSION_PATCH} -#define IGNITION_MATH_VERSION "${PROJECT_VERSION}" -#define IGNITION_MATH_VERSION_FULL "${PROJECT_VERSION_FULL}" +#define GZ_MATH_VERSION "${PROJECT_VERSION}" +#define GZ_MATH_VERSION_FULL "${PROJECT_VERSION_FULL}" -#define IGNITION_MATH_VERSION_NAMESPACE v${PROJECT_VERSION_MAJOR} +#define GZ_MATH_VERSION_NAMESPACE v${PROJECT_VERSION_MAJOR} -#define IGNITION_MATH_VERSION_HEADER "Ignition ${IGN_DESIGNATION}, version ${PROJECT_VERSION_FULL}\nCopyright (C) 2014 Open Source Robotics Foundation.\nReleased under the Apache 2.0 License.\n\n" +#define GZ_MATH_VERSION_HEADER "Gazebo Math, version ${PROJECT_VERSION_FULL}\nCopyright (C) 2014 Open Source Robotics Foundation.\nReleased under the Apache 2.0 License.\n\n" -#cmakedefine IGNITION_MATH_BUILD_TYPE_PROFILE 1 -#cmakedefine IGNITION_MATH_BUILD_TYPE_DEBUG 1 -#cmakedefine IGNITION_MATH_BUILD_TYPE_RELEASE 1 +#endif diff --git a/include/gz/math/detail/AxisIndex.hh b/include/gz/math/detail/AxisIndex.hh index 5988f9a0d..1c837e341 100644 --- a/include/gz/math/detail/AxisIndex.hh +++ b/include/gz/math/detail/AxisIndex.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_DETAIL_AXIS_INDEX_LOOKUP_FIELD_HH_ -#define IGNITION_MATH_DETAIL_AXIS_INDEX_LOOKUP_FIELD_HH_ +#ifndef GZ_MATH_DETAIL_AXIS_INDEX_LOOKUP_FIELD_HH_ +#define GZ_MATH_DETAIL_AXIS_INDEX_LOOKUP_FIELD_HH_ #include #include @@ -27,12 +27,12 @@ #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. - inline namespace IGNITION_MATH_VERSION_NAMESPACE { + inline namespace GZ_MATH_VERSION_NAMESPACE { /// \brief Represents a sparse number line which can be searched via /// search for indices. diff --git a/include/gz/math/detail/Box.hh b/include/gz/math/detail/Box.hh index f5e1ab082..830878462 100644 --- a/include/gz/math/detail/Box.hh +++ b/include/gz/math/detail/Box.hh @@ -24,7 +24,7 @@ #include #include -namespace ignition +namespace gz { namespace math { @@ -40,7 +40,7 @@ Box::Box(T _length, T _width, T _height) ////////////////////////////////////////////////// template Box::Box(T _length, T _width, T _height, - const ignition::math::Material &_mat) + const gz::math::Material &_mat) { this->size.X(_length); this->size.Y(_width); @@ -57,7 +57,7 @@ Box::Box(const Vector3 &_size) ////////////////////////////////////////////////// template -Box::Box(const Vector3 &_size, const ignition::math::Material &_mat) +Box::Box(const Vector3 &_size, const gz::math::Material &_mat) { this->size = _size; this->material = _mat; @@ -88,14 +88,14 @@ void Box::SetSize(const math::Vector3 &_size) ////////////////////////////////////////////////// template -const ignition::math::Material &Box::Material() const +const gz::math::Material &Box::Material() const { return this->material; } ////////////////////////////////////////////////// template -void Box::SetMaterial(const ignition::math::Material &_mat) +void Box::SetMaterial(const gz::math::Material &_mat) { this->material = _mat; } diff --git a/include/gz/math/detail/Capsule.hh b/include/gz/math/detail/Capsule.hh index b3cd6d745..8fb0f19ca 100644 --- a/include/gz/math/detail/Capsule.hh +++ b/include/gz/math/detail/Capsule.hh @@ -22,7 +22,7 @@ #include #include -namespace ignition +namespace gz { namespace math { diff --git a/include/gz/math/detail/Cylinder.hh b/include/gz/math/detail/Cylinder.hh index afb141aa5..8220a50f8 100644 --- a/include/gz/math/detail/Cylinder.hh +++ b/include/gz/math/detail/Cylinder.hh @@ -16,7 +16,7 @@ */ #ifndef GZ_MATH_DETAIL_CYLINDER_HH_ #define GZ_MATH_DETAIL_CYLINDER_HH_ -namespace ignition +namespace gz { namespace math { diff --git a/include/gz/math/detail/Ellipsoid.hh b/include/gz/math/detail/Ellipsoid.hh index b84522010..16ba4c8cb 100644 --- a/include/gz/math/detail/Ellipsoid.hh +++ b/include/gz/math/detail/Ellipsoid.hh @@ -22,7 +22,7 @@ #include #include -namespace ignition +namespace gz { namespace math { diff --git a/include/gz/math/detail/InterpolationPoint.hh b/include/gz/math/detail/InterpolationPoint.hh index 448b33c62..4f6d534a1 100644 --- a/include/gz/math/detail/InterpolationPoint.hh +++ b/include/gz/math/detail/InterpolationPoint.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_INTERPOLATION_POINT_HH_ -#define IGNITION_MATH_INTERPOLATION_POINT_HH_ +#ifndef GZ_MATH_INTERPOLATION_POINT_HH_ +#define GZ_MATH_INTERPOLATION_POINT_HH_ #include #include @@ -25,7 +25,7 @@ #include #include -namespace ignition +namespace gz { namespace math { @@ -193,7 +193,7 @@ namespace ignition /// \param[in] _start_index defines the slice to use. /// \param[in] _pos The position to project onto the plane template - ignition::math::Vector3 ProjectPointToPlane( + gz::math::Vector3 ProjectPointToPlane( const std::vector> _points, const std::size_t &_start_index, const Vector3 &_pos) diff --git a/include/gz/math/detail/Sphere.hh b/include/gz/math/detail/Sphere.hh index 91eddf9f1..04a43be6a 100644 --- a/include/gz/math/detail/Sphere.hh +++ b/include/gz/math/detail/Sphere.hh @@ -19,7 +19,7 @@ #include "gz/math/Sphere.hh" -namespace ignition +namespace gz { namespace math { @@ -32,7 +32,7 @@ Sphere::Sphere(const T _radius) ////////////////////////////////////////////////// template -Sphere::Sphere(const T _radius, const ignition::math::Material &_mat) +Sphere::Sphere(const T _radius, const gz::math::Material &_mat) { this->radius = _radius; this->material = _mat; @@ -54,14 +54,14 @@ void Sphere::SetRadius(const T _radius) ////////////////////////////////////////////////// template -const ignition::math::Material &Sphere::Material() const +const gz::math::Material &Sphere::Material() const { return this->material; } ////////////////////////////////////////////////// template -void Sphere::SetMaterial(const ignition::math::Material &_mat) +void Sphere::SetMaterial(const gz::math::Material &_mat) { this->material = _mat; } diff --git a/include/gz/math/detail/WellOrderedVector.hh b/include/gz/math/detail/WellOrderedVector.hh index 98aebfa7c..61dadbc11 100644 --- a/include/gz/math/detail/WellOrderedVector.hh +++ b/include/gz/math/detail/WellOrderedVector.hh @@ -18,7 +18,7 @@ #define GZ_MATH_DETAIL_WELLORDERED_VECTOR_HH_ #include -namespace ignition +namespace gz { namespace math { diff --git a/include/gz/math/graph/Edge.hh b/include/gz/math/graph/Edge.hh index 80931af0d..92f4b937c 100644 --- a/include/gz/math/graph/Edge.hh +++ b/include/gz/math/graph/Edge.hh @@ -27,12 +27,12 @@ #include #include "gz/math/graph/Vertex.hh" -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_MATH_VERSION_NAMESPACE { +inline namespace GZ_MATH_VERSION_NAMESPACE { namespace graph { /// \typedef EdgeId. diff --git a/include/gz/math/graph/Graph.hh b/include/gz/math/graph/Graph.hh index 4c0d07905..d13d8ae30 100644 --- a/include/gz/math/graph/Graph.hh +++ b/include/gz/math/graph/Graph.hh @@ -30,12 +30,12 @@ #include "gz/math/graph/Edge.hh" #include "gz/math/graph/Vertex.hh" -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_MATH_VERSION_NAMESPACE { +inline namespace GZ_MATH_VERSION_NAMESPACE { namespace graph { /// \brief A generic graph class. @@ -51,7 +51,7 @@ namespace graph /// /// // Create a directed graph that is capable of storing integer data in the /// // vertices and double data on the edges. - /// ignition::math::graph::DirectedGraph graph( + /// gz::math::graph::DirectedGraph graph( /// // Create the vertices, with default data and vertex ids. /// { /// {"vertex1"}, {"vertex2"}, {"vertex3"} @@ -64,7 +64,7 @@ namespace graph /// }); /// /// // You can assign data to vertices. - /// ignition::math::graph::DirectedGraph graph2( + /// gz::math::graph::DirectedGraph graph2( /// // Create the vertices, with custom data and default vertex ids. /// { /// {"vertex1", 1}, {"vertex2", 2}, {"vertex3", 10} @@ -78,7 +78,7 @@ namespace graph /// /// /// // It's also possible to specify vertex ids. - /// ignition::math::graph::DirectedGraph graph3( + /// gz::math::graph::DirectedGraph graph3( /// // Create the vertices with custom data and vertex ids. /// { /// {"vertex1", 1, 2}, {"vertex2", 2, 3}, {"vertex3", 10, 4} @@ -89,7 +89,7 @@ namespace graph /// }); /// /// // Finally, you can also assign weights to the edges. - /// ignition::math::graph::DirectedGraph graph4( + /// gz::math::graph::DirectedGraph graph4( /// // Create the vertices with custom data and vertex ids. /// { /// {"vertex1", 1, 2}, {"vertex2", 2, 3}, {"vertex3", 10, 4} diff --git a/include/gz/math/graph/GraphAlgorithms.hh b/include/gz/math/graph/GraphAlgorithms.hh index bbde04fdf..1dde695e4 100644 --- a/include/gz/math/graph/GraphAlgorithms.hh +++ b/include/gz/math/graph/GraphAlgorithms.hh @@ -29,12 +29,12 @@ #include "gz/math/graph/Graph.hh" #include "gz/math/Helpers.hh" -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_MATH_VERSION_NAMESPACE { +inline namespace GZ_MATH_VERSION_NAMESPACE { namespace graph { /// \typedef CostInfo. diff --git a/include/gz/math/graph/Vertex.hh b/include/gz/math/graph/Vertex.hh index 0b2f53899..e61fa22df 100644 --- a/include/gz/math/graph/Vertex.hh +++ b/include/gz/math/graph/Vertex.hh @@ -28,12 +28,12 @@ #include #include -namespace ignition +namespace gz { namespace math { // Inline bracket to help doxygen filtering. -inline namespace IGNITION_MATH_VERSION_NAMESPACE { +inline namespace GZ_MATH_VERSION_NAMESPACE { namespace graph { /// \typedef VertexId. diff --git a/include/ignition/math.hh b/include/ignition/math.hh index baadd4d4e..cad1e2c96 100644 --- a/include/ignition/math.hh +++ b/include/ignition/math.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/AdditivelySeparableScalarField3.hh b/include/ignition/math/AdditivelySeparableScalarField3.hh index c080ea3fc..62620a374 100644 --- a/include/ignition/math/AdditivelySeparableScalarField3.hh +++ b/include/ignition/math/AdditivelySeparableScalarField3.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Angle.hh b/include/ignition/math/Angle.hh index c040942ac..1bbb9750e 100644 --- a/include/ignition/math/Angle.hh +++ b/include/ignition/math/Angle.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/AxisAlignedBox.hh b/include/ignition/math/AxisAlignedBox.hh index 82b2dc1af..1a8a8e409 100644 --- a/include/ignition/math/AxisAlignedBox.hh +++ b/include/ignition/math/AxisAlignedBox.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Box.hh b/include/ignition/math/Box.hh index 9b916e378..361be9cbe 100644 --- a/include/ignition/math/Box.hh +++ b/include/ignition/math/Box.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Capsule.hh b/include/ignition/math/Capsule.hh index 0faa66672..88da16e00 100644 --- a/include/ignition/math/Capsule.hh +++ b/include/ignition/math/Capsule.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Color.hh b/include/ignition/math/Color.hh index a362200de..aeeedea91 100644 --- a/include/ignition/math/Color.hh +++ b/include/ignition/math/Color.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Cylinder.hh b/include/ignition/math/Cylinder.hh index 04264af84..54fc7b91e 100644 --- a/include/ignition/math/Cylinder.hh +++ b/include/ignition/math/Cylinder.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/DiffDriveOdometry.hh b/include/ignition/math/DiffDriveOdometry.hh index 65d76e4a6..b0f7e51ed 100644 --- a/include/ignition/math/DiffDriveOdometry.hh +++ b/include/ignition/math/DiffDriveOdometry.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Ellipsoid.hh b/include/ignition/math/Ellipsoid.hh index 4078fd4b9..1e7f95907 100644 --- a/include/ignition/math/Ellipsoid.hh +++ b/include/ignition/math/Ellipsoid.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Export.hh b/include/ignition/math/Export.hh index 4b45141c1..04084226f 100644 --- a/include/ignition/math/Export.hh +++ b/include/ignition/math/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Filter.hh b/include/ignition/math/Filter.hh index 0029af7c0..b0a4429d3 100644 --- a/include/ignition/math/Filter.hh +++ b/include/ignition/math/Filter.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Frustum.hh b/include/ignition/math/Frustum.hh index d2467cbf0..03f3f9c39 100644 --- a/include/ignition/math/Frustum.hh +++ b/include/ignition/math/Frustum.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/GaussMarkovProcess.hh b/include/ignition/math/GaussMarkovProcess.hh index f411fd60e..3de3dd0d8 100644 --- a/include/ignition/math/GaussMarkovProcess.hh +++ b/include/ignition/math/GaussMarkovProcess.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Helpers.hh b/include/ignition/math/Helpers.hh index e48efb669..efd519133 100644 --- a/include/ignition/math/Helpers.hh +++ b/include/ignition/math/Helpers.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Inertial.hh b/include/ignition/math/Inertial.hh index 252f824e0..b53893c72 100644 --- a/include/ignition/math/Inertial.hh +++ b/include/ignition/math/Inertial.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Interval.hh b/include/ignition/math/Interval.hh index f4a0a8bed..ce17d0916 100644 --- a/include/ignition/math/Interval.hh +++ b/include/ignition/math/Interval.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Kmeans.hh b/include/ignition/math/Kmeans.hh index 82fea2de7..beb24cf20 100644 --- a/include/ignition/math/Kmeans.hh +++ b/include/ignition/math/Kmeans.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Line2.hh b/include/ignition/math/Line2.hh index ea74c5939..7778a3789 100644 --- a/include/ignition/math/Line2.hh +++ b/include/ignition/math/Line2.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Line3.hh b/include/ignition/math/Line3.hh index 99fea8a78..1cdb41d94 100644 --- a/include/ignition/math/Line3.hh +++ b/include/ignition/math/Line3.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/MassMatrix3.hh b/include/ignition/math/MassMatrix3.hh index 307f4783f..5e9ab939f 100644 --- a/include/ignition/math/MassMatrix3.hh +++ b/include/ignition/math/MassMatrix3.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Material.hh b/include/ignition/math/Material.hh index 4628a81bc..515248bb6 100644 --- a/include/ignition/math/Material.hh +++ b/include/ignition/math/Material.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/MaterialType.hh b/include/ignition/math/MaterialType.hh index 0eedd3083..6fa0c8e6a 100644 --- a/include/ignition/math/MaterialType.hh +++ b/include/ignition/math/MaterialType.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Matrix3.hh b/include/ignition/math/Matrix3.hh index 36f1c98c5..97f447c70 100644 --- a/include/ignition/math/Matrix3.hh +++ b/include/ignition/math/Matrix3.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Matrix4.hh b/include/ignition/math/Matrix4.hh index b1636dfc8..e0444822c 100644 --- a/include/ignition/math/Matrix4.hh +++ b/include/ignition/math/Matrix4.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/MovingWindowFilter.hh b/include/ignition/math/MovingWindowFilter.hh index a2ee0370b..92d04d542 100644 --- a/include/ignition/math/MovingWindowFilter.hh +++ b/include/ignition/math/MovingWindowFilter.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/OrientedBox.hh b/include/ignition/math/OrientedBox.hh index b62a7bef9..3ff808b56 100644 --- a/include/ignition/math/OrientedBox.hh +++ b/include/ignition/math/OrientedBox.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/PID.hh b/include/ignition/math/PID.hh index c1ad844cf..a10fedcce 100644 --- a/include/ignition/math/PID.hh +++ b/include/ignition/math/PID.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/PiecewiseScalarField3.hh b/include/ignition/math/PiecewiseScalarField3.hh index a8bb2ba09..c52dd227b 100644 --- a/include/ignition/math/PiecewiseScalarField3.hh +++ b/include/ignition/math/PiecewiseScalarField3.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Plane.hh b/include/ignition/math/Plane.hh index eb0ad995c..4181967ce 100644 --- a/include/ignition/math/Plane.hh +++ b/include/ignition/math/Plane.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Polynomial3.hh b/include/ignition/math/Polynomial3.hh index 9b01782c7..9f1238926 100644 --- a/include/ignition/math/Polynomial3.hh +++ b/include/ignition/math/Polynomial3.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Pose3.hh b/include/ignition/math/Pose3.hh index c3a8d6071..e2c4b7236 100644 --- a/include/ignition/math/Pose3.hh +++ b/include/ignition/math/Pose3.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Quaternion.hh b/include/ignition/math/Quaternion.hh index a50e006da..433db415b 100644 --- a/include/ignition/math/Quaternion.hh +++ b/include/ignition/math/Quaternion.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Rand.hh b/include/ignition/math/Rand.hh index bb1b6d9e2..73628d05e 100644 --- a/include/ignition/math/Rand.hh +++ b/include/ignition/math/Rand.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Region3.hh b/include/ignition/math/Region3.hh index fdb86a12b..4b7564ef1 100644 --- a/include/ignition/math/Region3.hh +++ b/include/ignition/math/Region3.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/RollingMean.hh b/include/ignition/math/RollingMean.hh index c37891bcf..15b9d6205 100644 --- a/include/ignition/math/RollingMean.hh +++ b/include/ignition/math/RollingMean.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/RotationSpline.hh b/include/ignition/math/RotationSpline.hh index f650a74d8..41d40b903 100644 --- a/include/ignition/math/RotationSpline.hh +++ b/include/ignition/math/RotationSpline.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/SemanticVersion.hh b/include/ignition/math/SemanticVersion.hh index 78f50ebb4..1e7efa45a 100644 --- a/include/ignition/math/SemanticVersion.hh +++ b/include/ignition/math/SemanticVersion.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/SignalStats.hh b/include/ignition/math/SignalStats.hh index e4267dbf9..300e71679 100644 --- a/include/ignition/math/SignalStats.hh +++ b/include/ignition/math/SignalStats.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/SpeedLimiter.hh b/include/ignition/math/SpeedLimiter.hh index 5430372eb..ee5845136 100644 --- a/include/ignition/math/SpeedLimiter.hh +++ b/include/ignition/math/SpeedLimiter.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Sphere.hh b/include/ignition/math/Sphere.hh index a2b1aa806..fd47274fa 100644 --- a/include/ignition/math/Sphere.hh +++ b/include/ignition/math/Sphere.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/SphericalCoordinates.hh b/include/ignition/math/SphericalCoordinates.hh index 00c21c993..13eebdb47 100644 --- a/include/ignition/math/SphericalCoordinates.hh +++ b/include/ignition/math/SphericalCoordinates.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Spline.hh b/include/ignition/math/Spline.hh index 1d7f2849e..7b4955d8e 100644 --- a/include/ignition/math/Spline.hh +++ b/include/ignition/math/Spline.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Stopwatch.hh b/include/ignition/math/Stopwatch.hh index b87cbc3ef..a1e4634bb 100644 --- a/include/ignition/math/Stopwatch.hh +++ b/include/ignition/math/Stopwatch.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Temperature.hh b/include/ignition/math/Temperature.hh index 9d2ab5403..bb647abfc 100644 --- a/include/ignition/math/Temperature.hh +++ b/include/ignition/math/Temperature.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Triangle.hh b/include/ignition/math/Triangle.hh index e06d35e4d..bbb8489ec 100644 --- a/include/ignition/math/Triangle.hh +++ b/include/ignition/math/Triangle.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Triangle3.hh b/include/ignition/math/Triangle3.hh index 39b29e2b0..4b78e848f 100644 --- a/include/ignition/math/Triangle3.hh +++ b/include/ignition/math/Triangle3.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Vector2.hh b/include/ignition/math/Vector2.hh index a477170e6..9c07d790f 100644 --- a/include/ignition/math/Vector2.hh +++ b/include/ignition/math/Vector2.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Vector3.hh b/include/ignition/math/Vector3.hh index 6af392588..1c5a6ce00 100644 --- a/include/ignition/math/Vector3.hh +++ b/include/ignition/math/Vector3.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Vector3Stats.hh b/include/ignition/math/Vector3Stats.hh index bc90654f9..7da418aa8 100644 --- a/include/ignition/math/Vector3Stats.hh +++ b/include/ignition/math/Vector3Stats.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/Vector4.hh b/include/ignition/math/Vector4.hh index 6f524d279..f0abd02d1 100644 --- a/include/ignition/math/Vector4.hh +++ b/include/ignition/math/Vector4.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/VolumetricGridLookupField.hh b/include/ignition/math/VolumetricGridLookupField.hh index 3d3d40484..eb9dd9891 100644 --- a/include/ignition/math/VolumetricGridLookupField.hh +++ b/include/ignition/math/VolumetricGridLookupField.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/config.hh b/include/ignition/math/config.hh index 71685131d..fcee8bf38 100644 --- a/include/ignition/math/config.hh +++ b/include/ignition/math/config.hh @@ -15,4 +15,32 @@ * */ +#ifndef IGNITION_MATH__CONFIG_HH_ +#define IGNITION_MATH__CONFIG_HH_ + #include + +#define IGNITION_MATH_MAJOR_VERSION GZ_MATH_MAJOR_VERSION +#define IGNITION_MATH_MINOR_VERSION GZ_MATH_MINOR_VERSION +#define IGNITION_MATH_PATCH_VERSION GZ_MATH_PATCH_VERSION + +#define IGNITION_MATH_VERSION GZ_MATH_VERSION +#define IGNITION_MATH_VERSION_FULL GZ_MATH_VERSION_FULL + +#define IGNITION_MATH_VERSION_NAMESPACE GZ_MATH_VERSION_NAMESPACE + +#define IGNITION_MATH_VERSION_HEADER GZ_MATH_VERSION_HEADER + +namespace gz +{ +} + +namespace ignition +{ + #ifndef SUPPRESS_IGNITION_HEADER_DEPRECATION + #pragma message("ignition namespace is deprecated! Use gz instead!") + #endif + using namespace gz; +} + +#endif diff --git a/include/ignition/math/detail/AxisIndex.hh b/include/ignition/math/detail/AxisIndex.hh index 7ffbddb9d..818e6f60e 100644 --- a/include/ignition/math/detail/AxisIndex.hh +++ b/include/ignition/math/detail/AxisIndex.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/detail/Box.hh b/include/ignition/math/detail/Box.hh index 7ccd94539..78d1b94e4 100644 --- a/include/ignition/math/detail/Box.hh +++ b/include/ignition/math/detail/Box.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/detail/Capsule.hh b/include/ignition/math/detail/Capsule.hh index e548a21d8..93db5c930 100644 --- a/include/ignition/math/detail/Capsule.hh +++ b/include/ignition/math/detail/Capsule.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/detail/Cylinder.hh b/include/ignition/math/detail/Cylinder.hh index 24acee9af..b32e93af7 100644 --- a/include/ignition/math/detail/Cylinder.hh +++ b/include/ignition/math/detail/Cylinder.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/detail/Ellipsoid.hh b/include/ignition/math/detail/Ellipsoid.hh index 536f49c76..721ed50e0 100644 --- a/include/ignition/math/detail/Ellipsoid.hh +++ b/include/ignition/math/detail/Ellipsoid.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/detail/Export.hh b/include/ignition/math/detail/Export.hh index 29fd6d728..e3cdbfec4 100644 --- a/include/ignition/math/detail/Export.hh +++ b/include/ignition/math/detail/Export.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/detail/InterpolationPoint.hh b/include/ignition/math/detail/InterpolationPoint.hh index 1656262c0..d47868b4b 100644 --- a/include/ignition/math/detail/InterpolationPoint.hh +++ b/include/ignition/math/detail/InterpolationPoint.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/detail/Sphere.hh b/include/ignition/math/detail/Sphere.hh index 3a570ccb5..70e5f8740 100644 --- a/include/ignition/math/detail/Sphere.hh +++ b/include/ignition/math/detail/Sphere.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/detail/WellOrderedVector.hh b/include/ignition/math/detail/WellOrderedVector.hh index 2db4c489c..2c3eebed5 100644 --- a/include/ignition/math/detail/WellOrderedVector.hh +++ b/include/ignition/math/detail/WellOrderedVector.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/graph/Edge.hh b/include/ignition/math/graph/Edge.hh index 9353ebf1b..3f908c0b3 100644 --- a/include/ignition/math/graph/Edge.hh +++ b/include/ignition/math/graph/Edge.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/graph/Graph.hh b/include/ignition/math/graph/Graph.hh index a82f6b960..ffeaa58a7 100644 --- a/include/ignition/math/graph/Graph.hh +++ b/include/ignition/math/graph/Graph.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/graph/GraphAlgorithms.hh b/include/ignition/math/graph/GraphAlgorithms.hh index 15e68e72a..76da1e90c 100644 --- a/include/ignition/math/graph/GraphAlgorithms.hh +++ b/include/ignition/math/graph/GraphAlgorithms.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/include/ignition/math/graph/Vertex.hh b/include/ignition/math/graph/Vertex.hh index 9c84a0329..115d9ad2a 100644 --- a/include/ignition/math/graph/Vertex.hh +++ b/include/ignition/math/graph/Vertex.hh @@ -16,3 +16,4 @@ */ #include +#include diff --git a/src/AdditivelySeparableScalarField3_TEST.cc b/src/AdditivelySeparableScalarField3_TEST.cc index 8b36b6400..78d4bd6ad 100644 --- a/src/AdditivelySeparableScalarField3_TEST.cc +++ b/src/AdditivelySeparableScalarField3_TEST.cc @@ -21,7 +21,7 @@ #include "gz/math/AdditivelySeparableScalarField3.hh" #include "gz/math/Polynomial3.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(AdditivelySeparableScalarField3Test, Evaluate) diff --git a/src/Angle.cc b/src/Angle.cc index fd76d35a4..29d733b4a 100644 --- a/src/Angle.cc +++ b/src/Angle.cc @@ -17,7 +17,7 @@ #include "gz/math/Helpers.hh" #include "gz/math/Angle.hh" -using namespace ignition::math; +using namespace gz::math; namespace { diff --git a/src/Angle_TEST.cc b/src/Angle_TEST.cc index 74385e82b..e7a2445da 100644 --- a/src/Angle_TEST.cc +++ b/src/Angle_TEST.cc @@ -22,7 +22,7 @@ #include "gz/math/Helpers.hh" #include "gz/math/Angle.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(AngleTest, Angle) diff --git a/src/AxisAlignedBox.cc b/src/AxisAlignedBox.cc index 727513cc7..6ea66ca27 100644 --- a/src/AxisAlignedBox.cc +++ b/src/AxisAlignedBox.cc @@ -17,11 +17,11 @@ #include #include -using namespace ignition; +using namespace gz; using namespace math; // Private data for AxisAlignedBox class -class ignition::math::AxisAlignedBox::Implementation +class gz::math::AxisAlignedBox::Implementation { /// \brief Minimum corner of the box public: Vector3d min = Vector3d(MAX_D, MAX_D, MAX_D); @@ -32,7 +32,7 @@ class ignition::math::AxisAlignedBox::Implementation ////////////////////////////////////////////////// AxisAlignedBox::AxisAlignedBox() -: dataPtr(ignition::utils::MakeImpl()) +: dataPtr(gz::utils::MakeImpl()) { } diff --git a/src/AxisAlignedBox_TEST.cc b/src/AxisAlignedBox_TEST.cc index 86bf90bb7..46d3ccc79 100644 --- a/src/AxisAlignedBox_TEST.cc +++ b/src/AxisAlignedBox_TEST.cc @@ -19,7 +19,7 @@ #include "gz/math/AxisAlignedBox.hh" -using namespace ignition; +using namespace gz; using namespace math; class myAxisAlignedBox : public AxisAlignedBox diff --git a/src/Box_TEST.cc b/src/Box_TEST.cc index 4b9194111..9defa6297 100644 --- a/src/Box_TEST.cc +++ b/src/Box_TEST.cc @@ -19,7 +19,7 @@ #include "gz/math/Box.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(BoxTest, Constructor) diff --git a/src/Capsule_TEST.cc b/src/Capsule_TEST.cc index d383eb837..e2fdd0e8c 100644 --- a/src/Capsule_TEST.cc +++ b/src/Capsule_TEST.cc @@ -21,7 +21,7 @@ #include "gz/math/Capsule.hh" #include "gz/math/Helpers.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(CapsuleTest, Constructor) diff --git a/src/Color.cc b/src/Color.cc index 801761057..c79b52b4c 100644 --- a/src/Color.cc +++ b/src/Color.cc @@ -19,7 +19,7 @@ #include "gz/math/Color.hh" -using namespace ignition; +using namespace gz; using namespace math; namespace { diff --git a/src/Color_TEST.cc b/src/Color_TEST.cc index e6dbd1888..97eaf3539 100644 --- a/src/Color_TEST.cc +++ b/src/Color_TEST.cc @@ -19,7 +19,7 @@ #include #include -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(Color, ConstColors) diff --git a/src/Cylinder_TEST.cc b/src/Cylinder_TEST.cc index 66bb8d1e5..c9e5df94e 100644 --- a/src/Cylinder_TEST.cc +++ b/src/Cylinder_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/Cylinder.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(CylinderTest, Constructor) diff --git a/src/DiffDriveOdometry.cc b/src/DiffDriveOdometry.cc index 99380687f..983a7bf7c 100644 --- a/src/DiffDriveOdometry.cc +++ b/src/DiffDriveOdometry.cc @@ -18,12 +18,12 @@ #include "gz/math/DiffDriveOdometry.hh" #include "gz/math/RollingMean.hh" -using namespace ignition; +using namespace gz; using namespace math; // The implementation was borrowed from: https://github.com/ros-controls/ros_controllers/blob/melodic-devel/diff_drive_controller/src/odometry.cpp -class ignition::math::DiffDriveOdometry::Implementation +class gz::math::DiffDriveOdometry::Implementation { /// \brief Integrates the velocities (linear and angular) using 2nd order /// Runge-Kutta. @@ -83,7 +83,7 @@ class ignition::math::DiffDriveOdometry::Implementation ////////////////////////////////////////////////// DiffDriveOdometry::DiffDriveOdometry(size_t _windowSize) - : dataPtr(ignition::utils::MakeImpl()) + : dataPtr(gz::utils::MakeImpl()) { this->SetVelocityRollingWindowSize(_windowSize); } diff --git a/src/DiffDriveOdometry_TEST.cc b/src/DiffDriveOdometry_TEST.cc index ea7a61c60..35ecfbd50 100644 --- a/src/DiffDriveOdometry_TEST.cc +++ b/src/DiffDriveOdometry_TEST.cc @@ -22,7 +22,7 @@ #include "gz/math/Helpers.hh" #include "gz/math/DiffDriveOdometry.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(DiffDriveOdometryTest, DiffDriveOdometry) diff --git a/src/Ellipsoid_TEST.cc b/src/Ellipsoid_TEST.cc index 31d669a0c..951401bba 100644 --- a/src/Ellipsoid_TEST.cc +++ b/src/Ellipsoid_TEST.cc @@ -22,7 +22,7 @@ #include "gz/math/Helpers.hh" #include "gz/math/Vector3.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(EllipsoidTest, Constructor) diff --git a/src/Filter_TEST.cc b/src/Filter_TEST.cc index 8d193d8cb..aa9e9264f 100644 --- a/src/Filter_TEST.cc +++ b/src/Filter_TEST.cc @@ -19,7 +19,7 @@ #include "gz/math/Filter.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(FilterTest, OnePole) diff --git a/src/Frustum.cc b/src/Frustum.cc index 0798b8f08..dc9f2f8a8 100644 --- a/src/Frustum.cc +++ b/src/Frustum.cc @@ -26,7 +26,7 @@ #include "gz/math/Plane.hh" #include "gz/math/Pose3.hh" -using namespace ignition; +using namespace gz; using namespace math; /// \internal @@ -68,7 +68,7 @@ class Frustum::Implementation ///////////////////////////////////////////////// Frustum::Frustum() - : dataPtr(ignition::utils::MakeImpl()) + : dataPtr(gz::utils::MakeImpl()) { } diff --git a/src/Frustum_TEST.cc b/src/Frustum_TEST.cc index ce6fa1f54..1c9949bed 100644 --- a/src/Frustum_TEST.cc +++ b/src/Frustum_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/Helpers.hh" #include "gz/math/Frustum.hh" -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// diff --git a/src/GaussMarkovProcess.cc b/src/GaussMarkovProcess.cc index 886e1d7e1..e6a919609 100644 --- a/src/GaussMarkovProcess.cc +++ b/src/GaussMarkovProcess.cc @@ -18,10 +18,10 @@ #include #include -using namespace ignition::math; +using namespace gz::math; ////////////////////////////////////////////////// -class ignition::math::GaussMarkovProcess::Implementation +class gz::math::GaussMarkovProcess::Implementation { /// \brief Current process value. public: double value{0}; @@ -41,7 +41,7 @@ class ignition::math::GaussMarkovProcess::Implementation ////////////////////////////////////////////////// GaussMarkovProcess::GaussMarkovProcess() - : dataPtr(ignition::utils::MakeImpl()) + : dataPtr(gz::utils::MakeImpl()) { } diff --git a/src/GaussMarkovProcess_TEST.cc b/src/GaussMarkovProcess_TEST.cc index 6c05f71a9..cf239a083 100644 --- a/src/GaussMarkovProcess_TEST.cc +++ b/src/GaussMarkovProcess_TEST.cc @@ -21,7 +21,7 @@ #include "gz/math/Helpers.hh" #include "gz/math/Rand.hh" -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// diff --git a/src/Helpers.cc b/src/Helpers.cc index 19795fcb1..dc11b0fee 100644 --- a/src/Helpers.cc +++ b/src/Helpers.cc @@ -20,11 +20,11 @@ #include #include -namespace ignition +namespace gz { namespace math { - inline namespace IGNITION_MATH_VERSION_NAMESPACE + inline namespace GZ_MATH_VERSION_NAMESPACE { ///////////////////////////////////////////// diff --git a/src/Helpers.i b/src/Helpers.i index 096385f90..dc46cc394 100644 --- a/src/Helpers.i +++ b/src/Helpers.i @@ -38,7 +38,7 @@ constexpr T IGN_MASSMATRIX3_DEFAULT_TOLERANCE = T(10); #define IGN_BOX_VOLUME(_x, _y, _z) (_x *_y * _z) #define IGN_BOX_VOLUME_V(_v) (_v.X() *_v.Y() * _v.Z()) -namespace ignition +namespace gz { namespace math { diff --git a/src/Helpers_TEST.cc b/src/Helpers_TEST.cc index 30b165d3f..5b46fb61d 100644 --- a/src/Helpers_TEST.cc +++ b/src/Helpers_TEST.cc @@ -26,7 +26,7 @@ #include "gz/math/Helpers.hh" #include -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// // Test a few function in Helpers diff --git a/src/Helpers_TEST.rb b/src/Helpers_TEST.rb index ad8106cdb..f33b992d7 100644 --- a/src/Helpers_TEST.rb +++ b/src/Helpers_TEST.rb @@ -20,14 +20,14 @@ class Helpers_TEST < Test::Unit::TestCase def Helpers - assert(12345 == Ignition::Math::parseInt("12345"), + assert(12345 == Gz::Math::parseInt("12345"), "The string '12345' should parse to an integer") - assert(-12345 == Ignition::Math::parseInt("-12345"), + assert(-12345 == Gz::Math::parseInt("-12345"), "The string '-12345' should parse to an integer") - assert(-12345 == Ignition::Math::parseInt(" -12345")) - assert(0 == Ignition::Math::parseInt(" "), + assert(-12345 == Gz::Math::parseInt(" -12345")) + assert(0 == Gz::Math::parseInt(" "), "The string ' ' should parse to 0") - assert(23 == Ignition::Math::parseInt("23ab67"), + assert(23 == Gz::Math::parseInt("23ab67"), "The string '23ab67' should parse to 23") end end diff --git a/src/Inertial_TEST.cc b/src/Inertial_TEST.cc index 17ab090b6..76a9afbb6 100644 --- a/src/Inertial_TEST.cc +++ b/src/Inertial_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/Inertial.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// /// \brief Compare quaternions, but allow rotations of PI about any axis. @@ -500,10 +500,10 @@ TEST(Inertiald_Test, Addition) math::MassMatrix3d cubeMM3; EXPECT_TRUE(cubeMM3.SetFromBox(mass, size)); EXPECT_EQ( - ignition::math::Vector3d::One, + gz::math::Vector3d::One, cubeMM3.DiagonalMoments()); EXPECT_EQ( - ignition::math::Vector3d::Zero, + gz::math::Vector3d::Zero, cubeMM3.OffDiagonalMoments()); const math::Inertiald diagonalCubes = @@ -531,13 +531,13 @@ TEST(Inertiald_Test, Addition) // [ -1.5 -1.5 4.0 ] // // then double it to account for both cubes - EXPECT_EQ(ignition::math::Pose3d::Zero, diagonalCubes.Pose()); + EXPECT_EQ(gz::math::Pose3d::Zero, diagonalCubes.Pose()); EXPECT_DOUBLE_EQ(mass * 2.0, diagonalCubes.MassMatrix().Mass()); EXPECT_EQ( - ignition::math::Vector3d(8, 8, 8), + gz::math::Vector3d(8, 8, 8), diagonalCubes.MassMatrix().DiagonalMoments()); EXPECT_EQ( - ignition::math::Vector3d(-3, -3, -3), + gz::math::Vector3d(-3, -3, -3), diagonalCubes.MassMatrix().OffDiagonalMoments()); } } diff --git a/src/InterpolationPoint_TEST.cc b/src/InterpolationPoint_TEST.cc index e4ac0d999..88dcbe02c 100644 --- a/src/InterpolationPoint_TEST.cc +++ b/src/InterpolationPoint_TEST.cc @@ -18,7 +18,7 @@ #include -using namespace ignition; +using namespace gz; using namespace math; TEST(Interpolation, LinearInterpolate) diff --git a/src/Interval_TEST.cc b/src/Interval_TEST.cc index f378bb3e7..f03332ea3 100644 --- a/src/Interval_TEST.cc +++ b/src/Interval_TEST.cc @@ -19,7 +19,7 @@ #include "gz/math/Interval.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(IntervalTest, DefaultConstructor) diff --git a/src/Kmeans.cc b/src/Kmeans.cc index 221e36f5a..e8e3458ba 100644 --- a/src/Kmeans.cc +++ b/src/Kmeans.cc @@ -22,12 +22,12 @@ #include #include "KmeansPrivate.hh" -using namespace ignition; +using namespace gz; using namespace math; ////////////////////////////////////////////////// Kmeans::Kmeans(const std::vector &_obs) -: dataPtr(ignition::utils::MakeImpl()) +: dataPtr(gz::utils::MakeImpl()) { this->Observations(_obs); } diff --git a/src/KmeansPrivate.hh b/src/KmeansPrivate.hh index 4e77af1f1..ce475b948 100644 --- a/src/KmeansPrivate.hh +++ b/src/KmeansPrivate.hh @@ -14,19 +14,19 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_KMEANSPRIVATE_HH_ -#define IGNITION_MATH_KMEANSPRIVATE_HH_ +#ifndef GZ_MATH_KMEANSPRIVATE_HH_ +#define GZ_MATH_KMEANSPRIVATE_HH_ #include #include #include #include -namespace ignition +namespace gz { namespace math { - inline namespace IGNITION_MATH_VERSION_NAMESPACE + inline namespace GZ_MATH_VERSION_NAMESPACE { /// \internal /// \brief Private data for Kmeans class diff --git a/src/Kmeans_TEST.cc b/src/Kmeans_TEST.cc index 780e00650..64bc11afd 100644 --- a/src/Kmeans_TEST.cc +++ b/src/Kmeans_TEST.cc @@ -19,7 +19,7 @@ #include #include "gz/math/Kmeans.hh" -using namespace ignition; +using namespace gz; ////////////////////////////////////////////////// TEST(KmeansTest, Kmeans) diff --git a/src/Line2_TEST.cc b/src/Line2_TEST.cc index cef9e03e2..d166d24c7 100644 --- a/src/Line2_TEST.cc +++ b/src/Line2_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/Line2.hh" #include "gz/math/Helpers.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(Line2Test, Constructor) diff --git a/src/Line3_TEST.cc b/src/Line3_TEST.cc index d4dd57bba..92c58a15f 100644 --- a/src/Line3_TEST.cc +++ b/src/Line3_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/Line3.hh" #include "gz/math/Helpers.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(Line3Test, Constructor) diff --git a/src/MassMatrix3_TEST.cc b/src/MassMatrix3_TEST.cc index ef5750a8f..9e9dd144c 100644 --- a/src/MassMatrix3_TEST.cc +++ b/src/MassMatrix3_TEST.cc @@ -22,7 +22,7 @@ #include "gz/math/MassMatrix3.hh" #include "gz/math/Material.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(MassMatrix3dTest, Constructors) diff --git a/src/Material.cc b/src/Material.cc index d5e4b7ab8..60a39c02e 100644 --- a/src/Material.cc +++ b/src/Material.cc @@ -25,11 +25,11 @@ // Placing the kMaterialData in a separate file for conveniece and clarity. #include "MaterialType.hh" -using namespace ignition; +using namespace gz; using namespace math; // Private data for the Material class -class ignition::math::Material::Implementation +class gz::math::Material::Implementation { /// \brief Set from a kMaterialData constant. public: void SetFrom(const std::pair& _input) @@ -52,7 +52,7 @@ class ignition::math::Material::Implementation /////////////////////////////// Material::Material() -: dataPtr(ignition::utils::MakeImpl()) +: dataPtr(gz::utils::MakeImpl()) { } diff --git a/src/MaterialType.hh b/src/MaterialType.hh index aba2eb6fa..13825d2b2 100644 --- a/src/MaterialType.hh +++ b/src/MaterialType.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_SRC_MATERIAL_TYPE_HH_ -#define IGNITION_MATH_SRC_MATERIAL_TYPE_HH_ +#ifndef GZ_MATH_SRC_MATERIAL_TYPE_HH_ +#define GZ_MATH_SRC_MATERIAL_TYPE_HH_ #include #include -using namespace ignition; +using namespace gz; using namespace math; // This class is used to curly-brace initialize kMaterialData diff --git a/src/Material_TEST.cc b/src/Material_TEST.cc index b5a7b6896..c79a3a817 100644 --- a/src/Material_TEST.cc +++ b/src/Material_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/MaterialType.hh" #include "gz/math/Helpers.hh" -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// diff --git a/src/Matrix3.i b/src/Matrix3.i index d3a81c630..4a7b3a7ac 100644 --- a/src/Matrix3.i +++ b/src/Matrix3.i @@ -25,7 +25,7 @@ #include %} -namespace ignition +namespace gz { namespace math { @@ -39,27 +39,27 @@ namespace ignition public: Matrix3(T _v00, T _v01, T _v02, T _v10, T _v11, T _v12, T _v20, T _v21, T _v22); - public: explicit Matrix3(const ignition::math::Quaternion &_q); + public: explicit Matrix3(const gz::math::Quaternion &_q); public: ~Matrix3(); public: void Set(size_t _row, size_t _col, T _v); public: void Set(T _v00, T _v01, T _v02, T _v10, T _v11, T _v12, T _v20, T _v21, T _v22); - public: void SetAxes(const ignition::math::Vector3 &_xAxis, - const ignition::math::Vector3 &_yAxis, - const ignition::math::Vector3 &_zAxis); - public: void SetFromAxisAngle(const ignition::math::Vector3 &_axis, + public: void SetAxes(const gz::math::Vector3 &_xAxis, + const gz::math::Vector3 &_yAxis, + const gz::math::Vector3 &_zAxis); + public: void SetFromAxisAngle(const gz::math::Vector3 &_axis, T _angle); - public: void SetFrom2Axes(const ignition::math::Vector3 &_v1, - const ignition::math::Vector3 &_v2); + public: void SetFrom2Axes(const gz::math::Vector3 &_v1, + const gz::math::Vector3 &_v2); public: void SetCol(unsigned int _c, - const ignition::math::Vector3 &_v); + const gz::math::Vector3 &_v); public: Matrix3 operator-(const Matrix3 &_m) const; public: Matrix3 operator+(const Matrix3 &_m) const; public: Matrix3 operator*(const T &_s) const; public: Matrix3 operator*(const Matrix3 &_m) const; - public: ignition::math::Vector3 operator*( - const ignition::math::Vector3 &_vec) const; + public: gz::math::Vector3 operator*( + const gz::math::Vector3 &_vec) const; public: bool Equal(const Matrix3 &_m, const T &_tol) const; public: bool operator==(const Matrix3 &_m) const; public: inline T operator()(size_t _row, size_t _col) const; diff --git a/src/Matrix3_TEST.cc b/src/Matrix3_TEST.cc index 817c7ff76..f04824b44 100644 --- a/src/Matrix3_TEST.cc +++ b/src/Matrix3_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/Helpers.hh" #include "gz/math/Matrix3.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(Matrix3dTest, Matrix3d) diff --git a/src/Matrix3_TEST.rb b/src/Matrix3_TEST.rb index c88ac23ff..f4e4f2428 100644 --- a/src/Matrix3_TEST.rb +++ b/src/Matrix3_TEST.rb @@ -20,27 +20,27 @@ class Matrix3_TEST < Test::Unit::TestCase def test_construction - m = Ignition::Math::Matrix3d.new + m = Gz::Math::Matrix3d.new assert(m.(0, 0) == 0.0, - "Ignition::Math::Matrix3d default constructor should have (0,0)==0") + "Gz::Math::Matrix3d default constructor should have (0,0)==0") assert(m.(0, 1) == 0.0, - "Ignition::Math::Matrix3d default constructor should have (0,1)==0") + "Gz::Math::Matrix3d default constructor should have (0,1)==0") assert(m.(0, 2) == 0.0, - "Ignition::Math::Matrix3d default constructor should have (0,2)==0") + "Gz::Math::Matrix3d default constructor should have (0,2)==0") assert(m.(1, 0) == 0.0, - "Ignition::Math::Matrix3d default constructor should have (1,0)==0") + "Gz::Math::Matrix3d default constructor should have (1,0)==0") assert(m.(1, 1) == 0.0, - "Ignition::Math::Matrix3d default constructor should have (1,1)==0") + "Gz::Math::Matrix3d default constructor should have (1,1)==0") assert(m.(1, 2) == 0.0, - "Ignition::Math::Matrix3d default constructor should have (1,2)==0") + "Gz::Math::Matrix3d default constructor should have (1,2)==0") assert(m.(2, 0) == 0.0, - "Ignition::Math::Matrix3d default constructor should have (2,0)==0") + "Gz::Math::Matrix3d default constructor should have (2,0)==0") assert(m.(2, 1) == 0.0, - "Ignition::Math::Matrix3d default constructor should have (2,1)==0") + "Gz::Math::Matrix3d default constructor should have (2,1)==0") assert(m.(2, 2) == 0.0, - "Ignition::Math::Matrix3d default constructor should have (2,2)==0") + "Gz::Math::Matrix3d default constructor should have (2,2)==0") - m1 = Ignition::Math::Matrix3d.new(1, 2, 3, 4, 5, 6 , 7, 8, 9) + m1 = Gz::Math::Matrix3d.new(1, 2, 3, 4, 5, 6 , 7, 8, 9) assert(m1.(0, 0) == 1.0, "m1 should have (0,0)==1") assert(m1.(0, 1) == 2.0, diff --git a/src/Matrix4_TEST.cc b/src/Matrix4_TEST.cc index 0d498afac..a15c35afd 100644 --- a/src/Matrix4_TEST.cc +++ b/src/Matrix4_TEST.cc @@ -22,7 +22,7 @@ #include "gz/math/Quaternion.hh" #include "gz/math/Vector3.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(Matrix4dTest, Construct) diff --git a/src/MovingWindowFilter_TEST.cc b/src/MovingWindowFilter_TEST.cc index 6e298e99c..28c3531d6 100644 --- a/src/MovingWindowFilter_TEST.cc +++ b/src/MovingWindowFilter_TEST.cc @@ -19,7 +19,7 @@ #include "gz/math/Vector3.hh" #include "gz/math/MovingWindowFilter.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(MovingWindowFilterTest, SetWindowSize) @@ -39,7 +39,7 @@ TEST(MovingWindowFilterTest, FilterSomething) { math::MovingWindowFilter doubleMWF; math::MovingWindowFilter doubleMWF2; - math::MovingWindowFilter vectorMWF; + math::MovingWindowFilter vectorMWF; doubleMWF.SetWindowSize(10); doubleMWF2.SetWindowSize(2); @@ -49,7 +49,7 @@ TEST(MovingWindowFilterTest, FilterSomething) { doubleMWF.Update(static_cast(i)); doubleMWF2.Update(static_cast(i)); - ignition::math::Vector3d v(1.0*static_cast(i), + gz::math::Vector3d v(1.0*static_cast(i), 2.0*static_cast(i), 3.0*static_cast(i)); vectorMWF.Update(v); @@ -61,9 +61,9 @@ TEST(MovingWindowFilterTest, FilterSomething) EXPECT_DOUBLE_EQ(doubleMWF.Value(), sum/10.0); EXPECT_DOUBLE_EQ(doubleMWF2.Value(), (18.0+19.0)/2.0); - ignition::math::Vector3d vsum; + gz::math::Vector3d vsum; for (unsigned int i = 0; i < 20; ++i) - vsum += ignition::math::Vector3d(1.0*static_cast(i), + vsum += gz::math::Vector3d(1.0*static_cast(i), 2.0*static_cast(i), 3.0*static_cast(i)); EXPECT_EQ(vectorMWF.Value(), vsum / 20.0); diff --git a/src/OrientedBox_TEST.cc b/src/OrientedBox_TEST.cc index e4b204117..e20ab18fe 100644 --- a/src/OrientedBox_TEST.cc +++ b/src/OrientedBox_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/Angle.hh" #include "gz/math/OrientedBox.hh" -using namespace ignition; +using namespace gz; using namespace math; auto g_tolerance = 1e-6; diff --git a/src/PID.cc b/src/PID.cc index 52afe7b97..35f0b0684 100644 --- a/src/PID.cc +++ b/src/PID.cc @@ -20,7 +20,7 @@ #include "gz/math/Helpers.hh" #include "gz/math/PID.hh" -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// @@ -70,7 +70,7 @@ class PID::Implementation PID::PID(const double _p, const double _i, const double _d, const double _imax, const double _imin, const double _cmdMax, const double _cmdMin, const double _cmdOffset) -: dataPtr(ignition::utils::MakeImpl()) +: dataPtr(gz::utils::MakeImpl()) { this->Init(_p, _i, _d, _imax, _imin, _cmdMax, _cmdMin, _cmdOffset); } @@ -155,7 +155,7 @@ double PID::Update(const double _error, const std::chrono::duration &_dt) { if (_dt == std::chrono::duration(0) || - ignition::math::isnan(_error) || std::isinf(_error)) + gz::math::isnan(_error) || std::isinf(_error)) { return 0.0; } diff --git a/src/PID_TEST.cc b/src/PID_TEST.cc index d622f0864..b25998f1d 100644 --- a/src/PID_TEST.cc +++ b/src/PID_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/PID.hh" #include "gz/math/Helpers.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(PidTest, ConstructorDefault) diff --git a/src/PiecewiseScalarField3_TEST.cc b/src/PiecewiseScalarField3_TEST.cc index fc726ee4f..40e63d769 100644 --- a/src/PiecewiseScalarField3_TEST.cc +++ b/src/PiecewiseScalarField3_TEST.cc @@ -24,7 +24,7 @@ #include "gz/math/Polynomial3.hh" #include "gz/math/Vector3.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(PiecewiseScalarField3Test, Evaluate) diff --git a/src/Plane_TEST.cc b/src/Plane_TEST.cc index 3009845a2..a7970616d 100644 --- a/src/Plane_TEST.cc +++ b/src/Plane_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/Helpers.hh" #include "gz/math/Plane.hh" -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// diff --git a/src/Polynomial3_TEST.cc b/src/Polynomial3_TEST.cc index 16b05d792..e1b6f627d 100644 --- a/src/Polynomial3_TEST.cc +++ b/src/Polynomial3_TEST.cc @@ -19,7 +19,7 @@ #include "gz/math/Polynomial3.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(Polynomial3Test, DefaultConstructor) diff --git a/src/Pose3.i b/src/Pose3.i index db91e5646..31bc54d7d 100644 --- a/src/Pose3.i +++ b/src/Pose3.i @@ -25,7 +25,7 @@ #include %} -namespace ignition +namespace gz { namespace math { @@ -34,16 +34,16 @@ namespace ignition { public: static const Pose3 Zero; public: Pose3(); - public: Pose3(const ignition::math::Vector3 &_pos, - const ignition::math::Quaternion &_rot); + public: Pose3(const gz::math::Vector3 &_pos, + const gz::math::Quaternion &_rot); public: Pose3(T _x, T _y, T _z, T _roll, T _pitch, T _yaw); public: Pose3(T _x, T _y, T _z, T _qw, T _qx, T _qy, T _qz); public: Pose3(const Pose3 &_pose); public: ~Pose3(); - public: void Set(const ignition::math::Vector3 &_pos, - const ignition::math::Quaternion &_rot); - public: void Set(const ignition::math::Vector3 &_pos, - const ignition::math::Vector3 &_rpy); + public: void Set(const gz::math::Vector3 &_pos, + const gz::math::Quaternion &_rot); + public: void Set(const gz::math::Vector3 &_pos, + const gz::math::Vector3 &_rpy); public: void Set(T _x, T _y, T _z, T _roll, T _pitch, T _yaw); public: bool IsFinite() const; public: inline void Correct(); @@ -53,25 +53,25 @@ namespace ignition public: inline Pose3 operator-(const Pose3 &_pose) const; public: bool operator==(const Pose3 &_pose) const; public: Pose3 operator*(const Pose3 &_pose) const; - public: ignition::math::Vector3 CoordPositionAdd( - const ignition::math::Vector3 &_pos) const; - public: ignition::math::Vector3 CoordPositionAdd( + public: gz::math::Vector3 CoordPositionAdd( + const gz::math::Vector3 &_pos) const; + public: gz::math::Vector3 CoordPositionAdd( const Pose3 &_pose) const; - public: inline ignition::math::Vector3 CoordPositionSub( + public: inline gz::math::Vector3 CoordPositionSub( const Pose3 &_pose) const; - public: ignition::math::Quaternion CoordRotationAdd( - const ignition::math::Quaternion &_rot) const; - public: inline ignition::math::Quaternion CoordRotationSub( - const ignition::math::Quaternion &_rot) const; + public: gz::math::Quaternion CoordRotationAdd( + const gz::math::Quaternion &_rot) const; + public: inline gz::math::Quaternion CoordRotationSub( + const gz::math::Quaternion &_rot) const; public: Pose3 CoordPoseSolve(const Pose3 &_b) const; public: void Reset(); public: Pose3 RotatePositionAboutOrigin( - const ignition::math::Quaternion &_q) const; + const gz::math::Quaternion &_q) const; public: void Round(int _precision); - public: inline const ignition::math::Vector3 &Pos() const; - public: inline ignition::math::Vector3 &Pos(); - public: inline const ignition::math::Quaternion &Rot() const; - public: inline ignition::math::Quaternion &Rot(); + public: inline const gz::math::Vector3 &Pos() const; + public: inline gz::math::Vector3 &Pos(); + public: inline const gz::math::Quaternion &Rot() const; + public: inline gz::math::Quaternion &Rot(); }; %template(Pose3d) Pose3; diff --git a/src/Pose3_TEST.rb b/src/Pose3_TEST.rb index 1f60e8088..8f5a5b733 100644 --- a/src/Pose3_TEST.rb +++ b/src/Pose3_TEST.rb @@ -20,41 +20,41 @@ class Pose3_TEST < Test::Unit::TestCase def test_construction - p = Ignition::Math::Pose3d.new + p = Gz::Math::Pose3d.new assert(p.Pos().X() == 0.0, - "Ignition::Math::Pose3d default constructor should have PX==0") + "Gz::Math::Pose3d default constructor should have PX==0") assert(p.Pos().Y() == 0.0, - "Ignition::Math::Pose3d default constructor should have PY==0") + "Gz::Math::Pose3d default constructor should have PY==0") assert(p.Pos().Z() == 0.0, - "Ignition::Math::Pose3d default constructor should have PZ==0") + "Gz::Math::Pose3d default constructor should have PZ==0") assert(p.Rot().W() == 1.0, - "Ignition::Math::Pose3d default constructor should have QW==1") + "Gz::Math::Pose3d default constructor should have QW==1") assert(p.Rot().X() == 0.0, - "Ignition::Math::Pose3d default constructor should have QX==0") + "Gz::Math::Pose3d default constructor should have QX==0") assert(p.Rot().Y() == 0.0, - "Ignition::Math::Pose3d default constructor should have QY==0") + "Gz::Math::Pose3d default constructor should have QY==0") assert(p.Rot().Z() == 0.0, - "Ignition::Math::Pose3d default constructor should have QZ==0") + "Gz::Math::Pose3d default constructor should have QZ==0") - p1 = Ignition::Math::Pose3d.new( - Ignition::Math::Vector3d.new(1, 2, 3), - Ignition::Math::Quaterniond.new(0, 0, Math::PI/2.0)) + p1 = Gz::Math::Pose3d.new( + Gz::Math::Vector3d.new(1, 2, 3), + Gz::Math::Quaterniond.new(0, 0, Math::PI/2.0)) assert(p1.Pos().X() == 1.0, - "Ignition::Math::Pose3d default constructor should have PX==1") + "Gz::Math::Pose3d default constructor should have PX==1") assert(p1.Pos().Y() == 2.0, - "Ignition::Math::Pose3d default constructor should have PY==2") + "Gz::Math::Pose3d default constructor should have PY==2") assert(p1.Pos().Z() == 3.0, - "Ignition::Math::Pose3d default constructor should have PZ==3") + "Gz::Math::Pose3d default constructor should have PZ==3") assert(p1.Rot().Euler().X() == 0.0, - "Ignition::Math::Pose3d should have EulerX==0") + "Gz::Math::Pose3d should have EulerX==0") assert(p1.Rot().Euler().Y() == 0.0, - "Ignition::Math::Pose3d should have EulerY==0") + "Gz::Math::Pose3d should have EulerY==0") assert((p1.Rot().Euler().Z() - Math::PI/2.0).abs() < 1e-3, - "Ignition::Math::Pose3d should have EulerZ==PI/2") + "Gz::Math::Pose3d should have EulerZ==PI/2") end end diff --git a/src/Pose_TEST.cc b/src/Pose_TEST.cc index 9207a28bd..55c828d12 100644 --- a/src/Pose_TEST.cc +++ b/src/Pose_TEST.cc @@ -21,7 +21,7 @@ #include #include -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(PoseTest, Construction) diff --git a/src/Quaternion.i b/src/Quaternion.i index 18dd2d25a..8c26ee57c 100644 --- a/src/Quaternion.i +++ b/src/Quaternion.i @@ -25,7 +25,7 @@ #include %} -namespace ignition +namespace gz { namespace math { @@ -38,10 +38,10 @@ namespace ignition public: Quaternion(); public: Quaternion(const T &_w, const T &_x, const T &_y, const T &_z); public: Quaternion(const T &_roll, const T &_pitch, const T &_yaw); - public: Quaternion(const ignition::math::Vector3 &_axis, + public: Quaternion(const gz::math::Vector3 &_axis, const T &_angle); - public: explicit Quaternion(const ignition::math::Vector3 &_rpy); - public: explicit Quaternion(const ignition::math::Matrix3 &_mat); + public: explicit Quaternion(const gz::math::Vector3 &_rpy); + public: explicit Quaternion(const gz::math::Matrix3 &_mat); public: Quaternion(const Quaternion &_qt); public: ~Quaternion(); public: void Invert(); @@ -50,42 +50,42 @@ namespace ignition public: Quaternion Exp() const; public: void Normalize(); public: void SetFromAxisAngle(T _ax, T _ay, T _az, T _aa); - public: void SetFromAxisAngle(const ignition::math::Vector3 &_axis, + public: void SetFromAxisAngle(const gz::math::Vector3 &_axis, T _a); public: void Set(T _w, T _x, T _y, T _z); - public: void SetFromEuler(const ignition::math::Vector3 &_vec); + public: void SetFromEuler(const gz::math::Vector3 &_vec); public: void SetFromEuler(T _roll, T _pitch, T _yaw); - public: ignition::math::Vector3 Euler() const; + public: gz::math::Vector3 Euler() const; public: static Quaternion EulerToQuaternion( - const ignition::math::Vector3 &_vec); + const gz::math::Vector3 &_vec); public: static Quaternion EulerToQuaternion(T _x, T _y, T _z); public: T Roll() const; public: T Pitch() const; public: T Yaw() const; - public: void AxisAngle(ignition::math::Vector3 &_axis, + public: void AxisAngle(gz::math::Vector3 &_axis, T &_angle) const; - void SetFromMatrix(const ignition::math::Matrix3 &_mat); - public: void SetFrom2Axes(const ignition::math::Vector3 &_v1, - const ignition::math::Vector3 &_v2); + void SetFromMatrix(const gz::math::Matrix3 &_mat); + public: void SetFrom2Axes(const gz::math::Vector3 &_v1, + const gz::math::Vector3 &_v2); public: void Scale(T _scale); public: Quaternion operator+(const Quaternion &_qt) const; public: Quaternion operator-(const Quaternion &_qt) const; public: inline Quaternion operator*(const Quaternion &_q) const; public: Quaternion operator*(const T &_f) const; - public: ignition::math::Vector3 operator*( - const ignition::math::Vector3 &_v) const; + public: gz::math::Vector3 operator*( + const gz::math::Vector3 &_v) const; public: bool operator==(const Quaternion &_qt) const; public: bool Equal(const Quaternion &_qt, const T &_tol) const; public: Quaternion operator-() const; - public: inline ignition::math::Vector3 RotateVector( - const ignition::math::Vector3 &_vec) const; - public: ignition::math::Vector3 RotateVectorReverse( - const ignition::math::Vector3 &_vec) const; + public: inline gz::math::Vector3 RotateVector( + const gz::math::Vector3 &_vec) const; + public: gz::math::Vector3 RotateVectorReverse( + const gz::math::Vector3 &_vec) const; public: bool IsFinite() const; public: inline void Correct(); - public: ignition::math::Vector3 XAxis() const; - public: ignition::math::Vector3 YAxis() const; - public: ignition::math::Vector3 ZAxis() const; + public: gz::math::Vector3 XAxis() const; + public: gz::math::Vector3 YAxis() const; + public: gz::math::Vector3 ZAxis() const; public: void Round(int _precision); public: T Dot(const Quaternion &_q) const; public: static Quaternion Squad(T _fT, @@ -96,7 +96,7 @@ namespace ignition const Quaternion &_rkP, const Quaternion &_rkQ, bool _shortestPath = false); public: Quaternion Integrate( - const ignition::math::Vector3 &_angularVelocity, + const gz::math::Vector3 &_angularVelocity, const T _deltaT) const; public: inline T W() const; public: inline T X() const; diff --git a/src/Quaternion_TEST.cc b/src/Quaternion_TEST.cc index 82b9d3cb4..fe72f8ee8 100644 --- a/src/Quaternion_TEST.cc +++ b/src/Quaternion_TEST.cc @@ -25,7 +25,7 @@ #include "gz/math/Matrix4.hh" #include -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(QuaternionTest, Construction) diff --git a/src/Quaternion_TEST.rb b/src/Quaternion_TEST.rb index 4f1b3aca4..777b1fbac 100644 --- a/src/Quaternion_TEST.rb +++ b/src/Quaternion_TEST.rb @@ -20,35 +20,35 @@ class Quaternion_TEST < Test::Unit::TestCase def test_construction - q = Ignition::Math::Quaterniond.new + q = Gz::Math::Quaterniond.new assert(q.W() == 1.0, - "Ignition::Math::Quaterniond default constructor should have W==1") + "Gz::Math::Quaterniond default constructor should have W==1") assert(q.X() == 0.0, - "Ignition::Math::Quaterniond default constructor should have X==0") + "Gz::Math::Quaterniond default constructor should have X==0") assert(q.Y() == 0.0, - "Ignition::Math::Quaterniond default constructor should have Y==0") + "Gz::Math::Quaterniond default constructor should have Y==0") assert(q.Z() == 0.0, - "Ignition::Math::Quaterniond default constructor should have Z==0") + "Gz::Math::Quaterniond default constructor should have Z==0") - q1 = Ignition::Math::Quaterniond.new(1, 2, 3, 4) + q1 = Gz::Math::Quaterniond.new(1, 2, 3, 4) assert(q1.W() == 1.0, - "Ignition::Math::Quaterniond(1, 2, 3, 4) should have W==1") + "Gz::Math::Quaterniond(1, 2, 3, 4) should have W==1") assert(q1.X() == 2.0, - "Ignition::Math::Quaterniond(1, 2, 3, 4) should have X==2") + "Gz::Math::Quaterniond(1, 2, 3, 4) should have X==2") assert(q1.Y() == 3.0, - "Ignition::Math::Quaterniond(1, 2, 3, 4) should have Y==3") + "Gz::Math::Quaterniond(1, 2, 3, 4) should have Y==3") assert(q1.Z() == 4.0, - "Ignition::Math::Quaterniond default constructor should have Z==4") + "Gz::Math::Quaterniond default constructor should have Z==4") - q2 = Ignition::Math::Quaterniond.new(0, 0, 0, 0); + q2 = Gz::Math::Quaterniond.new(0, 0, 0, 0); assert(q2.W() == 0.0, - "Ignition::Math::Quaterniond(0, 0, 0, 0) should have W==0") + "Gz::Math::Quaterniond(0, 0, 0, 0) should have W==0") assert(q2.X() == 0.0, - "Ignition::Math::Quaterniond(0, 0, 0, 0) should have W==0") + "Gz::Math::Quaterniond(0, 0, 0, 0) should have W==0") assert(q2.Y() == 0.0, - "Ignition::Math::Quaterniond(0, 0, 0, 0) should have W==0") + "Gz::Math::Quaterniond(0, 0, 0, 0) should have W==0") assert(q2.Z() == 0.0, - "Ignition::Math::Quaterniond(0, 0, 0, 0) should have W==0") + "Gz::Math::Quaterniond(0, 0, 0, 0) should have W==0") # Test inverse qI = q2.Inverse() @@ -65,8 +65,8 @@ def test_construction for pitch in [-Math::PI*0.5, Math::PI*0.5] do for roll in (0..2 * Math::PI + 0.1).step(Math::PI*0.25) do for yaw in (0..2 * Math::PI + 0.1).step(Math::PI*0.25) do - qOrig = Ignition::Math::Quaterniond.new(roll, pitch, yaw) - qDerived = Ignition::Math::Quaterniond.new(qOrig.Euler()) + qOrig = Gz::Math::Quaterniond.new(roll, pitch, yaw) + qDerived = Gz::Math::Quaterniond.new(qOrig.Euler()) assert(qOrig == qDerived || qOrig == -qDerived, "Singularities should be handled correctly") end @@ -74,7 +74,7 @@ def test_construction end # Test construction from axis angle - qA = Ignition::Math::Quaterniond.new(Ignition::Math::Vector3d.new(0, 0, 1), + qA = Gz::Math::Quaterniond.new(Gz::Math::Vector3d.new(0, 0, 1), Math::PI) assert(qA.X() == 0.0, "X should equal 0") assert(qA.Y() == 0.0, "Y should equal 0") @@ -82,7 +82,7 @@ def test_construction assert((qA.W() - 0).abs < 1e-3, "W should equal 0") # Test the defined identity quaternion - qIdent = Ignition::Math::Quaterniond.Identity + qIdent = Gz::Math::Quaterniond.Identity assert(qIdent.W() == 1.0, "Identity W should equal 1") assert(qIdent.X() == 0.0, "Identity X should equal 0") assert(qIdent.Y() == 0.0, "Identity Y should equal 0") diff --git a/src/Rand.cc b/src/Rand.cc index 8aee9b392..0cb9b7b9f 100644 --- a/src/Rand.cc +++ b/src/Rand.cc @@ -27,7 +27,7 @@ #include "gz/math/Rand.hh" -using namespace ignition; +using namespace gz; using namespace math; ////////////////////////////////////////////////// diff --git a/src/Rand_TEST.cc b/src/Rand_TEST.cc index d278c3880..df31afbdc 100644 --- a/src/Rand_TEST.cc +++ b/src/Rand_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/Helpers.hh" #include "gz/math/Rand.hh" -using namespace ignition; +using namespace gz; ////////////////////////////////////////////////// TEST(RandTest, Rand) diff --git a/src/Region3_TEST.cc b/src/Region3_TEST.cc index da6486be5..2af3c1308 100644 --- a/src/Region3_TEST.cc +++ b/src/Region3_TEST.cc @@ -19,7 +19,7 @@ #include "gz/math/Region3.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(Region3Test, DefaultConstructor) diff --git a/src/RollingMean.cc b/src/RollingMean.cc index b467fe2b6..42f569842 100644 --- a/src/RollingMean.cc +++ b/src/RollingMean.cc @@ -20,10 +20,10 @@ #include #include "gz/math/RollingMean.hh" -using namespace ignition::math; +using namespace gz::math; /// \brief Private data -class ignition::math::RollingMean::Implementation +class gz::math::RollingMean::Implementation { /// \brief The window size public: size_t windowSize{10}; @@ -34,7 +34,7 @@ class ignition::math::RollingMean::Implementation ////////////////////////////////////////////////// RollingMean::RollingMean(size_t _windowSize) - : dataPtr(ignition::utils::MakeImpl()) + : dataPtr(gz::utils::MakeImpl()) { if (_windowSize > 0) this->dataPtr->windowSize = _windowSize; diff --git a/src/RollingMean_TEST.cc b/src/RollingMean_TEST.cc index 17fcc182f..4800003b8 100644 --- a/src/RollingMean_TEST.cc +++ b/src/RollingMean_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/Helpers.hh" #include "gz/math/RollingMean.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(RollingMeanTest, RollingMean) diff --git a/src/RotationSpline.cc b/src/RotationSpline.cc index fa3637428..cd57559a8 100644 --- a/src/RotationSpline.cc +++ b/src/RotationSpline.cc @@ -17,7 +17,7 @@ #include "gz/math/Quaternion.hh" #include "gz/math/RotationSpline.hh" -using namespace ignition; +using namespace gz; using namespace math; /// \internal @@ -37,7 +37,7 @@ class RotationSpline::Implementation ///////////////////////////////////////////////// RotationSpline::RotationSpline() -: dataPtr(ignition::utils::MakeImpl()) +: dataPtr(gz::utils::MakeImpl()) { } diff --git a/src/RotationSpline_TEST.cc b/src/RotationSpline_TEST.cc index dd8295afd..d01270b6c 100644 --- a/src/RotationSpline_TEST.cc +++ b/src/RotationSpline_TEST.cc @@ -22,7 +22,7 @@ #include "gz/math/Quaternion.hh" #include "gz/math/RotationSpline.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(RotationSplineTest, RotationSpline) diff --git a/src/SemanticVersion.cc b/src/SemanticVersion.cc index 02aecb1a3..500c19557 100644 --- a/src/SemanticVersion.cc +++ b/src/SemanticVersion.cc @@ -19,14 +19,14 @@ #include "gz/math/SemanticVersion.hh" -using namespace ignition; +using namespace gz; using namespace math; -namespace ignition +namespace gz { namespace math { - inline namespace IGNITION_MATH_VERSION_NAMESPACE + inline namespace GZ_MATH_VERSION_NAMESPACE { class SemanticVersion::Implementation { @@ -55,7 +55,7 @@ namespace ignition ///////////////////////////////////////////////// SemanticVersion::SemanticVersion() -: dataPtr(ignition::utils::MakeImpl()) +: dataPtr(gz::utils::MakeImpl()) { } diff --git a/src/SemanticVersion_TEST.cc b/src/SemanticVersion_TEST.cc index cc0c1a59f..6e3637ec5 100644 --- a/src/SemanticVersion_TEST.cc +++ b/src/SemanticVersion_TEST.cc @@ -19,7 +19,7 @@ #include "gz/math/SemanticVersion.hh" -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// diff --git a/src/SignalStats.cc b/src/SignalStats.cc index 964b2e230..151c40d85 100644 --- a/src/SignalStats.cc +++ b/src/SignalStats.cc @@ -19,7 +19,7 @@ #include #include "SignalStatsPrivate.hh" -using namespace ignition; +using namespace gz; using namespace math; ////////////////////////////////////////////////// diff --git a/src/SignalStatsPrivate.hh b/src/SignalStatsPrivate.hh index 65400fd63..ccb914cab 100644 --- a/src/SignalStatsPrivate.hh +++ b/src/SignalStatsPrivate.hh @@ -14,18 +14,18 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_SIGNALSTATSPRIVATE_HH_ -#define IGNITION_MATH_SIGNALSTATSPRIVATE_HH_ +#ifndef GZ_MATH_SIGNALSTATSPRIVATE_HH_ +#define GZ_MATH_SIGNALSTATSPRIVATE_HH_ #include #include #include -namespace ignition +namespace gz { namespace math { - inline namespace IGNITION_MATH_VERSION_NAMESPACE + inline namespace GZ_MATH_VERSION_NAMESPACE { /// \brief Private data class for the SignalStatistic class. class SignalStatisticPrivate diff --git a/src/SignalStats_TEST.cc b/src/SignalStats_TEST.cc index cdbc9456e..289deef78 100644 --- a/src/SignalStats_TEST.cc +++ b/src/SignalStats_TEST.cc @@ -20,7 +20,7 @@ #include #include -using namespace ignition; +using namespace gz; ////////////////////////////////////////////////// TEST(SignalStatsTest, SignalMaximumConstructor) diff --git a/src/SpeedLimiter.cc b/src/SpeedLimiter.cc index 49464a88a..20279dcfd 100644 --- a/src/SpeedLimiter.cc +++ b/src/SpeedLimiter.cc @@ -18,11 +18,11 @@ #include "gz/math/Helpers.hh" #include "gz/math/SpeedLimiter.hh" -using namespace ignition; +using namespace gz; using namespace math; /// \brief Private SpeedLimiter data class. -class ignition::math::SpeedLimiterPrivate +class gz::math::SpeedLimiterPrivate { /// \brief Minimum velocity limit. public: double minVelocity{-std::numeric_limits::infinity()}; @@ -142,7 +142,7 @@ double SpeedLimiter::LimitVelocity(double &_vel) const { const double vUnclamped = _vel; - _vel = ignition::math::clamp( + _vel = gz::math::clamp( _vel, this->dataPtr->minVelocity, this->dataPtr->maxVelocity); return _vel - vUnclamped; @@ -161,7 +161,7 @@ double SpeedLimiter::LimitAcceleration(double &_vel, double _prevVel, const double accUnclamped = (_vel - _prevVel) / dtSec; - const double accClamped = ignition::math::clamp(accUnclamped, + const double accClamped = gz::math::clamp(accUnclamped, this->dataPtr->minAcceleration, this->dataPtr->maxAcceleration); _vel = _prevVel + accClamped * dtSec; @@ -184,7 +184,7 @@ double SpeedLimiter::LimitJerk(double &_vel, double _prevVel, const double accPrev = (_prevVel - _prevPrevVel) / dtSec; const double jerkUnclamped = (accUnclamped - accPrev) / dtSec; - const double jerkClamped = ignition::math::clamp(jerkUnclamped, + const double jerkClamped = gz::math::clamp(jerkUnclamped, this->dataPtr->minJerk, this->dataPtr->maxJerk); const double accClamped = accPrev + jerkClamped * dtSec; diff --git a/src/SpeedLimiter_TEST.cc b/src/SpeedLimiter_TEST.cc index 9092e9f6a..c6a2b6d44 100644 --- a/src/SpeedLimiter_TEST.cc +++ b/src/SpeedLimiter_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/Helpers.hh" #include "gz/math/SpeedLimiter.hh" -using namespace ignition; +using namespace gz; using namespace math; using namespace std::literals::chrono_literals; diff --git a/src/Sphere_TEST.cc b/src/Sphere_TEST.cc index aa1f97a5f..ac2aac72c 100644 --- a/src/Sphere_TEST.cc +++ b/src/Sphere_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/Sphere.hh" -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// diff --git a/src/SphericalCoordinates.cc b/src/SphericalCoordinates.cc index c66d93e46..de95c0a2c 100644 --- a/src/SphericalCoordinates.cc +++ b/src/SphericalCoordinates.cc @@ -20,7 +20,7 @@ #include "gz/math/Matrix3.hh" #include "gz/math/SphericalCoordinates.hh" -using namespace ignition; +using namespace gz; using namespace math; // Parameters for EARTH_WGS84 model @@ -39,23 +39,23 @@ const double g_EarthWGS84Flattening = 1.0/298.257223563; const double g_EarthRadius = 6371000.0; // Private data for the SphericalCoordinates class. -class ignition::math::SphericalCoordinates::Implementation +class gz::math::SphericalCoordinates::Implementation { /// \brief Type of surface being used. public: SphericalCoordinates::SurfaceType surfaceType; /// \brief Latitude of reference point. - public: ignition::math::Angle latitudeReference; + public: gz::math::Angle latitudeReference; /// \brief Longitude of reference point. - public: ignition::math::Angle longitudeReference; + public: gz::math::Angle longitudeReference; /// \brief Elevation of reference point relative to sea level in meters. public: double elevationReference; /// \brief Heading offset, expressed as angle from East to /// gazebo x-axis, or equivalently from North to gazebo y-axis. - public: ignition::math::Angle headingOffset; + public: gz::math::Angle headingOffset; /// \brief Semi-major axis ellipse parameter public: double ellA; @@ -73,13 +73,13 @@ class ignition::math::SphericalCoordinates::Implementation public: double ellP; /// \brief Rotation matrix that moves ECEF to GLOBAL - public: ignition::math::Matrix3d rotECEFToGlobal; + public: gz::math::Matrix3d rotECEFToGlobal; /// \brief Rotation matrix that moves GLOBAL to ECEF - public: ignition::math::Matrix3d rotGlobalToECEF; + public: gz::math::Matrix3d rotGlobalToECEF; /// \brief Cache the ECEF position of the the origin - public: ignition::math::Vector3d origin; + public: gz::math::Vector3d origin; /// \brief Cache cosine head transform public: double cosHea; @@ -114,7 +114,7 @@ std::string SphericalCoordinates::Convert( ////////////////////////////////////////////////// SphericalCoordinates::SphericalCoordinates() - : dataPtr(ignition::utils::MakeImpl()) + : dataPtr(gz::utils::MakeImpl()) { this->SetSurface(EARTH_WGS84); this->SetElevationReference(0.0); @@ -130,10 +130,10 @@ SphericalCoordinates::SphericalCoordinates(const SurfaceType _type) ////////////////////////////////////////////////// SphericalCoordinates::SphericalCoordinates(const SurfaceType _type, - const ignition::math::Angle &_latitude, - const ignition::math::Angle &_longitude, + const gz::math::Angle &_latitude, + const gz::math::Angle &_longitude, const double _elevation, - const ignition::math::Angle &_heading) + const gz::math::Angle &_heading) : SphericalCoordinates() { // Set the reference and calculate ellipse parameters @@ -156,13 +156,13 @@ SphericalCoordinates::SurfaceType SphericalCoordinates::Surface() const } ////////////////////////////////////////////////// -ignition::math::Angle SphericalCoordinates::LatitudeReference() const +gz::math::Angle SphericalCoordinates::LatitudeReference() const { return this->dataPtr->latitudeReference; } ////////////////////////////////////////////////// -ignition::math::Angle SphericalCoordinates::LongitudeReference() const +gz::math::Angle SphericalCoordinates::LongitudeReference() const { return this->dataPtr->longitudeReference; } @@ -174,7 +174,7 @@ double SphericalCoordinates::ElevationReference() const } ////////////////////////////////////////////////// -ignition::math::Angle SphericalCoordinates::HeadingOffset() const +gz::math::Angle SphericalCoordinates::HeadingOffset() const { return this->dataPtr->headingOffset; } @@ -221,7 +221,7 @@ void SphericalCoordinates::SetSurface(const SurfaceType &_type) ////////////////////////////////////////////////// void SphericalCoordinates::SetLatitudeReference( - const ignition::math::Angle &_angle) + const gz::math::Angle &_angle) { this->dataPtr->latitudeReference = _angle; this->UpdateTransformationMatrix(); @@ -229,7 +229,7 @@ void SphericalCoordinates::SetLatitudeReference( ////////////////////////////////////////////////// void SphericalCoordinates::SetLongitudeReference( - const ignition::math::Angle &_angle) + const gz::math::Angle &_angle) { this->dataPtr->longitudeReference = _angle; this->UpdateTransformationMatrix(); @@ -243,17 +243,17 @@ void SphericalCoordinates::SetElevationReference(const double _elevation) } ////////////////////////////////////////////////// -void SphericalCoordinates::SetHeadingOffset(const ignition::math::Angle &_angle) +void SphericalCoordinates::SetHeadingOffset(const gz::math::Angle &_angle) { this->dataPtr->headingOffset.SetRadian(_angle.Radian()); this->UpdateTransformationMatrix(); } ////////////////////////////////////////////////// -ignition::math::Vector3d SphericalCoordinates::SphericalFromLocalPosition( - const ignition::math::Vector3d &_xyz) const +gz::math::Vector3d SphericalCoordinates::SphericalFromLocalPosition( + const gz::math::Vector3d &_xyz) const { - ignition::math::Vector3d result = + gz::math::Vector3d result = this->PositionTransform(_xyz, LOCAL, SPHERICAL); result.X(IGN_RTOD(result.X())); result.Y(IGN_RTOD(result.Y())); @@ -261,38 +261,38 @@ ignition::math::Vector3d SphericalCoordinates::SphericalFromLocalPosition( } ////////////////////////////////////////////////// -ignition::math::Vector3d SphericalCoordinates::LocalFromSphericalPosition( - const ignition::math::Vector3d &_xyz) const +gz::math::Vector3d SphericalCoordinates::LocalFromSphericalPosition( + const gz::math::Vector3d &_xyz) const { - ignition::math::Vector3d result = _xyz; + gz::math::Vector3d result = _xyz; result.X(IGN_DTOR(result.X())); result.Y(IGN_DTOR(result.Y())); return this->PositionTransform(result, SPHERICAL, LOCAL); } ////////////////////////////////////////////////// -ignition::math::Vector3d SphericalCoordinates::GlobalFromLocalVelocity( - const ignition::math::Vector3d &_xyz) const +gz::math::Vector3d SphericalCoordinates::GlobalFromLocalVelocity( + const gz::math::Vector3d &_xyz) const { return this->VelocityTransform(_xyz, LOCAL, GLOBAL); } ////////////////////////////////////////////////// -ignition::math::Vector3d SphericalCoordinates::LocalFromGlobalVelocity( - const ignition::math::Vector3d &_xyz) const +gz::math::Vector3d SphericalCoordinates::LocalFromGlobalVelocity( + const gz::math::Vector3d &_xyz) const { return this->VelocityTransform(_xyz, GLOBAL, LOCAL); } ////////////////////////////////////////////////// /// Based on Haversine formula (http://en.wikipedia.org/wiki/Haversine_formula). -double SphericalCoordinates::Distance(const ignition::math::Angle &_latA, - const ignition::math::Angle &_lonA, - const ignition::math::Angle &_latB, - const ignition::math::Angle &_lonB) +double SphericalCoordinates::Distance(const gz::math::Angle &_latA, + const gz::math::Angle &_lonA, + const gz::math::Angle &_latB, + const gz::math::Angle &_lonB) { - ignition::math::Angle dLat = _latB - _latA; - ignition::math::Angle dLon = _lonB - _lonA; + gz::math::Angle dLat = _latB - _latA; + gz::math::Angle dLon = _lonB - _lonA; double a = sin(dLat.Radian() / 2) * sin(dLat.Radian() / 2) + sin(dLon.Radian() / 2) * sin(dLon.Radian() / 2) * @@ -315,7 +315,7 @@ void SphericalCoordinates::UpdateTransformationMatrix() // Create a rotation matrix that moves ECEF to GLOBAL // http://www.navipedia.net/index.php/ // Transformations_between_ECEF_and_ENU_coordinates - this->dataPtr->rotECEFToGlobal = ignition::math::Matrix3d( + this->dataPtr->rotECEFToGlobal = gz::math::Matrix3d( -sinLon, cosLon, 0.0, -cosLon * sinLat, -sinLon * sinLat, cosLat, cosLon * cosLat, sinLon * cosLat, sinLat); @@ -323,7 +323,7 @@ void SphericalCoordinates::UpdateTransformationMatrix() // Create a rotation matrix that moves GLOBAL to ECEF // http://www.navipedia.net/index.php/ // Transformations_between_ECEF_and_ENU_coordinates - this->dataPtr->rotGlobalToECEF = ignition::math::Matrix3d( + this->dataPtr->rotGlobalToECEF = gz::math::Matrix3d( -sinLon, -cosLon * sinLat, cosLon * cosLat, cosLon, -sinLon * sinLat, sinLon * cosLat, 0, cosLat, sinLat); @@ -337,7 +337,7 @@ void SphericalCoordinates::UpdateTransformationMatrix() this->dataPtr->sinHea = sin(-this->dataPtr->headingOffset.Radian()); // Cache the ECEF coordinate of the origin - this->dataPtr->origin = ignition::math::Vector3d( + this->dataPtr->origin = gz::math::Vector3d( this->dataPtr->latitudeReference.Radian(), this->dataPtr->longitudeReference.Radian(), this->dataPtr->elevationReference); @@ -346,11 +346,11 @@ void SphericalCoordinates::UpdateTransformationMatrix() } ///////////////////////////////////////////////// -ignition::math::Vector3d SphericalCoordinates::PositionTransform( - const ignition::math::Vector3d &_pos, +gz::math::Vector3d SphericalCoordinates::PositionTransform( + const gz::math::Vector3d &_pos, const CoordinateType &_in, const CoordinateType &_out) const { - ignition::math::Vector3d tmp = _pos; + gz::math::Vector3d tmp = _pos; // Cache trig results double cosLat = cos(_pos.X()); @@ -455,7 +455,7 @@ ignition::math::Vector3d SphericalCoordinates::PositionTransform( case LOCAL2: tmp = this->dataPtr->rotECEFToGlobal * (tmp - this->dataPtr->origin); - tmp = ignition::math::Vector3d( + tmp = gz::math::Vector3d( tmp.X() * this->dataPtr->cosHea - tmp.Y() * this->dataPtr->sinHea, tmp.X() * this->dataPtr->sinHea + tmp.Y() * this->dataPtr->cosHea, tmp.Z()); @@ -474,8 +474,8 @@ ignition::math::Vector3d SphericalCoordinates::PositionTransform( } ////////////////////////////////////////////////// -ignition::math::Vector3d SphericalCoordinates::VelocityTransform( - const ignition::math::Vector3d &_vel, +gz::math::Vector3d SphericalCoordinates::VelocityTransform( + const gz::math::Vector3d &_vel, const CoordinateType &_in, const CoordinateType &_out) const { // Sanity check -- velocity should not be expressed in spherical coordinates @@ -485,7 +485,7 @@ ignition::math::Vector3d SphericalCoordinates::VelocityTransform( } // Intermediate data type - ignition::math::Vector3d tmp = _vel; + gz::math::Vector3d tmp = _vel; // First, convert to an ECEF vector switch (_in) @@ -534,7 +534,7 @@ ignition::math::Vector3d SphericalCoordinates::VelocityTransform( case LOCAL: case LOCAL2: tmp = this->dataPtr->rotECEFToGlobal * tmp; - tmp = ignition::math::Vector3d( + tmp = gz::math::Vector3d( tmp.X() * this->dataPtr->cosHea - tmp.Y() * this->dataPtr->sinHea, tmp.X() * this->dataPtr->sinHea + tmp.Y() * this->dataPtr->cosHea, tmp.Z()); diff --git a/src/SphericalCoordinates_TEST.cc b/src/SphericalCoordinates_TEST.cc index e6297d688..f0e4b0191 100644 --- a/src/SphericalCoordinates_TEST.cc +++ b/src/SphericalCoordinates_TEST.cc @@ -18,7 +18,7 @@ #include "gz/math/SphericalCoordinates.hh" -using namespace ignition; +using namespace gz; ////////////////////////////////////////////////// // Test different constructors, default parameters @@ -32,9 +32,9 @@ TEST(SphericalCoordinatesTest, Constructor) { math::SphericalCoordinates sc; EXPECT_EQ(sc.Surface(), st); - EXPECT_EQ(sc.LatitudeReference(), ignition::math::Angle()); - EXPECT_EQ(sc.LongitudeReference(), ignition::math::Angle()); - EXPECT_EQ(sc.HeadingOffset(), ignition::math::Angle()); + EXPECT_EQ(sc.LatitudeReference(), gz::math::Angle()); + EXPECT_EQ(sc.LongitudeReference(), gz::math::Angle()); + EXPECT_EQ(sc.HeadingOffset(), gz::math::Angle()); EXPECT_NEAR(sc.ElevationReference(), 0.0, 1e-6); } @@ -42,15 +42,15 @@ TEST(SphericalCoordinatesTest, Constructor) { math::SphericalCoordinates sc(st); EXPECT_EQ(sc.Surface(), st); - EXPECT_EQ(sc.LatitudeReference(), ignition::math::Angle()); - EXPECT_EQ(sc.LongitudeReference(), ignition::math::Angle()); - EXPECT_EQ(sc.HeadingOffset(), ignition::math::Angle()); + EXPECT_EQ(sc.LatitudeReference(), gz::math::Angle()); + EXPECT_EQ(sc.LongitudeReference(), gz::math::Angle()); + EXPECT_EQ(sc.HeadingOffset(), gz::math::Angle()); EXPECT_NEAR(sc.ElevationReference(), 0.0, 1e-6); } // All arguments { - ignition::math::Angle lat(0.3), lon(-1.2), heading(0.5); + gz::math::Angle lat(0.3), lon(-1.2), heading(0.5); double elev = 354.1; math::SphericalCoordinates sc(st, lat, lon, elev, heading); EXPECT_EQ(sc.Surface(), st); @@ -94,13 +94,13 @@ TEST(SphericalCoordinatesTest, SetFunctions) // Default parameters math::SphericalCoordinates sc; EXPECT_EQ(sc.Surface(), st); - EXPECT_EQ(sc.LatitudeReference(), ignition::math::Angle()); - EXPECT_EQ(sc.LongitudeReference(), ignition::math::Angle()); - EXPECT_EQ(sc.HeadingOffset(), ignition::math::Angle()); + EXPECT_EQ(sc.LatitudeReference(), gz::math::Angle()); + EXPECT_EQ(sc.LongitudeReference(), gz::math::Angle()); + EXPECT_EQ(sc.HeadingOffset(), gz::math::Angle()); EXPECT_NEAR(sc.ElevationReference(), 0.0, 1e-6); { - ignition::math::Angle lat(0.3), lon(-1.2), heading(0.5); + gz::math::Angle lat(0.3), lon(-1.2), heading(0.5); double elev = 354.1; sc.SetSurface(st); sc.SetLatitudeReference(lat); @@ -126,8 +126,8 @@ TEST(SphericalCoordinatesTest, CoordinateTransforms) { // Parameters - ignition::math::Angle lat(0.3), lon(-1.2), - heading(ignition::math::Angle::HalfPi); + gz::math::Angle lat(0.3), lon(-1.2), + heading(gz::math::Angle::HalfPi); double elev = 354.1; math::SphericalCoordinates sc(st, lat, lon, elev, heading); @@ -136,9 +136,9 @@ TEST(SphericalCoordinatesTest, CoordinateTransforms) // Heading 90: X == North, Y == West , Z == Up { // local frame - ignition::math::Vector3d xyz; + gz::math::Vector3d xyz; // east, north, up - ignition::math::Vector3d enu; + gz::math::Vector3d enu; xyz.Set(1, 0, 0); enu = sc.GlobalFromLocalVelocity(xyz); @@ -168,9 +168,9 @@ TEST(SphericalCoordinatesTest, CoordinateTransforms) // Check SphericalFromLocal { // local frame - ignition::math::Vector3d xyz; + gz::math::Vector3d xyz; // spherical coordinates - ignition::math::Vector3d sph; + gz::math::Vector3d sph; // No offset xyz.Set(0, 0, 0); @@ -193,7 +193,7 @@ TEST(SphericalCoordinatesTest, CoordinateTransforms) // no change in longitude EXPECT_NEAR(sph.Z(), 3507.024791, 1e-6); - ignition::math::Vector3d xyz2 = sc.LocalFromSphericalPosition(sph); + gz::math::Vector3d xyz2 = sc.LocalFromSphericalPosition(sph); EXPECT_EQ(xyz, xyz2); } @@ -203,11 +203,11 @@ TEST(SphericalCoordinatesTest, CoordinateTransforms) // > gdaltransform -s_srs WGS84 -t_srs EPSG:4978 // > latitude longitude altitude // > X Y Z - ignition::math::Vector3d tmp; - ignition::math::Vector3d osrf_s(37.3877349, -122.0651166, 32.0); - ignition::math::Vector3d osrf_e( + gz::math::Vector3d tmp; + gz::math::Vector3d osrf_s(37.3877349, -122.0651166, 32.0); + gz::math::Vector3d osrf_e( -2693701.91434394, -4299942.14687992, 3851691.0393571); - ignition::math::Vector3d goog_s(37.4216719, -122.0821853, 30.0); + gz::math::Vector3d goog_s(37.4216719, -122.0821853, 30.0); // Local tangent plane coordinates (ENU = GLOBAL) coordinates of // Google when OSRF is taken as the origin: @@ -215,16 +215,16 @@ TEST(SphericalCoordinatesTest, CoordinateTransforms) // +lat_0=37.3877349 +lon_0=-122.0651166 +k=1 +x_0=0 +y_0=0 // > -122.0821853 37.4216719 (LON,LAT) // > -1510.88 3766.64 (EAST,NORTH) - ignition::math::Vector3d vec(-1510.88, 3766.64, -3.29); + gz::math::Vector3d vec(-1510.88, 3766.64, -3.29); // Convert degrees to radians osrf_s.X() *= 0.0174532925; osrf_s.Y() *= 0.0174532925; // Set the ORIGIN to be the Open Source Robotics Foundation - math::SphericalCoordinates sc2(st, ignition::math::Angle(osrf_s.X()), - ignition::math::Angle(osrf_s.Y()), osrf_s.Z(), - ignition::math::Angle::Zero); + math::SphericalCoordinates sc2(st, gz::math::Angle(osrf_s.X()), + gz::math::Angle(osrf_s.Y()), osrf_s.Z(), + gz::math::Angle::Zero); // Check that SPHERICAL -> ECEF works tmp = sc2.PositionTransform(osrf_s, @@ -260,16 +260,16 @@ TEST(SphericalCoordinatesTest, CoordinateTransforms) // Give no heading offset to confirm ENU frame { - ignition::math::Angle lat(0.3), lon(-1.2), heading(0.0); + gz::math::Angle lat(0.3), lon(-1.2), heading(0.0); double elev = 354.1; math::SphericalCoordinates sc(st, lat, lon, elev, heading); // Check GlobalFromLocal with no heading offset { // local frame - ignition::math::Vector3d xyz; + gz::math::Vector3d xyz; // east, north, up - ignition::math::Vector3d enu; + gz::math::Vector3d enu; xyz.Set(1, 0, 0); enu = sc.VelocityTransform(xyz, @@ -306,7 +306,7 @@ TEST(SphericalCoordinatesTest, CoordinateTransforms) // Test distance TEST(SphericalCoordinatesTest, Distance) { - ignition::math::Angle latA, longA, latB, longB; + gz::math::Angle latA, longA, latB, longB; latA.SetDegree(46.250944); longA.SetDegree(-122.249972); latB.SetDegree(46.124953); @@ -392,18 +392,18 @@ TEST(SphericalCoordinatesTest, EqualityOps) // Default surface type math::SphericalCoordinates::SurfaceType st = math::SphericalCoordinates::EARTH_WGS84; - ignition::math::Angle lat(0.3), lon(-1.2), heading(0.5); + gz::math::Angle lat(0.3), lon(-1.2), heading(0.5); double elev = 354.1; math::SphericalCoordinates sc1(st, lat, lon, elev, heading); math::SphericalCoordinates sc2(st, lat, lon, elev, heading); EXPECT_TRUE(sc1 == sc2); EXPECT_FALSE(sc1 != sc2); - math::SphericalCoordinates sc3(st, ignition::math::Angle::Zero, lon, elev, + math::SphericalCoordinates sc3(st, gz::math::Angle::Zero, lon, elev, heading); EXPECT_FALSE(sc1 == sc3); EXPECT_TRUE(sc1 != sc3); - math::SphericalCoordinates sc4(st, lat, ignition::math::Angle::Zero, elev, + math::SphericalCoordinates sc4(st, lat, gz::math::Angle::Zero, elev, heading); EXPECT_FALSE(sc1 == sc4); EXPECT_TRUE(sc1 != sc4); @@ -411,7 +411,7 @@ TEST(SphericalCoordinatesTest, EqualityOps) EXPECT_FALSE(sc1 == sc5); EXPECT_TRUE(sc1 != sc5); math::SphericalCoordinates sc6(st, lat, lon, elev, - ignition::math::Angle::Zero); + gz::math::Angle::Zero); EXPECT_FALSE(sc1 == sc6); EXPECT_TRUE(sc1 != sc6); } @@ -423,7 +423,7 @@ TEST(SphericalCoordinatesTest, AssignmentOp) // Default surface type math::SphericalCoordinates::SurfaceType st = math::SphericalCoordinates::EARTH_WGS84; - ignition::math::Angle lat(0.3), lon(-1.2), heading(0.5); + gz::math::Angle lat(0.3), lon(-1.2), heading(0.5); double elev = 354.1; math::SphericalCoordinates sc1(st, lat, lon, elev, heading); @@ -623,7 +623,7 @@ TEST(SphericalCoordinatesTest, WithHeading) TEST(SphericalCoordinatesTest, Inverse) { auto st = math::SphericalCoordinates::EARTH_WGS84; - ignition::math::Angle lat(0.3), lon(-1.2), heading(0.5); + gz::math::Angle lat(0.3), lon(-1.2), heading(0.5); double elev = 354.1; math::SphericalCoordinates sc(st, lat, lon, elev, heading); diff --git a/src/Spline.cc b/src/Spline.cc index b4dfbedec..10853a250 100644 --- a/src/Spline.cc +++ b/src/Spline.cc @@ -23,12 +23,12 @@ #include "SplinePrivate.hh" -using namespace ignition; +using namespace gz; using namespace math; /////////////////////////////////////////////////////////// Spline::Spline() - : dataPtr(ignition::utils::MakeImpl()) + : dataPtr(gz::utils::MakeImpl()) { } diff --git a/src/SplinePrivate.cc b/src/SplinePrivate.cc index 570acf9dd..df1ef6d18 100644 --- a/src/SplinePrivate.cc +++ b/src/SplinePrivate.cc @@ -19,11 +19,11 @@ #include "SplinePrivate.hh" -namespace ignition +namespace gz { namespace math { -inline namespace IGNITION_MATH_VERSION_NAMESPACE +inline namespace GZ_MATH_VERSION_NAMESPACE { /////////////////////////////////////////////////////////// Vector4d PolynomialPowers(const unsigned int _order, diff --git a/src/SplinePrivate.hh b/src/SplinePrivate.hh index fea4d391b..287975f28 100644 --- a/src/SplinePrivate.hh +++ b/src/SplinePrivate.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_SPLINEPRIVATE_HH_ -#define IGNITION_MATH_SPLINEPRIVATE_HH_ +#ifndef GZ_MATH_SPLINEPRIVATE_HH_ +#define GZ_MATH_SPLINEPRIVATE_HH_ #include #include @@ -25,11 +25,11 @@ #include #include -namespace ignition +namespace gz { namespace math { - inline namespace IGNITION_MATH_VERSION_NAMESPACE + inline namespace GZ_MATH_VERSION_NAMESPACE { /// \brief Control point representation for /// polynomial interpolation, defined in terms @@ -63,7 +63,7 @@ namespace ignition { // Workaround to compare the two vector of vectors in MSVC 2013 // and MSVC 2015. See - // https://github.com/ignitionrobotics/ign-math/issues/70 + // https://github.com/gazebosim/gz-math/issues/70 if (this->derivatives.size() != _other.derivatives.size()) return false; diff --git a/src/Spline_TEST.cc b/src/Spline_TEST.cc index a1bf856c9..1cbd627f3 100644 --- a/src/Spline_TEST.cc +++ b/src/Spline_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/Vector3.hh" #include "gz/math/Spline.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(SplineTest, Spline) diff --git a/src/Stopwatch.cc b/src/Stopwatch.cc index 2e6474975..4d407c593 100644 --- a/src/Stopwatch.cc +++ b/src/Stopwatch.cc @@ -17,10 +17,10 @@ #include #include "gz/math/Stopwatch.hh" -using namespace ignition::math; +using namespace gz::math; // Private data class -class ignition::math::Stopwatch::Implementation +class gz::math::Stopwatch::Implementation { /// \brief True if the real time clock is running. public: bool running = false; @@ -40,7 +40,7 @@ class ignition::math::Stopwatch::Implementation ////////////////////////////////////////////////// Stopwatch::Stopwatch() - : dataPtr(ignition::utils::MakeImpl()) + : dataPtr(gz::utils::MakeImpl()) { } diff --git a/src/Stopwatch_TEST.cc b/src/Stopwatch_TEST.cc index b2565df69..8367d6432 100644 --- a/src/Stopwatch_TEST.cc +++ b/src/Stopwatch_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/Stopwatch.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// // Helper function that runs a few tests @@ -42,7 +42,7 @@ void runTimer(math::Stopwatch &_time) // The start time should be greater than the stop time. EXPECT_GT(_time.StartTime(), _time.StopTime()); // The elapsed stop time should still be zero. - EXPECT_EQ(ignition::math::clock::duration::zero(), + EXPECT_EQ(gz::math::clock::duration::zero(), _time.ElapsedStopTime()); // Wait for some time... @@ -98,8 +98,8 @@ TEST(Stopwatch, Constructor) EXPECT_FALSE(watch.Running()); EXPECT_EQ(watch.StopTime(), watch.StartTime()); - EXPECT_EQ(ignition::math::clock::duration::zero(), watch.ElapsedRunTime()); - EXPECT_EQ(ignition::math::clock::duration::zero(), watch.ElapsedStopTime()); + EXPECT_EQ(gz::math::clock::duration::zero(), watch.ElapsedRunTime()); + EXPECT_EQ(gz::math::clock::duration::zero(), watch.ElapsedStopTime()); runTimer(watch); @@ -144,8 +144,8 @@ TEST(Stopwatch, StartStopReset) EXPECT_FALSE(watch.Running()); EXPECT_EQ(watch.StopTime(), watch.StartTime()); - EXPECT_EQ(ignition::math::clock::duration::zero(), watch.ElapsedRunTime()); - EXPECT_EQ(ignition::math::clock::duration::zero(), watch.ElapsedStopTime()); + EXPECT_EQ(gz::math::clock::duration::zero(), watch.ElapsedRunTime()); + EXPECT_EQ(gz::math::clock::duration::zero(), watch.ElapsedStopTime()); runTimer(watch); @@ -154,8 +154,8 @@ TEST(Stopwatch, StartStopReset) watch.Start(true); EXPECT_TRUE(watch.Running()); EXPECT_LT(watch.StopTime(), watch.StartTime()); - EXPECT_NE(ignition::math::clock::duration::zero(), watch.ElapsedRunTime()); - EXPECT_EQ(ignition::math::clock::duration::zero(), watch.ElapsedStopTime()); + EXPECT_NE(gz::math::clock::duration::zero(), watch.ElapsedRunTime()); + EXPECT_EQ(gz::math::clock::duration::zero(), watch.ElapsedStopTime()); } ///////////////////////////////////////////////// diff --git a/src/Temperature.cc b/src/Temperature.cc index d1772d195..7ecc0b594 100644 --- a/src/Temperature.cc +++ b/src/Temperature.cc @@ -21,18 +21,18 @@ #include /// \brief Private data for the Temperature class. -class ignition::math::Temperature::Implementation +class gz::math::Temperature::Implementation { /// \brief Temperature value in Kelvin. public: double kelvin{0.0}; }; -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// Temperature::Temperature() -: dataPtr(ignition::utils::MakeImpl()) +: dataPtr(gz::utils::MakeImpl()) { } @@ -235,13 +235,13 @@ const Temperature &Temperature::operator/=(const Temperature &_temp) ///////////////////////////////////////////////// bool Temperature::operator==(const Temperature &_temp) const { - return ignition::math::equal(this->dataPtr->kelvin, _temp.Kelvin()); + return gz::math::equal(this->dataPtr->kelvin, _temp.Kelvin()); } ///////////////////////////////////////////////// bool Temperature::operator==(double _temp) const { - return ignition::math::equal(this->dataPtr->kelvin, _temp); + return gz::math::equal(this->dataPtr->kelvin, _temp); } ///////////////////////////////////////////////// diff --git a/src/Temperature.i b/src/Temperature.i index d150bf0a0..7df174e27 100644 --- a/src/Temperature.i +++ b/src/Temperature.i @@ -20,7 +20,7 @@ #include %} -namespace ignition +namespace gz { namespace math { diff --git a/src/Temperature_TEST.cc b/src/Temperature_TEST.cc index bb03a6377..2db33a89f 100644 --- a/src/Temperature_TEST.cc +++ b/src/Temperature_TEST.cc @@ -18,7 +18,7 @@ #include "gz/math/Temperature.hh" -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// diff --git a/src/Temperature_TEST.rb b/src/Temperature_TEST.rb index 210266487..417c3d96e 100644 --- a/src/Temperature_TEST.rb +++ b/src/Temperature_TEST.rb @@ -20,7 +20,7 @@ class Temperature_TEST < Test::Unit::TestCase def test_construction - tmp = Ignition::Math::Temperature.new + tmp = Gz::Math::Temperature.new assert(tmp.Kelvin() == 0.0, "Temperature::Kelvin() should equal zero") @@ -29,14 +29,14 @@ def test_construction assert(tmp.Kelvin() == 123.5, "Temperature::Kelvin() should equal 123.5") - tmp2 = Ignition::Math::Temperature.new(123.5) + tmp2 = Gz::Math::Temperature.new(123.5) assert(tmp == tmp2, "Both temperatures should be the same.") tmp2.SetCelsius(123.6) assert(tmp != tmp2, "Both temperatures should not be the same.") assert(tmp < tmp2, "123.6K should be less than 123.6C") - assert(Ignition::Math::Temperature::CelsiusToKelvin(123.6) == tmp2.Kelvin(), + assert(Gz::Math::Temperature::CelsiusToKelvin(123.6) == tmp2.Kelvin(), "123.6C convert to Kelvin should equal tmp2" ) end end diff --git a/src/Triangle3_TEST.cc b/src/Triangle3_TEST.cc index 92293e506..6748ab648 100644 --- a/src/Triangle3_TEST.cc +++ b/src/Triangle3_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/Triangle3.hh" #include "gz/math/Helpers.hh" -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// diff --git a/src/Triangle_TEST.cc b/src/Triangle_TEST.cc index 25097de05..7581c39ed 100644 --- a/src/Triangle_TEST.cc +++ b/src/Triangle_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/Triangle.hh" #include "gz/math/Helpers.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(TriangleTest, Constructor) diff --git a/src/Vector2_TEST.cc b/src/Vector2_TEST.cc index 5116babbf..d5eaa8c3d 100644 --- a/src/Vector2_TEST.cc +++ b/src/Vector2_TEST.cc @@ -21,7 +21,7 @@ #include "gz/math/Helpers.hh" #include "gz/math/Vector2.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(Vector2Test, Construction) diff --git a/src/Vector3Stats.cc b/src/Vector3Stats.cc index 346cd59ce..21a652fed 100644 --- a/src/Vector3Stats.cc +++ b/src/Vector3Stats.cc @@ -16,7 +16,7 @@ */ #include -using namespace ignition; +using namespace gz; using namespace math; /// \brief Private data class for the Vector3Stats class. @@ -37,7 +37,7 @@ class Vector3Stats::Implementation ////////////////////////////////////////////////// Vector3Stats::Vector3Stats() - : dataPtr(ignition::utils::MakeImpl()) + : dataPtr(gz::utils::MakeImpl()) { } diff --git a/src/Vector3Stats_TEST.cc b/src/Vector3Stats_TEST.cc index d6c799a39..b720e989e 100644 --- a/src/Vector3Stats_TEST.cc +++ b/src/Vector3Stats_TEST.cc @@ -19,7 +19,7 @@ #include -using namespace ignition; +using namespace gz; class Vector3StatsTest : public ::testing::Test { diff --git a/src/Vector3_TEST.cc b/src/Vector3_TEST.cc index 0c62f571b..30e38ba12 100644 --- a/src/Vector3_TEST.cc +++ b/src/Vector3_TEST.cc @@ -23,7 +23,7 @@ #include "gz/math/Helpers.hh" #include "gz/math/Vector3.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(Vector3dTest, Construction) diff --git a/src/Vector4_TEST.cc b/src/Vector4_TEST.cc index 58455e2a3..61b59c7a1 100644 --- a/src/Vector4_TEST.cc +++ b/src/Vector4_TEST.cc @@ -21,7 +21,7 @@ #include "gz/math/Matrix4.hh" #include "gz/math/Vector4.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(Vector4dTest, Construction) diff --git a/src/VolumetricGridLookupField_TEST.cc b/src/VolumetricGridLookupField_TEST.cc index cf7a6555b..2f88af89a 100644 --- a/src/VolumetricGridLookupField_TEST.cc +++ b/src/VolumetricGridLookupField_TEST.cc @@ -19,7 +19,7 @@ #include #include #include -using namespace ignition; +using namespace gz; using namespace math; diff --git a/src/graph/Edge_TEST.cc b/src/graph/Edge_TEST.cc index ec3b0c3e7..85486b431 100644 --- a/src/graph/Edge_TEST.cc +++ b/src/graph/Edge_TEST.cc @@ -22,7 +22,7 @@ #include "gz/math/graph/Edge.hh" #include "gz/math/graph/Vertex.hh" -using namespace ignition; +using namespace gz; using namespace math; using namespace graph; diff --git a/src/graph/GraphAlgorithms_TEST.cc b/src/graph/GraphAlgorithms_TEST.cc index 89acff4aa..1130f7e94 100644 --- a/src/graph/GraphAlgorithms_TEST.cc +++ b/src/graph/GraphAlgorithms_TEST.cc @@ -21,7 +21,7 @@ #include "gz/math/graph/Graph.hh" #include "gz/math/graph/GraphAlgorithms.hh" -using namespace ignition; +using namespace gz; using namespace math; using namespace graph; diff --git a/src/graph/GraphDirected_TEST.cc b/src/graph/GraphDirected_TEST.cc index ae40602ed..f9f338383 100644 --- a/src/graph/GraphDirected_TEST.cc +++ b/src/graph/GraphDirected_TEST.cc @@ -21,7 +21,7 @@ #include "gz/math/graph/Graph.hh" -using namespace ignition; +using namespace gz; using namespace math; using namespace graph; diff --git a/src/graph/GraphUndirected_TEST.cc b/src/graph/GraphUndirected_TEST.cc index 20aba5948..a49ee4337 100644 --- a/src/graph/GraphUndirected_TEST.cc +++ b/src/graph/GraphUndirected_TEST.cc @@ -23,7 +23,7 @@ #include "gz/math/graph/Graph.hh" -using namespace ignition; +using namespace gz; using namespace math; using namespace graph; diff --git a/src/graph/Graph_TEST.cc b/src/graph/Graph_TEST.cc index 2ec96881d..01fb7fbac 100644 --- a/src/graph/Graph_TEST.cc +++ b/src/graph/Graph_TEST.cc @@ -20,7 +20,7 @@ #include "gz/math/graph/Graph.hh" -using namespace ignition; +using namespace gz; using namespace math; using namespace graph; diff --git a/src/graph/Vertex_TEST.cc b/src/graph/Vertex_TEST.cc index 49be7de3c..b0b9030ff 100644 --- a/src/graph/Vertex_TEST.cc +++ b/src/graph/Vertex_TEST.cc @@ -21,7 +21,7 @@ #include "gz/math/graph/Vertex.hh" -using namespace ignition; +using namespace gz; using namespace math; using namespace graph; diff --git a/src/python_pybind11/src/Angle.cc b/src/python_pybind11/src/Angle.cc index 32b9f90f2..b04760b35 100644 --- a/src/python_pybind11/src/Angle.cc +++ b/src/python_pybind11/src/Angle.cc @@ -25,7 +25,7 @@ using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { @@ -33,7 +33,7 @@ namespace python { void defineMathAngle(py::module &m, const std::string &typestr) { - using Class = ignition::math::Angle; + using Class = gz::math::Angle; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -94,4 +94,4 @@ void defineMathAngle(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/Angle.hh b/src/python_pybind11/src/Angle.hh index 9626eee7d..d8fbfff2b 100644 --- a/src/python_pybind11/src/Angle.hh +++ b/src/python_pybind11/src/Angle.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_PYTHON__ANGLE_HPP_ -#define IGNITION_MATH_PYTHON__ANGLE_HPP_ +#ifndef GZ_MATH_PYTHON__ANGLE_HPP_ +#define GZ_MATH_PYTHON__ANGLE_HPP_ #include #include @@ -24,13 +24,13 @@ namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Angle +/// Define a pybind11 wrapper for an gz::math::Angle /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -38,6 +38,6 @@ namespace python void defineMathAngle(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__ANGLE_HPP_ +#endif // GZ_MATH_PYTHON__ANGLE_HPP_ diff --git a/src/python_pybind11/src/AxisAlignedBox.cc b/src/python_pybind11/src/AxisAlignedBox.cc index 5b58fc528..8d2468c0d 100644 --- a/src/python_pybind11/src/AxisAlignedBox.cc +++ b/src/python_pybind11/src/AxisAlignedBox.cc @@ -27,7 +27,7 @@ using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { @@ -35,7 +35,7 @@ namespace python { void defineMathAxisAlignedBox(py::module &m, const std::string &typestr) { - using Class = ignition::math::AxisAlignedBox; + using Class = gz::math::AxisAlignedBox; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -50,8 +50,8 @@ void defineMathAxisAlignedBox(py::module &m, const std::string &typestr) .def(py::init()) .def(py::init()) - .def(py::init()) + .def(py::init()) .def("x_length", &Class::XLength, "Get the length along the x dimension") @@ -75,8 +75,8 @@ void defineMathAxisAlignedBox(py::module &m, const std::string &typestr) "Get the volume of the box in m^3.") .def(py::self + py::self) .def(py::self += py::self) - .def(py::self + ignition::math::Vector3d()) - .def(py::self - ignition::math::Vector3d()) + .def(py::self + gz::math::Vector3d()) + .def(py::self - gz::math::Vector3d()) .def(py::self == py::self) .def(py::self != py::self) .def("min", @@ -120,4 +120,4 @@ void defineMathAxisAlignedBox(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/AxisAlignedBox.hh b/src/python_pybind11/src/AxisAlignedBox.hh index 057852353..c7f962d6a 100644 --- a/src/python_pybind11/src/AxisAlignedBox.hh +++ b/src/python_pybind11/src/AxisAlignedBox.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_PYTHON__AXISALIGNEDBOX_HPP_ -#define IGNITION_MATH_PYTHON__AXISALIGNEDBOX_HPP_ +#ifndef GZ_MATH_PYTHON__AXISALIGNEDBOX_HPP_ +#define GZ_MATH_PYTHON__AXISALIGNEDBOX_HPP_ #include @@ -23,13 +23,13 @@ namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::AxisAlignedBox +/// Define a pybind11 wrapper for an gz::math::AxisAlignedBox /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -37,6 +37,6 @@ namespace python void defineMathAxisAlignedBox(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__AXISALIGNEDBOX_HPP_ +#endif // GZ_MATH_PYTHON__AXISALIGNEDBOX_HPP_ diff --git a/src/python_pybind11/src/Box.hh b/src/python_pybind11/src/Box.hh index baf5cb590..9b611132d 100644 --- a/src/python_pybind11/src/Box.hh +++ b/src/python_pybind11/src/Box.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__BOX_HH_ -#define IGNITION_MATH_PYTHON__BOX_HH_ +#ifndef GZ_MATH_PYTHON__BOX_HH_ +#define GZ_MATH_PYTHON__BOX_HH_ #include #include @@ -30,13 +30,13 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Box +/// Define a pybind11 wrapper for an gz::math::Box /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -45,7 +45,7 @@ template void defineMathBox(py::module &m, const std::string &typestr) { - using Class = ignition::math::Box; + using Class = gz::math::Box; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -53,18 +53,18 @@ void defineMathBox(py::module &m, const std::string &typestr) py::dynamic_attr()) .def(py::init<>()) .def(py::init()) - .def(py::init()) - .def(py::init()) - .def(py::init&>()) - .def(py::init&, - const ignition::math::Material&>()) + .def(py::init()) + .def(py::init()) + .def(py::init&>()) + .def(py::init&, + const gz::math::Material&>()) .def(py::self != py::self) .def(py::self == py::self) .def("size", &Class::Size, "Get the size of the box.") .def("set_size", - py::overload_cast&> + py::overload_cast&> (&Class::SetSize), "Set the size of the box.") .def("set_size", @@ -90,7 +90,7 @@ void defineMathBox(py::module &m, const std::string &typestr) .def("vertices_below", [](const Class &self, const Plane &_plane) { - std::vector> result; + std::vector> result; auto vertices = self.VerticesBelow(_plane); for (auto & v : vertices) { @@ -113,7 +113,7 @@ void defineMathBox(py::module &m, const std::string &typestr) .def("intersections", [](const Class &self, const Plane &_plane) { - std::vector> result; + std::vector> result; auto vertices = self.Intersections(_plane); for (auto & v : vertices) { @@ -133,6 +133,6 @@ void defineMathBox(py::module &m, const std::string &typestr) } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__BOX_HH_ +#endif // GZ_MATH_PYTHON__BOX_HH_ diff --git a/src/python_pybind11/src/Capsule.cc b/src/python_pybind11/src/Capsule.cc index da24ab2eb..050ccc3f4 100644 --- a/src/python_pybind11/src/Capsule.cc +++ b/src/python_pybind11/src/Capsule.cc @@ -17,7 +17,7 @@ #include "Capsule.hh" -namespace ignition +namespace gz { namespace math { @@ -31,4 +31,4 @@ void defineMathCapsule(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/Capsule.hh b/src/python_pybind11/src/Capsule.hh index 92eeed120..9bf0fca2a 100644 --- a/src/python_pybind11/src/Capsule.hh +++ b/src/python_pybind11/src/Capsule.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__CAPSULE_HH_ -#define IGNITION_MATH_PYTHON__CAPSULE_HH_ +#ifndef GZ_MATH_PYTHON__CAPSULE_HH_ +#define GZ_MATH_PYTHON__CAPSULE_HH_ #include @@ -29,13 +29,13 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Capsule +/// Define a pybind11 wrapper for an gz::math::Capsule /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -43,7 +43,7 @@ namespace python template void helpDefineMathCapsule(py::module &m, const std::string &typestr) { - using Class = ignition::math::Capsule; + using Class = gz::math::Capsule; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -51,7 +51,7 @@ void helpDefineMathCapsule(py::module &m, const std::string &typestr) py::dynamic_attr()) .def(py::init<>()) .def(py::init()) - .def(py::init()) + .def(py::init()) .def(py::self == py::self) .def("radius", &Class::Radius, @@ -93,7 +93,7 @@ void helpDefineMathCapsule(py::module &m, const std::string &typestr) }, "memo"_a); } -/// Define a pybind11 wrapper for an ignition::math::Line2 +/// Define a pybind11 wrapper for an gz::math::Line2 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -102,6 +102,6 @@ void defineMathCapsule(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__BOX_HH_ +#endif // GZ_MATH_PYTHON__BOX_HH_ diff --git a/src/python_pybind11/src/Color.cc b/src/python_pybind11/src/Color.cc index e643e1aaa..9428fa26a 100644 --- a/src/python_pybind11/src/Color.cc +++ b/src/python_pybind11/src/Color.cc @@ -25,7 +25,7 @@ using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { @@ -33,7 +33,7 @@ namespace python { void defineMathColor(py::module &m, const std::string &typestr) { - using Class = ignition::math::Color; + using Class = gz::math::Color; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -152,4 +152,4 @@ void defineMathColor(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/Color.hh b/src/python_pybind11/src/Color.hh index ed28f7bcc..514ad3e23 100644 --- a/src/python_pybind11/src/Color.hh +++ b/src/python_pybind11/src/Color.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__COLOR_HH_ -#define IGNITION_MATH_PYTHON__COLOR_HH_ +#ifndef GZ_MATH_PYTHON__COLOR_HH_ +#define GZ_MATH_PYTHON__COLOR_HH_ #include #include @@ -24,13 +24,13 @@ namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Color +/// Define a pybind11 wrapper for an gz::math::Color /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -38,6 +38,6 @@ namespace python void defineMathColor(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__COLOR_HH_ +#endif // GZ_MATH_PYTHON__COLOR_HH_ diff --git a/src/python_pybind11/src/Cylinder.hh b/src/python_pybind11/src/Cylinder.hh index 6480dc91b..722e3fc53 100644 --- a/src/python_pybind11/src/Cylinder.hh +++ b/src/python_pybind11/src/Cylinder.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__CYLINDER_HH_ -#define IGNITION_MATH_PYTHON__CYLINDER_HH_ +#ifndef GZ_MATH_PYTHON__CYLINDER_HH_ +#define GZ_MATH_PYTHON__CYLINDER_HH_ #include @@ -29,13 +29,13 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Cylinder +/// Define a pybind11 wrapper for an gz::math::Cylinder /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -44,7 +44,7 @@ template void defineMathCylinder(py::module &m, const std::string &typestr) { - using Class = ignition::math::Cylinder; + using Class = gz::math::Cylinder; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -52,17 +52,17 @@ void defineMathCylinder(py::module &m, const std::string &typestr) py::dynamic_attr()) .def(py::init<>()) .def(py::init&>(), + const gz::math::Quaternion&>(), py::arg("_length") = 0, py::arg("_radius") = 0, - py::arg("_rotOffset") = ignition::math::Quaternion::Identity) + py::arg("_rotOffset") = gz::math::Quaternion::Identity) .def(py::init&>(), + const gz::math::Material&, + const gz::math::Quaternion&>(), py::arg("_length") = 0, py::arg("_radius") = 0, - py::arg("_material") = ignition::math::Material(), - py::arg("_rotOffset") = ignition::math::Quaternion::Identity) + py::arg("_material") = gz::math::Material(), + py::arg("_rotOffset") = gz::math::Quaternion::Identity) .def(py::self == py::self) .def("radius", &Class::Radius, @@ -112,6 +112,6 @@ void defineMathCylinder(py::module &m, const std::string &typestr) } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__CYLINDER_HH_ +#endif // GZ_MATH_PYTHON__CYLINDER_HH_ diff --git a/src/python_pybind11/src/DiffDriveOdometry.cc b/src/python_pybind11/src/DiffDriveOdometry.cc index 025981181..818c3cd4c 100644 --- a/src/python_pybind11/src/DiffDriveOdometry.cc +++ b/src/python_pybind11/src/DiffDriveOdometry.cc @@ -17,7 +17,7 @@ #include #include "DiffDriveOdometry.hh" -namespace ignition +namespace gz { namespace math { @@ -26,7 +26,7 @@ namespace python void defineMathDiffDriveOdometry( py::module &m, const std::string &typestr) { - using Class = ignition::math::DiffDriveOdometry; + using Class = gz::math::DiffDriveOdometry; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -58,5 +58,5 @@ void defineMathDiffDriveOdometry( "Set the velocity rolling window size."); } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz diff --git a/src/python_pybind11/src/DiffDriveOdometry.hh b/src/python_pybind11/src/DiffDriveOdometry.hh index fdab22418..abcc16239 100644 --- a/src/python_pybind11/src/DiffDriveOdometry.hh +++ b/src/python_pybind11/src/DiffDriveOdometry.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_PYTHON__DIFFDRIVEODOMETRY_HH_ -#define IGNITION_MATH_PYTHON__DIFFDRIVEODOMETRY_HH_ +#ifndef GZ_MATH_PYTHON__DIFFDRIVEODOMETRY_HH_ +#define GZ_MATH_PYTHON__DIFFDRIVEODOMETRY_HH_ #include #include @@ -26,20 +26,20 @@ namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a py:: wrapper for an ignition::gazebo::DiffDriveOdometry +/// Define a py:: wrapper for an gz::math::DiffDriveOdometry /** * \param[in] module a py:: module to add the definition to */ void defineMathDiffDriveOdometry( py::module &m, const std::string &typestr); } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz -#endif // IGNITION_MATH_PYTHON__DIFFDRIVEODOMETRY_HH_ +#endif // GZ_MATH_PYTHON__DIFFDRIVEODOMETRY_HH_ diff --git a/src/python_pybind11/src/Ellipsoid.cc b/src/python_pybind11/src/Ellipsoid.cc index ce654c43e..64e7d8e1b 100644 --- a/src/python_pybind11/src/Ellipsoid.cc +++ b/src/python_pybind11/src/Ellipsoid.cc @@ -17,7 +17,7 @@ #include "Ellipsoid.hh" -namespace ignition +namespace gz { namespace math { @@ -30,4 +30,4 @@ void defineMathEllipsoid(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/Ellipsoid.hh b/src/python_pybind11/src/Ellipsoid.hh index ff2fdfa77..84008f1f9 100644 --- a/src/python_pybind11/src/Ellipsoid.hh +++ b/src/python_pybind11/src/Ellipsoid.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__Ellipsoid_HH_ -#define IGNITION_MATH_PYTHON__Ellipsoid_HH_ +#ifndef GZ_MATH_PYTHON__Ellipsoid_HH_ +#define GZ_MATH_PYTHON__Ellipsoid_HH_ #include @@ -30,13 +30,13 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Ellipsoid +/// Define a pybind11 wrapper for an gz::math::Ellipsoid /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -44,16 +44,16 @@ namespace python template void helpDefineMathEllipsoid(py::module &m, const std::string &typestr) { - using Class = ignition::math::Ellipsoid; + using Class = gz::math::Ellipsoid; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), py::buffer_protocol(), py::dynamic_attr()) .def(py::init<>()) - .def(py::init>()) - .def(py::init, - const ignition::math::Material&>()) + .def(py::init>()) + .def(py::init, + const gz::math::Material&>()) .def(py::self == py::self) .def("radii", &Class::Radii, @@ -89,7 +89,7 @@ void helpDefineMathEllipsoid(py::module &m, const std::string &typestr) }, "memo"_a); } -/// Define a pybind11 wrapper for an ignition::math::Ellipsoid +/// Define a pybind11 wrapper for an gz::math::Ellipsoid /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -98,6 +98,6 @@ void defineMathEllipsoid(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__BOX_HH_ +#endif // GZ_MATH_PYTHON__BOX_HH_ diff --git a/src/python_pybind11/src/Filter.cc b/src/python_pybind11/src/Filter.cc index 93abe5c60..350970897 100644 --- a/src/python_pybind11/src/Filter.cc +++ b/src/python_pybind11/src/Filter.cc @@ -17,7 +17,7 @@ #include "Filter.hh" -namespace ignition +namespace gz { namespace math { @@ -39,7 +39,7 @@ void defineMathOnePole(py::module &m, const std::string &typestr) void defineMathOnePoleQuaternion(py::module &m, const std::string &typestr) { - using Class = ignition::math::OnePoleQuaternion; + using Class = gz::math::OnePoleQuaternion; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -63,7 +63,7 @@ void defineMathOnePoleQuaternion(py::module &m, const std::string &typestr) void defineMathOnePoleVector3(py::module &m, const std::string &typestr) { - using Class = ignition::math::OnePoleVector3; + using Class = gz::math::OnePoleVector3; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -95,7 +95,7 @@ void defineMathBiQuad(py::module &m, const std::string &typestr) void defineMathBiQuadVector3(py::module &m, const std::string &typestr) { - using Class = ignition::math::BiQuadVector3; + using Class = gz::math::BiQuadVector3; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -121,4 +121,4 @@ void defineMathBiQuadVector3(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/Filter.hh b/src/python_pybind11/src/Filter.hh index 30faac9c2..01c10549b 100644 --- a/src/python_pybind11/src/Filter.hh +++ b/src/python_pybind11/src/Filter.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__FILTER_HH_ -#define IGNITION_MATH_PYTHON__FILTER_HH_ +#ifndef GZ_MATH_PYTHON__FILTER_HH_ +#define GZ_MATH_PYTHON__FILTER_HH_ #include @@ -28,7 +28,7 @@ namespace py = pybind11; -namespace ignition +namespace gz { namespace math { @@ -71,7 +71,7 @@ public: } }; -/// Help define a pybind11 wrapper for an ignition::math::Filter +/// Help define a pybind11 wrapper for an gz::math::Filter /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -79,7 +79,7 @@ public: template void helpDefineMathFilter(py::module &m, const std::string &typestr) { - using Class = ignition::math::Filter; + using Class = gz::math::Filter; std::string pyclass_name = typestr; py::class_>(m, pyclass_name.c_str(), @@ -97,7 +97,7 @@ void helpDefineMathFilter(py::module &m, const std::string &typestr) "Get the output of the filter."); } -/// Define a pybind11 wrapper for an ignition::math::Filter +/// Define a pybind11 wrapper for an gz::math::Filter /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -123,7 +123,7 @@ public: } }; -/// Help define a pybind11 wrapper for an ignition::math::OnePole +/// Help define a pybind11 wrapper for an gz::math::OnePole /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -131,7 +131,7 @@ public: template void helpDefineMathOnePole(py::module &m, const std::string &typestr) { - using Class = ignition::math::OnePole; + using Class = gz::math::OnePole; std::string pyclass_name = typestr; py::class_>(m, pyclass_name.c_str(), @@ -153,21 +153,21 @@ void helpDefineMathOnePole(py::module &m, const std::string &typestr) "Update the filter's output."); } -/// Define a pybind11 wrapper for an ignition::math::OnePole +/// Define a pybind11 wrapper for an gz::math::OnePole /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python */ void defineMathOnePole(py::module &m, const std::string &typestr); -/// Define a pybind11 wrapper for an ignition::math::OnePoleQuaterion +/// Define a pybind11 wrapper for an gz::math::OnePoleQuaterion /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python */ void defineMathOnePoleQuaternion(py::module &m, const std::string &typestr); -/// Define a pybind11 wrapper for an ignition::math::OnePoleVector3 +/// Define a pybind11 wrapper for an gz::math::OnePoleVector3 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -213,7 +213,7 @@ public: } }; -/// Help define a pybind11 wrapper for an ignition::math::BiQuad +/// Help define a pybind11 wrapper for an gz::math::BiQuad /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -221,7 +221,7 @@ public: template void helpDefineMathBiQuad(py::module &m, const std::string &typestr) { - using Class = ignition::math::BiQuad; + using Class = gz::math::BiQuad; std::string pyclass_name = typestr; py::class_>(m, pyclass_name.c_str(), @@ -246,14 +246,14 @@ void helpDefineMathBiQuad(py::module &m, const std::string &typestr) "Update the filter's output."); } -/// Define a pybind11 wrapper for an ignition::math::BiQuad +/// Define a pybind11 wrapper for an gz::math::BiQuad /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python */ void defineMathBiQuad(py::module &m, const std::string &typestr); -/// Define a pybind11 wrapper for an ignition::math::BiQuadVector3 +/// Define a pybind11 wrapper for an gz::math::BiQuadVector3 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -262,6 +262,6 @@ void defineMathBiQuadVector3(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__FILTER_HH_ +#endif // GZ_MATH_PYTHON__FILTER_HH_ diff --git a/src/python_pybind11/src/Frustum.cc b/src/python_pybind11/src/Frustum.cc index daf2b756f..2ac6c2447 100644 --- a/src/python_pybind11/src/Frustum.cc +++ b/src/python_pybind11/src/Frustum.cc @@ -22,7 +22,7 @@ #include #include -namespace ignition +namespace gz { namespace math { @@ -30,20 +30,20 @@ namespace python { void defineMathFrustum(py::module &m, const std::string &typestr) { - using Class = ignition::math::Frustum; + using Class = gz::math::Frustum; std::string pyclass_name = typestr; py::class_ (m, pyclass_name.c_str(), py::buffer_protocol(), py::dynamic_attr()) .def(py::init<>()) - .def(py::init(), + .def(py::init(), py::arg("_near") = 0, py::arg("_far") = 0, - py::arg("_fov") = ignition::math::Angle(0), + py::arg("_fov") = gz::math::Angle(0), py::arg("_aspectRatio") = 0, - py::arg("_pose") = ignition::math::Pose3d::Zero) + py::arg("_pose") = gz::math::Pose3d::Zero) .def(py::init()) .def("near", &Class::Near, @@ -84,32 +84,32 @@ void defineMathFrustum(py::module &m, const std::string &typestr) &Class::SetPose, "Set the pose of the frustum") .def("contains", - py::overload_cast + py::overload_cast (&Class::Contains, py::const_), "Check if a box lies inside the pyramid frustum.") .def("contains", - py::overload_cast + py::overload_cast (&Class::Contains, py::const_), "Check if a point lies inside the pyramid frustum.") .def("plane", &Class::Plane, "Get a plane of the frustum."); - py::enum_(m, "FrustumPlane") + py::enum_(m, "FrustumPlane") .value("FRUSTUM_PLANE_NEAR", - ignition::math::Frustum::FrustumPlane::FRUSTUM_PLANE_NEAR) + gz::math::Frustum::FrustumPlane::FRUSTUM_PLANE_NEAR) .value("FRUSTUM_PLANE_FAR", - ignition::math::Frustum::FrustumPlane::FRUSTUM_PLANE_FAR) + gz::math::Frustum::FrustumPlane::FRUSTUM_PLANE_FAR) .value("FRUSTUM_PLANE_LEFT", - ignition::math::Frustum::FrustumPlane::FRUSTUM_PLANE_LEFT) + gz::math::Frustum::FrustumPlane::FRUSTUM_PLANE_LEFT) .value("FRUSTUM_PLANE_RIGHT", - ignition::math::Frustum::FrustumPlane::FRUSTUM_PLANE_RIGHT) + gz::math::Frustum::FrustumPlane::FRUSTUM_PLANE_RIGHT) .value("FRUSTUM_PLANE_TOP", - ignition::math::Frustum::FrustumPlane::FRUSTUM_PLANE_TOP) + gz::math::Frustum::FrustumPlane::FRUSTUM_PLANE_TOP) .value("FRUSTUM_PLANE_BOTTOM", - ignition::math::Frustum::FrustumPlane::FRUSTUM_PLANE_BOTTOM) + gz::math::Frustum::FrustumPlane::FRUSTUM_PLANE_BOTTOM) .export_values(); } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/Frustum.hh b/src/python_pybind11/src/Frustum.hh index 688baf013..3a2472780 100644 --- a/src/python_pybind11/src/Frustum.hh +++ b/src/python_pybind11/src/Frustum.hh @@ -15,21 +15,21 @@ * */ -#ifndef IGNITION_MATH_PYTHON__FRUSTUM_HH_ -#define IGNITION_MATH_PYTHON__FRUSTUM_HH_ +#ifndef GZ_MATH_PYTHON__FRUSTUM_HH_ +#define GZ_MATH_PYTHON__FRUSTUM_HH_ #include #include namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Frustum +/// Define a pybind11 wrapper for an gz::math::Frustum /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -37,6 +37,6 @@ namespace python void defineMathFrustum(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__FRUSTUM_HH_ +#endif // GZ_MATH_PYTHON__FRUSTUM_HH_ diff --git a/src/python_pybind11/src/GaussMarkovProcess.cc b/src/python_pybind11/src/GaussMarkovProcess.cc index 786f8f6ac..edfccf0af 100644 --- a/src/python_pybind11/src/GaussMarkovProcess.cc +++ b/src/python_pybind11/src/GaussMarkovProcess.cc @@ -28,7 +28,7 @@ namespace py = pybind11; -namespace ignition +namespace gz { namespace math { @@ -37,7 +37,7 @@ namespace python void defineMathGaussMarkovProcess( py::module &m, const std::string &typestr) { - using Class = ignition::math::GaussMarkovProcess; + using Class = gz::math::GaussMarkovProcess; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -70,4 +70,4 @@ void defineMathGaussMarkovProcess( } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/GaussMarkovProcess.hh b/src/python_pybind11/src/GaussMarkovProcess.hh index c100c684f..a9a2bf565 100644 --- a/src/python_pybind11/src/GaussMarkovProcess.hh +++ b/src/python_pybind11/src/GaussMarkovProcess.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__GAUSSMARKOVPROCESS_HH_ -#define IGNITION_MATH_PYTHON__GAUSSMARKOVPROCESS_HH_ +#ifndef GZ_MATH_PYTHON__GAUSSMARKOVPROCESS_HH_ +#define GZ_MATH_PYTHON__GAUSSMARKOVPROCESS_HH_ #include @@ -24,13 +24,13 @@ namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::GaussMarkovProcess +/// Define a pybind11 wrapper for an gz::math::GaussMarkovProcess /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -38,6 +38,6 @@ namespace python void defineMathGaussMarkovProcess(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__GAUSSMARKOVPROCESS_HH_ +#endif // GZ_MATH_PYTHON__GAUSSMARKOVPROCESS_HH_ diff --git a/src/python_pybind11/src/Helpers.cc b/src/python_pybind11/src/Helpers.cc index df33a255e..947bee33c 100644 --- a/src/python_pybind11/src/Helpers.cc +++ b/src/python_pybind11/src/Helpers.cc @@ -22,7 +22,7 @@ #include #include -namespace ignition +namespace gz { namespace math { @@ -62,7 +62,7 @@ float BoxVolume(const float _x, const float _y, const float _z) /// \brief Compute box volume from a vector /// \param[in] _v Vector3d that contains the box's dimensions. /// \return box volume from a vector -float BoxVolumeV(const ignition::math::Vector3d &_v) +float BoxVolumeV(const gz::math::Vector3d &_v) { return IGN_BOX_VOLUME_V(_v); } @@ -92,55 +92,55 @@ void defineMathHelpers(py::module &m) { using Class = Helpers; - m.def("clamp", &ignition::math::clamp, "Simple clamping function") - .def("clamp", &ignition::math::clamp, "Simple clamping function") + m.def("clamp", &gz::math::clamp, "Simple clamping function") + .def("clamp", &gz::math::clamp, "Simple clamping function") .def("isnan", - py::overload_cast(&ignition::math::isnan), + py::overload_cast(&gz::math::isnan), "Check if a float is NaN") .def("fixnan", - py::overload_cast(&ignition::math::fixnan), + py::overload_cast(&gz::math::fixnan), "Fix a nan value.") .def("is_even", - py::overload_cast(&ignition::math::isEven), + py::overload_cast(&gz::math::isEven), "Check if parameter is even.") .def("is_odd", - py::overload_cast(&ignition::math::isOdd), + py::overload_cast(&gz::math::isOdd), "Check if parameter is odd.") .def("sgn", - &ignition::math::sgn, + &gz::math::sgn, "Returns 0 for zero values, -1 for negative values and +1 for positive" " values.") .def("signum", - &ignition::math::signum, + &gz::math::signum, "Returns 0 for zero values, -1 for negative values and " "+1 for positive values.") - .def("mean", &ignition::math::mean, "Get mean of vector of values") + .def("mean", &gz::math::mean, "Get mean of vector of values") .def("variance", - &ignition::math::variance, + &gz::math::variance, "Get variance of vector of values") .def("max", - &ignition::math::max, + &gz::math::max, "Get the maximum value of vector of values") .def("max", - &ignition::math::max, + &gz::math::max, "Get the maximum value of vector of values") .def("min", - &ignition::math::min, + &gz::math::min, "Get the minimum value of vector of values") .def("min", - &ignition::math::min, + &gz::math::min, "Get the minimum value of vector of values") .def("equal", - &ignition::math::equal, + &gz::math::equal, "check if two values are equal, within a tolerance") .def("less_or_near_equal", - &ignition::math::lessOrNearEqual, + &gz::math::lessOrNearEqual, "Inequality test, within a tolerance") .def("greater_or_near_equal", - &ignition::math::greaterOrNearEqual, + &gz::math::greaterOrNearEqual, "Inequality test, within a tolerance") .def("precision", - &ignition::math::precision, + &gz::math::precision, "Get value at a specified precision") .def("sort2", &Sort2, @@ -149,20 +149,20 @@ void defineMathHelpers(py::module &m) &Sort3, "Sort three numbers, such that _a <= _b <= _c") .def("is_power_of_two", - &ignition::math::isPowerOfTwo, + &gz::math::isPowerOfTwo, "Is this a power of 2?") .def("round_up_power_of_two", - &ignition::math::roundUpPowerOfTwo, + &gz::math::roundUpPowerOfTwo, "Get the smallest power of two that is greater or equal to a given " "value") .def("round_up_multiple", - &ignition::math::roundUpMultiple, + &gz::math::roundUpMultiple, "Round a number up to the nearest multiple") .def("parse_int", - &ignition::math::parseInt, + &gz::math::parseInt, "parse string into an integer") .def("parse_float", - &ignition::math::parseFloat, + &gz::math::parseFloat, "parse string into an float") .def("ign_sphere_volume", &SphereVolume, @@ -227,5 +227,5 @@ void defineMathHelpers(py::module &m) .def_readonly_static("NAN_I", &NAN_I); } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz diff --git a/src/python_pybind11/src/Helpers.hh b/src/python_pybind11/src/Helpers.hh index ed22bd325..9faaefdca 100644 --- a/src/python_pybind11/src/Helpers.hh +++ b/src/python_pybind11/src/Helpers.hh @@ -15,26 +15,26 @@ * */ -#ifndef IGNITION_MATH_PYTHON__HELPERS_HH_ -#define IGNITION_MATH_PYTHON__HELPERS_HH_ +#ifndef GZ_MATH_PYTHON__HELPERS_HH_ +#define GZ_MATH_PYTHON__HELPERS_HH_ #include namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a py::bind11 wrapper for an ignition::math::Helpers +/// Define a py::bind11 wrapper for an gz::math::Helpers /** * \param[in] module a py::bind11 module to add the definition to */ void defineMathHelpers(py::module &m); } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz -#endif // IGNITION_MATH_PYTHON__HELPERS_HH_ +#endif // GZ_MATH_PYTHON__HELPERS_HH_ diff --git a/src/python_pybind11/src/Inertial.hh b/src/python_pybind11/src/Inertial.hh index dd66cc1c2..ee28f5c1e 100644 --- a/src/python_pybind11/src/Inertial.hh +++ b/src/python_pybind11/src/Inertial.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__INERTIAL_HH_ -#define IGNITION_MATH_PYTHON__INERTIAL_HH_ +#ifndef GZ_MATH_PYTHON__INERTIAL_HH_ +#define GZ_MATH_PYTHON__INERTIAL_HH_ #include @@ -29,13 +29,13 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Inertial +/// Define a pybind11 wrapper for an gz::math::Inertial /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -44,15 +44,15 @@ template void defineMathInertial(py::module &m, const std::string &typestr) { - using Class = ignition::math::Inertial; + using Class = gz::math::Inertial; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), py::buffer_protocol(), py::dynamic_attr()) .def(py::init<>()) - .def(py::init&, - const ignition::math::Pose3&>()) + .def(py::init&, + const gz::math::Pose3&>()) .def(py::init()) .def(py::self == py::self) .def(py::self != py::self) @@ -60,7 +60,7 @@ void defineMathInertial(py::module &m, const std::string &typestr) .def(py::self + py::self) .def("set_mass_matrix", &Class::SetMassMatrix, - py::arg("_m") = ignition::math::MassMatrix3(), + py::arg("_m") = gz::math::MassMatrix3(), py::arg("_tolerance") = IGN_MASSMATRIX3_DEFAULT_TOLERANCE, "Set the mass and inertia matrix.") .def("mass_matrix", @@ -82,7 +82,7 @@ void defineMathInertial(py::module &m, const std::string &typestr) "MOI in the base coordinate frame.") .def("set_mass_matrix_rotation", &Class::SetMassMatrixRotation, - py::arg("_q") = ignition::math::Quaternion::Identity, + py::arg("_q") = gz::math::Quaternion::Identity, py::arg("_tol") = 1e-6, "Set the MassMatrix rotation (eigenvectors of inertia matrix) " "without affecting the MOI in the base coordinate frame.") @@ -96,6 +96,6 @@ void defineMathInertial(py::module &m, const std::string &typestr) } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__INERTIAL_HH_ +#endif // GZ_MATH_PYTHON__INERTIAL_HH_ diff --git a/src/python_pybind11/src/Kmeans.cc b/src/python_pybind11/src/Kmeans.cc index cd3273685..1218cf4ac 100644 --- a/src/python_pybind11/src/Kmeans.cc +++ b/src/python_pybind11/src/Kmeans.cc @@ -21,7 +21,7 @@ #include #include -namespace ignition +namespace gz { namespace math { @@ -29,15 +29,15 @@ namespace python { void defineMathKmeans(py::module &m, const std::string &typestr) { - using Class = ignition::math::Kmeans; + using Class = gz::math::Kmeans; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), py::buffer_protocol(), py::dynamic_attr()) - .def(py::init&>()) + .def(py::init&>()) .def("observations", - py::overload_cast&> + py::overload_cast&> (&Class::Observations), "Set the observations to cluster.") .def("observations", @@ -48,7 +48,7 @@ void defineMathKmeans(py::module &m, const std::string &typestr) "Add observations to the cluster.") .def("cluster", [](Class &self, int k) { - std::vector> centroids; + std::vector> centroids; std::vector labels; bool result = self.Cluster(k, centroids, labels); return std::make_tuple(result, centroids, labels); @@ -57,4 +57,4 @@ void defineMathKmeans(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/Kmeans.hh b/src/python_pybind11/src/Kmeans.hh index d9c1de4e0..1ed198988 100644 --- a/src/python_pybind11/src/Kmeans.hh +++ b/src/python_pybind11/src/Kmeans.hh @@ -15,21 +15,21 @@ * */ -#ifndef IGNITION_MATH_PYTHON__KMEANS_HH_ -#define IGNITION_MATH_PYTHON__KMEANS_HH_ +#ifndef GZ_MATH_PYTHON__KMEANS_HH_ +#define GZ_MATH_PYTHON__KMEANS_HH_ #include #include namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Kmeans +/// Define a pybind11 wrapper for an gz::math::Kmeans /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -37,6 +37,6 @@ namespace python void defineMathKmeans(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__KMEANS_HH_ +#endif // GZ_MATH_PYTHON__KMEANS_HH_ diff --git a/src/python_pybind11/src/Line2.cc b/src/python_pybind11/src/Line2.cc index 530bf14ec..034632a44 100644 --- a/src/python_pybind11/src/Line2.cc +++ b/src/python_pybind11/src/Line2.cc @@ -17,7 +17,7 @@ #include "Line2.hh" -namespace ignition +namespace gz { namespace math { @@ -32,4 +32,4 @@ void defineMathLine2(py::module &m, const std::string &typestr) } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/Line2.hh b/src/python_pybind11/src/Line2.hh index 1a59603dd..33a9379f3 100644 --- a/src/python_pybind11/src/Line2.hh +++ b/src/python_pybind11/src/Line2.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__LINE2_HH_ -#define IGNITION_MATH_PYTHON__LINE2_HH_ +#ifndef GZ_MATH_PYTHON__LINE2_HH_ +#define GZ_MATH_PYTHON__LINE2_HH_ #include #include @@ -29,13 +29,13 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Help define a pybind11 wrapper for an ignition::math::Line2 +/// Help define a pybind11 wrapper for an gz::math::Line2 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -43,7 +43,7 @@ namespace python template void helpDefineMathLine2(py::module &m, const std::string &typestr) { - using Class = ignition::math::Line2; + using Class = gz::math::Line2; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -54,14 +54,14 @@ void helpDefineMathLine2(py::module &m, const std::string &typestr) pyclass_name.c_str(), py::buffer_protocol(), py::dynamic_attr()) - .def(py::init&, - const ignition::math::Vector2&>()) + .def(py::init&, + const gz::math::Vector2&>()) .def(py::init()) .def(py::self != py::self) .def(py::self == py::self) .def("set", - py::overload_cast&, - const ignition::math::Vector2&>(&Class::Set), + py::overload_cast&, + const gz::math::Vector2&>(&Class::Set), "Set the start and end point of the line segment") .def("set", py::overload_cast(&Class::Set), @@ -70,13 +70,13 @@ void helpDefineMathLine2(py::module &m, const std::string &typestr) py::overload_cast(&Class::CrossProduct, py::const_), "Return the cross product of this line and the given line.") .def("cross_product", - py::overload_cast&>( + py::overload_cast&>( &Class::CrossProduct, py::const_), "Return the cross product of this line and the given line.") .def("collinear", - py::overload_cast&, double>( + py::overload_cast&, double>( &Class::Collinear, py::const_), - py::arg("_pt") = ignition::math::Vector2::Zero, + py::arg("_pt") = gz::math::Vector2::Zero, py::arg("_epsilon") = 1e-6, "Check if the given point is collinear with this line.") .def("collinear", @@ -98,11 +98,11 @@ void helpDefineMathLine2(py::module &m, const std::string &typestr) .def("intersect", py::overload_cast< const Class&, - ignition::math::Vector2&, + gz::math::Vector2&, double>( &Class::Intersect, py::const_), py::arg("_line") = Class(0, 0, 0, 0), - py::arg("_pt") = ignition::math::Vector2::Zero, + py::arg("_pt") = gz::math::Vector2::Zero, py::arg("_epsilon") = 1e-6, "Check if this line intersects the given line segment.") .def("intersect", @@ -129,7 +129,7 @@ void helpDefineMathLine2(py::module &m, const std::string &typestr) .def("__repr__", toString); } -/// Define a pybind11 wrapper for an ignition::math::Line2 +/// Define a pybind11 wrapper for an gz::math::Line2 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -138,6 +138,6 @@ void defineMathLine2(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__LINE2_HH_ +#endif // GZ_MATH_PYTHON__LINE2_HH_ diff --git a/src/python_pybind11/src/Line3.cc b/src/python_pybind11/src/Line3.cc index 477820a90..c4f41c93d 100644 --- a/src/python_pybind11/src/Line3.cc +++ b/src/python_pybind11/src/Line3.cc @@ -17,7 +17,7 @@ #include "Line3.hh" -namespace ignition +namespace gz { namespace math { @@ -32,4 +32,4 @@ void defineMathLine3(py::module &m, const std::string &typestr) } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/Line3.hh b/src/python_pybind11/src/Line3.hh index d7d949da4..62fba2866 100644 --- a/src/python_pybind11/src/Line3.hh +++ b/src/python_pybind11/src/Line3.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__LINE3_HH_ -#define IGNITION_MATH_PYTHON__LINE3_HH_ +#ifndef GZ_MATH_PYTHON__LINE3_HH_ +#define GZ_MATH_PYTHON__LINE3_HH_ #include #include @@ -30,13 +30,13 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Help define a pybind11 wrapper for an ignition::math::Line3 +/// Help define a pybind11 wrapper for an gz::math::Line3 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -44,7 +44,7 @@ namespace python template void helpDefineMathLine3(py::module &m, const std::string &typestr) { - using Class = ignition::math::Line3; + using Class = gz::math::Line3; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -57,8 +57,8 @@ void helpDefineMathLine3(py::module &m, const std::string &typestr) py::dynamic_attr()) .def(py::init<>()) .def(py::init()) - .def(py::init&, - const ignition::math::Vector3&>(), + .def(py::init&, + const gz::math::Vector3&>(), "Constructor") .def(py::init(), "2D Constructor where Z coordinates are 0") @@ -68,8 +68,8 @@ void helpDefineMathLine3(py::module &m, const std::string &typestr) .def(py::self != py::self) .def(py::self == py::self) .def("set", - py::overload_cast&, - const ignition::math::Vector3&>(&Class::Set), + py::overload_cast&, + const gz::math::Vector3&>(&Class::Set), "Set the start and end point of the line segment") .def("set_a", &Class::SetA, @@ -101,17 +101,17 @@ void helpDefineMathLine3(py::module &m, const std::string &typestr) py::arg("_line"), py::arg("_result"), py::arg("_epsilon") = 1e-6, "Get the shortest line between this line and the provided line.") .def("distance", - py::overload_cast&>( + py::overload_cast&>( &Class::Distance), "Calculate shortest distance between line and point") .def("intersect", py::overload_cast< const Class&, - ignition::math::Vector3&, + gz::math::Vector3&, double>( &Class::Intersect, py::const_), py::arg("_line") = Class(0, 0, 0, 0), - py::arg("_pt") = ignition::math::Vector3::Zero, + py::arg("_pt") = gz::math::Vector3::Zero, py::arg("_epsilon") = 1e-6, "Check if this line intersects the given line segment.") .def("intersect", @@ -128,7 +128,7 @@ void helpDefineMathLine3(py::module &m, const std::string &typestr) "Check if the given line is parallel with this line.") .def("within", &Class::Within, - py::arg("_pt") = ignition::math::Vector3::Zero, + py::arg("_pt") = gz::math::Vector3::Zero, py::arg("_epsilon") = 1e-6, "Check if the given point is between the start and end " "points of the line segment.") @@ -146,7 +146,7 @@ void helpDefineMathLine3(py::module &m, const std::string &typestr) .def("__repr__", toString); } -/// Define a pybind11 wrapper for an ignition::math::Line3 +/// Define a pybind11 wrapper for an gz::math::Line3 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -154,6 +154,6 @@ void helpDefineMathLine3(py::module &m, const std::string &typestr) void defineMathLine3(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__LINE3_HH_ +#endif // GZ_MATH_PYTHON__LINE3_HH_ diff --git a/src/python_pybind11/src/MassMatrix3.cc b/src/python_pybind11/src/MassMatrix3.cc index b7595bdf1..defb87cbc 100644 --- a/src/python_pybind11/src/MassMatrix3.cc +++ b/src/python_pybind11/src/MassMatrix3.cc @@ -19,7 +19,7 @@ #include "MassMatrix3.hh" -namespace ignition +namespace gz { namespace math { @@ -32,5 +32,5 @@ void defineMathMassMatrix3(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz diff --git a/src/python_pybind11/src/MassMatrix3.hh b/src/python_pybind11/src/MassMatrix3.hh index c6e584b54..0b7b42815 100644 --- a/src/python_pybind11/src/MassMatrix3.hh +++ b/src/python_pybind11/src/MassMatrix3.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__MASSMATRIX3_HH_ -#define IGNITION_MATH_PYTHON__MASSMATRIX3_HH_ +#ifndef GZ_MATH_PYTHON__MASSMATRIX3_HH_ +#define GZ_MATH_PYTHON__MASSMATRIX3_HH_ #include #include @@ -27,20 +27,20 @@ namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::MassMatrix3 +/// Define a pybind11 wrapper for an gz::math::MassMatrix3 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python */ void defineMathMassMatrix3(py::module &m, const std::string &typestr); -/// Help define a pybind11 wrapper for an ignition::math::MassMatrix3 +/// Help define a pybind11 wrapper for an gz::math::MassMatrix3 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -48,7 +48,7 @@ void defineMathMassMatrix3(py::module &m, const std::string &typestr); template void helpDefineMathMassMatrix3(py::module &m, const std::string &typestr) { - using Class = ignition::math::MassMatrix3; + using Class = gz::math::MassMatrix3; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -56,8 +56,8 @@ void helpDefineMathMassMatrix3(py::module &m, const std::string &typestr) py::dynamic_attr()) .def(py::init<>()) .def(py::init()) - .def(py::init&, - const ignition::math::Vector3&>()) + .def(py::init&, + const gz::math::Vector3&>()) .def("set_mass", &Class::SetMass, "Set the mass.") .def("mass", py::overload_cast<>(&Class::Mass, py::const_), "Get the mass") .def("ixx", &Class::Ixx, "Get ixx") @@ -92,55 +92,55 @@ void helpDefineMathMassMatrix3(py::module &m, const std::string &typestr) &Class::SetDiagonalMoments, "Set the diagonal moments of inertia (Ixx, Iyy, Izz).") .def("set_from_box", - py::overload_cast&, - const ignition::math::Quaternion&> + py::overload_cast&, + const gz::math::Quaternion&> (&Class::SetFromBox), - py::arg("_mat") = ignition::math::Material(), - py::arg("_size") = ignition::math::Vector3::Zero, - py::arg("_rot") = ignition::math::Quaternion::Identity, + py::arg("_mat") = gz::math::Material(), + py::arg("_size") = gz::math::Vector3::Zero, + py::arg("_rot") = gz::math::Quaternion::Identity, "Set inertial properties based on a Material and equivalent box.") .def("set_from_box", - py::overload_cast&, - const ignition::math::Quaternion&> + py::overload_cast&, + const gz::math::Quaternion&> (&Class::SetFromBox), py::arg("_mass") = 0, - py::arg("_size") = ignition::math::Vector3::Zero, - py::arg("_rot") = ignition::math::Quaternion::Identity, + py::arg("_size") = gz::math::Vector3::Zero, + py::arg("_rot") = gz::math::Quaternion::Identity, "Set inertial properties based on a Material and equivalent box.") .def("set_from_box", - py::overload_cast&, - const ignition::math::Quaternion&> + py::overload_cast&, + const gz::math::Quaternion&> (&Class::SetFromBox), - py::arg("_size") = ignition::math::Vector3::Zero, - py::arg("_rot") = ignition::math::Quaternion::Identity, + py::arg("_size") = gz::math::Vector3::Zero, + py::arg("_rot") = gz::math::Quaternion::Identity, "Set inertial properties based on a Material and equivalent box.") .def("set_from_cylinder_z", py::overload_cast&> + const gz::math::Quaternion&> (&Class::SetFromCylinderZ), - py::arg("_mat") = ignition::math::Material(), + py::arg("_mat") = gz::math::Material(), py::arg("_length") = 0, py::arg("_radius") = 0, - py::arg("_rot") = ignition::math::Quaternion::Identity, + py::arg("_rot") = gz::math::Quaternion::Identity, "Set inertial properties based on a Material and equivalent " "cylinder aligned with Z axis.") .def("set_from_cylinder_z", py::overload_cast&> + const gz::math::Quaternion&> (&Class::SetFromCylinderZ), py::arg("_mass") = 0, py::arg("_length") = 0, py::arg("_radius") = 0, - py::arg("_rot") = ignition::math::Quaternion::Identity, + py::arg("_rot") = gz::math::Quaternion::Identity, "Set inertial properties based on a Material and equivalent " "cylinder aligned with Z axis.") .def("set_from_cylinder_z", py::overload_cast&> + const gz::math::Quaternion&> (&Class::SetFromCylinderZ), py::arg("_length") = 0, py::arg("_radius") = 0, - py::arg("_rot") = ignition::math::Quaternion::Identity, + py::arg("_rot") = gz::math::Quaternion::Identity, "Set inertial properties based on a Material and equivalent " "cylinder aligned with Z axis.") .def("set_from_sphere", @@ -159,8 +159,8 @@ void helpDefineMathMassMatrix3(py::module &m, const std::string &typestr) "using the current mass value.") .def("equivalent_box", &Class::EquivalentBox, - py::arg("_size") = ignition::math::Vector3::Zero, - py::arg("_rot") = ignition::math::Quaternion::Identity, + py::arg("_size") = gz::math::Vector3::Zero, + py::arg("_rot") = gz::math::Quaternion::Identity, py::arg("_tol") = 1e-6, "Get dimensions and rotation offset of uniform box " "with equivalent mass and moment of inertia.") @@ -182,7 +182,7 @@ void helpDefineMathMassMatrix3(py::module &m, const std::string &typestr) "Verify that inertia values are positive semi-definite " "and satisfy the triangle inequality.") .def("epsilon", - py::overload_cast&, const T> + py::overload_cast&, const T> (&Class::Epsilon), py::arg("_tolerance") = IGN_MASSMATRIX3_DEFAULT_TOLERANCE, "Get an epsilon value that represents the amount of " @@ -202,6 +202,6 @@ void helpDefineMathMassMatrix3(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__MASSMATRIX3_HH_ +#endif // GZ_MATH_PYTHON__MASSMATRIX3_HH_ diff --git a/src/python_pybind11/src/Material.cc b/src/python_pybind11/src/Material.cc index fee925ba9..92140db55 100644 --- a/src/python_pybind11/src/Material.cc +++ b/src/python_pybind11/src/Material.cc @@ -25,7 +25,7 @@ #include #include -namespace ignition +namespace gz { namespace math { @@ -35,17 +35,17 @@ void defineMathMaterial(py::module &m, const std::string &typestr) { py::bind_map> + gz::math::MaterialType, gz::math::Material>> (m, "MaterialMap"); - using Class = ignition::math::Material; + using Class = gz::math::Material; std::string pyclass_name = typestr; py::class_ (m, pyclass_name.c_str(), py::buffer_protocol(), py::dynamic_attr()) .def(py::init<>()) - .def(py::init()) + .def(py::init()) .def(py::init()) .def(py::init()) .def(py::init()) @@ -83,24 +83,24 @@ void defineMathMaterial(py::module &m, const std::string &typestr) .def("density", &Class::Density, "Set the density value of the material in kg/m^3."); - py::enum_(m, "MaterialType") - .value("STYROFOAM", ignition::math::MaterialType::STYROFOAM) - .value("PINE", ignition::math::MaterialType::PINE) - .value("WOOD", ignition::math::MaterialType::WOOD) - .value("OAK", ignition::math::MaterialType::OAK) - .value("PLASTIC", ignition::math::MaterialType::PLASTIC) - .value("CONCRETE", ignition::math::MaterialType::CONCRETE) - .value("ALUMINUM", ignition::math::MaterialType::ALUMINUM) - .value("STEEL_ALLOY", ignition::math::MaterialType::STEEL_ALLOY) - .value("STEEL_STAINLESS", ignition::math::MaterialType::STEEL_STAINLESS) - .value("IRON", ignition::math::MaterialType::IRON) - .value("BRASS", ignition::math::MaterialType::BRASS) - .value("COPPER", ignition::math::MaterialType::COPPER) - .value("TUNGSTEN", ignition::math::MaterialType::TUNGSTEN) + py::enum_(m, "MaterialType") + .value("STYROFOAM", gz::math::MaterialType::STYROFOAM) + .value("PINE", gz::math::MaterialType::PINE) + .value("WOOD", gz::math::MaterialType::WOOD) + .value("OAK", gz::math::MaterialType::OAK) + .value("PLASTIC", gz::math::MaterialType::PLASTIC) + .value("CONCRETE", gz::math::MaterialType::CONCRETE) + .value("ALUMINUM", gz::math::MaterialType::ALUMINUM) + .value("STEEL_ALLOY", gz::math::MaterialType::STEEL_ALLOY) + .value("STEEL_STAINLESS", gz::math::MaterialType::STEEL_STAINLESS) + .value("IRON", gz::math::MaterialType::IRON) + .value("BRASS", gz::math::MaterialType::BRASS) + .value("COPPER", gz::math::MaterialType::COPPER) + .value("TUNGSTEN", gz::math::MaterialType::TUNGSTEN) .value("UNKNOWN_MATERIAL", - ignition::math::MaterialType::UNKNOWN_MATERIAL) + gz::math::MaterialType::UNKNOWN_MATERIAL) .export_values(); } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/Material.hh b/src/python_pybind11/src/Material.hh index a8029c707..e194e90c5 100644 --- a/src/python_pybind11/src/Material.hh +++ b/src/python_pybind11/src/Material.hh @@ -15,21 +15,21 @@ * */ -#ifndef IGNITION_MATH_PYTHON__MATERIAL_HH_ -#define IGNITION_MATH_PYTHON__MATERIAL_HH_ +#ifndef GZ_MATH_PYTHON__MATERIAL_HH_ +#define GZ_MATH_PYTHON__MATERIAL_HH_ #include #include namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Material +/// Define a pybind11 wrapper for an gz::math::Material /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -37,6 +37,6 @@ namespace python void defineMathMaterial(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__MATERIAL_HH_ +#endif // GZ_MATH_PYTHON__MATERIAL_HH_ diff --git a/src/python_pybind11/src/Matrix3.cc b/src/python_pybind11/src/Matrix3.cc index e987a96db..927411b2b 100644 --- a/src/python_pybind11/src/Matrix3.cc +++ b/src/python_pybind11/src/Matrix3.cc @@ -19,7 +19,7 @@ #include "Matrix3.hh" -namespace ignition +namespace gz { namespace math { @@ -33,5 +33,5 @@ void defineMathMatrix3(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz diff --git a/src/python_pybind11/src/Matrix3.hh b/src/python_pybind11/src/Matrix3.hh index a6a5a32dc..ea492b148 100644 --- a/src/python_pybind11/src/Matrix3.hh +++ b/src/python_pybind11/src/Matrix3.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__MATRIX3_HH_ -#define IGNITION_MATH_PYTHON__MATRIX3_HH_ +#ifndef GZ_MATH_PYTHON__MATRIX3_HH_ +#define GZ_MATH_PYTHON__MATRIX3_HH_ #include #include @@ -29,20 +29,20 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Matrix3 +/// Define a pybind11 wrapper for an gz::math::Matrix3 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python */ void defineMathMatrix3(py::module &m, const std::string &typestr); -/// Help define a pybind11 wrapper for an ignition::math::Matrix3 +/// Help define a pybind11 wrapper for an gz::math::Matrix3 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -50,7 +50,7 @@ void defineMathMatrix3(py::module &m, const std::string &typestr); template void helpDefineMathMatrix3(py::module &m, const std::string &typestr) { - using Class = ignition::math::Matrix3; + using Class = gz::math::Matrix3; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -64,12 +64,12 @@ void helpDefineMathMatrix3(py::module &m, const std::string &typestr) .def(py::init<>()) .def(py::init()) .def(py::init()) - .def(py::init&>()) + .def(py::init&>()) .def(py::self - py::self) .def(py::self + py::self) .def(py::self * py::self) .def(py::self * float()) - .def(py::self * ignition::math::Vector3()) + .def(py::self * gz::math::Vector3()) // .def(py::self * py::self) // .def(py::self += py::self) // .def(-py::self) @@ -127,6 +127,6 @@ void helpDefineMathMatrix3(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__MATRIX3_HH_ +#endif // GZ_MATH_PYTHON__MATRIX3_HH_ diff --git a/src/python_pybind11/src/Matrix4.cc b/src/python_pybind11/src/Matrix4.cc index 42c6bae50..73bff28ed 100644 --- a/src/python_pybind11/src/Matrix4.cc +++ b/src/python_pybind11/src/Matrix4.cc @@ -19,7 +19,7 @@ #include "Matrix4.hh" -namespace ignition +namespace gz { namespace math { @@ -33,5 +33,5 @@ void defineMathMatrix4(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz diff --git a/src/python_pybind11/src/Matrix4.hh b/src/python_pybind11/src/Matrix4.hh index f7e4a0472..076918c81 100644 --- a/src/python_pybind11/src/Matrix4.hh +++ b/src/python_pybind11/src/Matrix4.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__MATRIX4_HH_ -#define IGNITION_MATH_PYTHON__MATRIX4_HH_ +#ifndef GZ_MATH_PYTHON__MATRIX4_HH_ +#define GZ_MATH_PYTHON__MATRIX4_HH_ #include #include @@ -29,20 +29,20 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Matrix4 +/// Define a pybind11 wrapper for an gz::math::Matrix4 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python */ void defineMathMatrix4(py::module &m, const std::string &typestr); -/// Define a pybind11 wrapper for an ignition::math::Matrix4 +/// Define a pybind11 wrapper for an gz::math::Matrix4 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -50,7 +50,7 @@ void defineMathMatrix4(py::module &m, const std::string &typestr); template void helpDefineMathMatrix4(py::module &m, const std::string &typestr) { - using Class = ignition::math::Matrix4; + using Class = gz::math::Matrix4; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -64,10 +64,10 @@ void helpDefineMathMatrix4(py::module &m, const std::string &typestr) .def(py::init<>()) .def(py::init()) .def(py::init()) - .def(py::init&>()) - .def(py::init&>()) + .def(py::init&>()) + .def(py::init&>()) .def(py::self * py::self) - .def(py::self * ignition::math::Vector3()) + .def(py::self * gz::math::Vector3()) .def(py::self == py::self) .def(py::self != py::self) .def("__call__", @@ -80,7 +80,7 @@ void helpDefineMathMatrix4(py::module &m, const std::string &typestr) py::overload_cast(&Class::SetTranslation), "Set the translational values [ (0, 3) (1, 3) (2, 3) ]") .def("set_translation", - py::overload_cast&>( + py::overload_cast&>( &Class::SetTranslation), "Set the translational values [ (0, 3) (1, 3) (2, 3) ]") .def("translation", @@ -111,7 +111,7 @@ void helpDefineMathMatrix4(py::module &m, const std::string &typestr) &Class::Pose, "Get the transformation as math::Pose") .def("scale", - py::overload_cast&>( + py::overload_cast&>( &Class::Scale), "Get the scale values as a Vector3") .def("scale", @@ -121,8 +121,8 @@ void helpDefineMathMatrix4(py::module &m, const std::string &typestr) &Class::IsAffine, "Get the scale values as a Vector3") .def("transform_affine", - py::overload_cast&, - ignition::math::Vector3&>( + py::overload_cast&, + gz::math::Vector3&>( &Class::TransformAffine, py::const_), "Perform an affine transformation") .def("equal", @@ -130,9 +130,9 @@ void helpDefineMathMatrix4(py::module &m, const std::string &typestr) "Equality test operator") .def("look_at", &Class::LookAt, - // py::arg("_eye") = ignition::math::Vector3::Zero, - py::arg("_target") = ignition::math::Vector3::Zero, - py::arg("_up") = ignition::math::Vector3::UnitZ, + // py::arg("_eye") = gz::math::Vector3::Zero, + py::arg("_target") = gz::math::Vector3::Zero, + py::arg("_up") = gz::math::Vector3::UnitZ, "Get transform which translates to _eye and rotates the X axis " "so it faces the _target. The rotation is such that Z axis is in the" "_up direction, if possible. The coordinate system is right-handed") @@ -148,7 +148,7 @@ void helpDefineMathMatrix4(py::module &m, const std::string &typestr) .def("__repr__", toString); } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz -#endif // IGNITION_MATH_PYTHON__MATRIX4_HH_ +#endif // GZ_MATH_PYTHON__MATRIX4_HH_ diff --git a/src/python_pybind11/src/MovingWindowFilter.cc b/src/python_pybind11/src/MovingWindowFilter.cc index c90733784..00b9a3108 100644 --- a/src/python_pybind11/src/MovingWindowFilter.cc +++ b/src/python_pybind11/src/MovingWindowFilter.cc @@ -20,7 +20,7 @@ #include #include "MovingWindowFilter.hh" -namespace ignition +namespace gz { namespace math { @@ -30,9 +30,9 @@ void defineMathMovingWindowFilter(py::module &m, const std::string &typestr) { helpDefineMathMovingWindowFilter(m, typestr + "i"); helpDefineMathMovingWindowFilter(m, typestr + "d"); - helpDefineMathMovingWindowFilter(m, typestr + "v3"); + helpDefineMathMovingWindowFilter(m, typestr + "v3"); } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz diff --git a/src/python_pybind11/src/MovingWindowFilter.hh b/src/python_pybind11/src/MovingWindowFilter.hh index a499ccb64..e09cc4430 100644 --- a/src/python_pybind11/src/MovingWindowFilter.hh +++ b/src/python_pybind11/src/MovingWindowFilter.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__MOVINGWINDOWFILTER_HH_ -#define IGNITION_MATH_PYTHON__MOVINGWINDOWFILTER_HH_ +#ifndef GZ_MATH_PYTHON__MOVINGWINDOWFILTER_HH_ +#define GZ_MATH_PYTHON__MOVINGWINDOWFILTER_HH_ #include @@ -27,13 +27,13 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Help define a pybind11 wrapper for an ignition::math::MovingWindowFilter +/// Help define a pybind11 wrapper for an gz::math::MovingWindowFilter /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -41,7 +41,7 @@ namespace python template void helpDefineMathMovingWindowFilter(py::module &m, const std::string &typestr) { - using Class = ignition::math::MovingWindowFilter; + using Class = gz::math::MovingWindowFilter; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -57,7 +57,7 @@ void helpDefineMathMovingWindowFilter(py::module &m, const std::string &typestr) .def("value", &Class::Value, "Get filtered result"); } -/// Define a pybind11 wrapper for an ignition::math::MovingWindowFilter +/// Define a pybind11 wrapper for an gz::math::MovingWindowFilter /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -65,6 +65,6 @@ void helpDefineMathMovingWindowFilter(py::module &m, const std::string &typestr) void defineMathMovingWindowFilter(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__MovingWindowFilterD_HH_ +#endif // GZ_MATH_PYTHON__MovingWindowFilterD_HH_ diff --git a/src/python_pybind11/src/OrientedBox.hh b/src/python_pybind11/src/OrientedBox.hh index 118b15f86..c2704ee08 100644 --- a/src/python_pybind11/src/OrientedBox.hh +++ b/src/python_pybind11/src/OrientedBox.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__ORIENTEDBOX_HH_ -#define IGNITION_MATH_PYTHON__ORIENTEDBOX_HH_ +#ifndef GZ_MATH_PYTHON__ORIENTEDBOX_HH_ +#define GZ_MATH_PYTHON__ORIENTEDBOX_HH_ #include #include @@ -29,13 +29,13 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::OrientedBox +/// Define a pybind11 wrapper for an gz::math::OrientedBox /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -44,7 +44,7 @@ template void defineMathOrientedBox(py::module &m, const std::string &typestr) { - using Class = ignition::math::OrientedBox; + using Class = gz::math::OrientedBox; std::string pyclass_name = typestr; auto toString = [](const Class &si) { std::stringstream stream; @@ -56,19 +56,19 @@ void defineMathOrientedBox(py::module &m, const std::string &typestr) py::buffer_protocol(), py::dynamic_attr()) .def(py::init<>()) - .def(py::init&, - const ignition::math::Pose3&>()) - .def(py::init&, - const ignition::math::Pose3&, - const ignition::math::Material&>()) - .def(py::init&>()) + .def(py::init&, + const gz::math::Pose3&>()) + .def(py::init&, + const gz::math::Pose3&, + const gz::math::Material&>()) + .def(py::init&>()) .def(py::init()) - .def(py::init&, - const ignition::math::Material&>()) + .def(py::init&, + const gz::math::Material&>()) .def(py::self != py::self) .def(py::self == py::self) .def("pose", - py::overload_cast&>(&Class::Pose), + py::overload_cast&>(&Class::Pose), "Set the box pose, which is the pose of its center.") .def("pose", py::overload_cast<>(&Class::Pose, py::const_), @@ -77,7 +77,7 @@ void defineMathOrientedBox(py::module &m, const std::string &typestr) py::overload_cast<>(&Class::Size, py::const_), "Get the size of the OrientedBox.") .def("size", - py::overload_cast&> + py::overload_cast&> (&Class::Size), "Set the size of the OrientedBox.") .def("x_length", @@ -124,6 +124,6 @@ void defineMathOrientedBox(py::module &m, const std::string &typestr) } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__ORIENTEDBOX_HH_ +#endif // GZ_MATH_PYTHON__ORIENTEDBOX_HH_ diff --git a/src/python_pybind11/src/PID.cc b/src/python_pybind11/src/PID.cc index 4d8ccb37c..a3107d9bf 100644 --- a/src/python_pybind11/src/PID.cc +++ b/src/python_pybind11/src/PID.cc @@ -22,7 +22,7 @@ #include "PID.hh" -namespace ignition +namespace gz { namespace math { @@ -30,7 +30,7 @@ namespace python { void defineMathPID(py::module &m, const std::string &typestr) { - using Class = ignition::math::PID; + using Class = gz::math::PID; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -123,4 +123,4 @@ void defineMathPID(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/PID.hh b/src/python_pybind11/src/PID.hh index 819fba131..4295a4927 100644 --- a/src/python_pybind11/src/PID.hh +++ b/src/python_pybind11/src/PID.hh @@ -15,20 +15,20 @@ * */ -#ifndef IGNITION_MATH_PYTHON__PID_HH_ -#define IGNITION_MATH_PYTHON__PID_HH_ +#ifndef GZ_MATH_PYTHON__PID_HH_ +#define GZ_MATH_PYTHON__PID_HH_ #include #include namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::PID +/// Define a pybind11 wrapper for an gz::math::PID /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -36,6 +36,6 @@ namespace python void defineMathPID(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__PID_HH_ +#endif // GZ_MATH_PYTHON__PID_HH_ diff --git a/src/python_pybind11/src/Plane.hh b/src/python_pybind11/src/Plane.hh index f310dbd26..da93bb052 100644 --- a/src/python_pybind11/src/Plane.hh +++ b/src/python_pybind11/src/Plane.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__PLANE_HH_ -#define IGNITION_MATH_PYTHON__PLANE_HH_ +#ifndef GZ_MATH_PYTHON__PLANE_HH_ +#define GZ_MATH_PYTHON__PLANE_HH_ #include @@ -29,13 +29,13 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Plane +/// Define a pybind11 wrapper for an gz::math::Plane /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -43,52 +43,52 @@ namespace python template void defineMathPlane(py::module &m, const std::string &typestr) { - using Class = ignition::math::Plane; + using Class = gz::math::Plane; std::string pyclass_name = typestr; py::class_ plane(m, pyclass_name.c_str(), py::buffer_protocol(), py::dynamic_attr()); plane.def(py::init<>()) - .def(py::init&, T>(), - py::arg("_normal") = ignition::math::Vector3::Zero, + .def(py::init&, T>(), + py::arg("_normal") = gz::math::Vector3::Zero, py::arg("_offset") = 0.0) - .def(py::init&, - const ignition::math::Vector2&, T>()) + .def(py::init&, + const gz::math::Vector2&, T>()) .def(py::init()) .def("set", - py::overload_cast&, T> + py::overload_cast&, T> (&Class::Set), "Set the plane") .def("set", - py::overload_cast&, - const ignition::math::Vector2&, T> + py::overload_cast&, + const gz::math::Vector2&, T> (&Class::Set), "Set the plane") .def("distance", - py::overload_cast&> + py::overload_cast&> (&Class::Distance, py::const_), "The distance to the plane from the given point. The " "distance can be negative, which indicates the point is on the " "negative side of the plane.") .def("distance", - py::overload_cast&, - const ignition::math::Vector3&> + py::overload_cast&, + const gz::math::Vector3&> (&Class::Distance, py::const_), "Get distance to the plane give an origin and direction.") .def("intersection", &Class::Intersection, - py::arg("_point") = ignition::math::Vector3::Zero, - py::arg("_gradient") = ignition::math::Vector3::Zero, + py::arg("_point") = gz::math::Vector3::Zero, + py::arg("_gradient") = gz::math::Vector3::Zero, py::arg("_tolerance") = 1e-6, "Get the intersection of an infinite line with the plane, " "given the line's gradient and a point in parametrized space.") .def("side", - py::overload_cast&> + py::overload_cast&> (&Class::Side, py::const_), "The side of the plane a point is on.") .def("side", - py::overload_cast + py::overload_cast (&Class::Side, py::const_), "The side of the plane a point is on.") .def("size", @@ -109,16 +109,16 @@ void defineMathPlane(py::module &m, const std::string &typestr) return Class(self); }, "memo"_a); - py::enum_(m, "PlaneSide") - .value("NEGATIVE_SIDE", ignition::math::Planed::PlaneSide::NEGATIVE_SIDE) - .value("POSITIVE_SIDE", ignition::math::Planed::PlaneSide::POSITIVE_SIDE) - .value("NO_SIDE", ignition::math::Planed::PlaneSide::NO_SIDE) - .value("BOTH_SIDE", ignition::math::Planed::PlaneSide::BOTH_SIDE) + py::enum_(m, "PlaneSide") + .value("NEGATIVE_SIDE", gz::math::Planed::PlaneSide::NEGATIVE_SIDE) + .value("POSITIVE_SIDE", gz::math::Planed::PlaneSide::POSITIVE_SIDE) + .value("NO_SIDE", gz::math::Planed::PlaneSide::NO_SIDE) + .value("BOTH_SIDE", gz::math::Planed::PlaneSide::BOTH_SIDE) .export_values(); } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__PLANE_HH_ +#endif // GZ_MATH_PYTHON__PLANE_HH_ diff --git a/src/python_pybind11/src/Pose3.cc b/src/python_pybind11/src/Pose3.cc index b79de9d8e..7996e0b3a 100644 --- a/src/python_pybind11/src/Pose3.cc +++ b/src/python_pybind11/src/Pose3.cc @@ -19,7 +19,7 @@ #include "Pose3.hh" -namespace ignition +namespace gz { namespace math { @@ -33,5 +33,5 @@ void defineMathPose3(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz diff --git a/src/python_pybind11/src/Pose3.hh b/src/python_pybind11/src/Pose3.hh index 4dc6a17c7..209535f6c 100644 --- a/src/python_pybind11/src/Pose3.hh +++ b/src/python_pybind11/src/Pose3.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__POSE3_HH_ -#define IGNITION_MATH_PYTHON__POSE3_HH_ +#ifndef GZ_MATH_PYTHON__POSE3_HH_ +#define GZ_MATH_PYTHON__POSE3_HH_ #include #include @@ -29,20 +29,20 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Pose3 +/// Define a pybind11 wrapper for an gz::math::Pose3 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python */ void defineMathPose3(py::module &m, const std::string &typestr); -/// Help define a pybind11 wrapper for an ignition::math::Pose3 +/// Help define a pybind11 wrapper for an gz::math::Pose3 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -50,7 +50,7 @@ void defineMathPose3(py::module &m, const std::string &typestr); template void helpDefineMathPose3(py::module &m, const std::string &typestr) { - using Class = ignition::math::Pose3; + using Class = gz::math::Pose3; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -62,8 +62,8 @@ void helpDefineMathPose3(py::module &m, const std::string &typestr) py::buffer_protocol(), py::dynamic_attr()) .def(py::init<>()) - .def(py::init&, - const ignition::math::Quaternion&>()) + .def(py::init&, + const gz::math::Quaternion&>()) .def(py::init()) .def(py::init()) .def(py::init()) @@ -77,12 +77,12 @@ void helpDefineMathPose3(py::module &m, const std::string &typestr) .def(py::self * py::self) .def(py::self *= py::self) .def("set", - py::overload_cast&, - const ignition::math::Quaternion&>(&Class::Set), + py::overload_cast&, + const gz::math::Quaternion&>(&Class::Set), "Set the pose from a Vector3 and a Quaternion") .def("set", - py::overload_cast&, - const ignition::math::Vector3&>(&Class::Set), + py::overload_cast&, + const gz::math::Vector3&>(&Class::Set), "Set the pose from pos and rpy vectors") .def("set", py::overload_cast(&Class::Set), @@ -97,7 +97,7 @@ void helpDefineMathPose3(py::module &m, const std::string &typestr) &Class::Inverse, "Get the inverse of this pose") .def("coord_position_add", - py::overload_cast&>( + py::overload_cast&>( &Class::CoordPositionAdd, py::const_), "Add one point to a vector: result = this + pos") .def("coord_position_add", @@ -152,7 +152,7 @@ void helpDefineMathPose3(py::module &m, const std::string &typestr) .def("__repr__", toString); } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz -#endif // IGNITION_MATH_PYTHON__POSE3_HH_ +#endif // GZ_MATH_PYTHON__POSE3_HH_ diff --git a/src/python_pybind11/src/Quaternion.cc b/src/python_pybind11/src/Quaternion.cc index c6cf443e6..2b57f597c 100644 --- a/src/python_pybind11/src/Quaternion.cc +++ b/src/python_pybind11/src/Quaternion.cc @@ -19,7 +19,7 @@ #include "Quaternion.hh" -namespace ignition +namespace gz { namespace math { @@ -33,5 +33,5 @@ void defineMathQuaternion(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz diff --git a/src/python_pybind11/src/Quaternion.hh b/src/python_pybind11/src/Quaternion.hh index e191bb782..be1eaa2f4 100644 --- a/src/python_pybind11/src/Quaternion.hh +++ b/src/python_pybind11/src/Quaternion.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__QUATERNION_HH_ -#define IGNITION_MATH_PYTHON__QUATERNION_HH_ +#ifndef GZ_MATH_PYTHON__QUATERNION_HH_ +#define GZ_MATH_PYTHON__QUATERNION_HH_ #include #include @@ -32,20 +32,20 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Quaternion +/// Define a pybind11 wrapper for an gz::math::Quaternion /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python */ void defineMathQuaternion(py::module &m, const std::string &typestr); -/// Help define a pybind11 wrapper for an ignition::math::Quaternion +/// Help define a pybind11 wrapper for an gz::math::Quaternion /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -53,7 +53,7 @@ void defineMathQuaternion(py::module &m, const std::string &typestr); template void helpDefineMathQuaternion(py::module &m, const std::string &typestr) { - using Class = ignition::math::Quaternion; + using Class = gz::math::Quaternion; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -67,9 +67,9 @@ void helpDefineMathQuaternion(py::module &m, const std::string &typestr) .def(py::init<>()) .def(py::init()) .def(py::init()) - .def(py::init&, T>()) - .def(py::init&>()) - .def(py::init&>()) + .def(py::init&, T>()) + .def(py::init&>()) + .def(py::init&>()) .def(py::init()) .def(py::self + py::self) .def(py::self += py::self) @@ -78,7 +78,7 @@ void helpDefineMathQuaternion(py::module &m, const std::string &typestr) .def(py::self -= py::self) .def(py::self * py::self) .def(py::self * float()) - .def(py::self * ignition::math::Vector3()) + .def(py::self * gz::math::Vector3()) .def(py::self *= py::self) .def(py::self == py::self) .def(py::self != py::self) @@ -106,14 +106,14 @@ void helpDefineMathQuaternion(py::module &m, const std::string &typestr) py::overload_cast(&Class::SetFromAxisAngle), "Set the quaternion from an axis and angle") .def("set_from_axis_angle", - py::overload_cast&, T>( + py::overload_cast&, T>( &Class::SetFromAxisAngle), "Set the quaternion from an axis and angle") .def("set", &Class::Set, "Set this quaternion from 4 floating numbers") .def("set_from_euler", - py::overload_cast&>( + py::overload_cast&>( &Class::SetFromEuler), "Set the quaternion from Euler angles. The order of operations " "is roll, pitch, yaw around a fixed body frame axis " @@ -125,7 +125,7 @@ void helpDefineMathQuaternion(py::module &m, const std::string &typestr) py::overload_cast<>(&Class::Euler, py::const_), "Return the rotation in Euler angles") .def("euler_to_quaternion", - py::overload_cast&>( + py::overload_cast&>( &Class::EulerToQuaternion), "Convert euler angles to quatern.") .def("euler_to_quaternion", @@ -136,7 +136,7 @@ void helpDefineMathQuaternion(py::module &m, const std::string &typestr) .def("yaw", &Class::Yaw, "Get the Euler yaw angle in radians") .def("axis_angle", [](const Class &self) { - ignition::math::Vector3 _axis; + gz::math::Vector3 _axis; T _angle; self.AxisAngle(_axis, _angle); return std::make_tuple(_axis, _angle); @@ -215,6 +215,6 @@ void helpDefineMathQuaternion(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__QUATERNION_HH_ +#endif // GZ_MATH_PYTHON__QUATERNION_HH_ diff --git a/src/python_pybind11/src/Rand.cc b/src/python_pybind11/src/Rand.cc index 9818ba229..927a28573 100644 --- a/src/python_pybind11/src/Rand.cc +++ b/src/python_pybind11/src/Rand.cc @@ -19,7 +19,7 @@ #include "Rand.hh" #include -namespace ignition +namespace gz { namespace math { @@ -27,7 +27,7 @@ namespace python { void defineMathRand(py::module &m, const std::string &typestr) { - using Class = ignition::math::Rand; + using Class = gz::math::Rand; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -35,24 +35,24 @@ void defineMathRand(py::module &m, const std::string &typestr) py::dynamic_attr()) .def(py::init<>()) .def("seed", - py::overload_cast<>(&ignition::math::Rand::Seed), + py::overload_cast<>(&gz::math::Rand::Seed), "Get the seed value.") .def("seed", - py::overload_cast(&ignition::math::Rand::Seed), + py::overload_cast(&gz::math::Rand::Seed), "Set the seed value.") .def("dbl_uniform", - ignition::math::Rand::DblUniform, + gz::math::Rand::DblUniform, "Get a double from a uniform distribution") .def("dbl_normal", - ignition::math::Rand::DblNormal, + gz::math::Rand::DblNormal, "Get a double from a normal distribution") .def("int_uniform", - ignition::math::Rand::IntUniform, + gz::math::Rand::IntUniform, "Get a integer from a uniform distribution") .def("int_normal", - ignition::math::Rand::IntNormal, + gz::math::Rand::IntNormal, "Get a integer from a normal distribution"); } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz diff --git a/src/python_pybind11/src/Rand.hh b/src/python_pybind11/src/Rand.hh index 9242fdbf6..0d7976d56 100644 --- a/src/python_pybind11/src/Rand.hh +++ b/src/python_pybind11/src/Rand.hh @@ -15,27 +15,27 @@ * */ -#ifndef IGNITION_MATH_PYTHON__RAND_HH_ -#define IGNITION_MATH_PYTHON__RAND_HH_ +#ifndef GZ_MATH_PYTHON__RAND_HH_ +#define GZ_MATH_PYTHON__RAND_HH_ #include #include namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Rand +/// Define a pybind11 wrapper for an gz::math::Rand /** * \param[in] module a pybind11 module to add the definition to */ void defineMathRand(py::module &m, const std::string &typestr); } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz -#endif // IGNITION_MATH_PYTHON__RAND_HH_ +#endif // GZ_MATH_PYTHON__RAND_HH_ diff --git a/src/python_pybind11/src/RollingMean.cc b/src/python_pybind11/src/RollingMean.cc index c5c446eba..888e00391 100644 --- a/src/python_pybind11/src/RollingMean.cc +++ b/src/python_pybind11/src/RollingMean.cc @@ -18,7 +18,7 @@ #include "RollingMean.hh" #include -namespace ignition +namespace gz { namespace math { @@ -26,7 +26,7 @@ namespace python { void defineMathRollingMean(py::module &m, const std::string &typestr) { - using Class = ignition::math::RollingMean; + using Class = gz::math::RollingMean; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -45,4 +45,4 @@ void defineMathRollingMean(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/RollingMean.hh b/src/python_pybind11/src/RollingMean.hh index 122e513fc..7ee67f187 100644 --- a/src/python_pybind11/src/RollingMean.hh +++ b/src/python_pybind11/src/RollingMean.hh @@ -15,21 +15,21 @@ * */ -#ifndef IGNITION_MATH_PYTHON__ROLLINGMEAN_HH_ -#define IGNITION_MATH_PYTHON__ROLLINGMEAN_HH_ +#ifndef GZ_MATH_PYTHON__ROLLINGMEAN_HH_ +#define GZ_MATH_PYTHON__ROLLINGMEAN_HH_ #include #include namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::RollingMean +/// Define a pybind11 wrapper for an gz::math::RollingMean /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -37,6 +37,6 @@ namespace python void defineMathRollingMean(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__ROLLINGMEAN_HH_ +#endif // GZ_MATH_PYTHON__ROLLINGMEAN_HH_ diff --git a/src/python_pybind11/src/RotationSpline.cc b/src/python_pybind11/src/RotationSpline.cc index fab414e6a..bc400fdd6 100644 --- a/src/python_pybind11/src/RotationSpline.cc +++ b/src/python_pybind11/src/RotationSpline.cc @@ -18,7 +18,7 @@ #include "RotationSpline.hh" #include -namespace ignition +namespace gz { namespace math { @@ -26,7 +26,7 @@ namespace python { void defineMathRotationSpline(py::module &m, const std::string &typestr) { - using Class = ignition::math::RotationSpline; + using Class = gz::math::RotationSpline; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -68,4 +68,4 @@ void defineMathRotationSpline(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/RotationSpline.hh b/src/python_pybind11/src/RotationSpline.hh index 670b2ad97..d870fd508 100644 --- a/src/python_pybind11/src/RotationSpline.hh +++ b/src/python_pybind11/src/RotationSpline.hh @@ -15,21 +15,21 @@ * */ -#ifndef IGNITION_MATH_PYTHON__ROTATIONSPLINE_HH_ -#define IGNITION_MATH_PYTHON__ROTATIONSPLINE_HH_ +#ifndef GZ_MATH_PYTHON__ROTATIONSPLINE_HH_ +#define GZ_MATH_PYTHON__ROTATIONSPLINE_HH_ #include #include namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::RotationSpline +/// Define a pybind11 wrapper for an gz::math::RotationSpline /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -37,6 +37,6 @@ namespace python void defineMathRotationSpline(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__ROTATIONSPLINE_HH_ +#endif // GZ_MATH_PYTHON__ROTATIONSPLINE_HH_ diff --git a/src/python_pybind11/src/SemanticVersion.cc b/src/python_pybind11/src/SemanticVersion.cc index 42019f367..5c0c42070 100644 --- a/src/python_pybind11/src/SemanticVersion.cc +++ b/src/python_pybind11/src/SemanticVersion.cc @@ -25,7 +25,7 @@ using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { @@ -33,7 +33,7 @@ namespace python { void defineMathSemanticVersion(py::module &m, const std::string &typestr) { - using Class = ignition::math::SemanticVersion; + using Class = gz::math::SemanticVersion; std::string pyclass_name = typestr; auto toString = [](const Class &si) { std::stringstream stream; @@ -92,4 +92,4 @@ void defineMathSemanticVersion(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/SemanticVersion.hh b/src/python_pybind11/src/SemanticVersion.hh index 0c600c2a3..1468f7eed 100644 --- a/src/python_pybind11/src/SemanticVersion.hh +++ b/src/python_pybind11/src/SemanticVersion.hh @@ -15,21 +15,21 @@ * */ -#ifndef IGNITION_MATH_PYTHON__SEMANTICVERSION_HH_ -#define IGNITION_MATH_PYTHON__SEMANTICVERSION_HH_ +#ifndef GZ_MATH_PYTHON__SEMANTICVERSION_HH_ +#define GZ_MATH_PYTHON__SEMANTICVERSION_HH_ #include #include namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::SemanticVersion +/// Define a pybind11 wrapper for an gz::math::SemanticVersion /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -37,6 +37,6 @@ namespace python void defineMathSemanticVersion(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__SEMANTICVERSION_HH_ +#endif // GZ_MATH_PYTHON__SEMANTICVERSION_HH_ diff --git a/src/python_pybind11/src/SignalStats.cc b/src/python_pybind11/src/SignalStats.cc index 8260cf109..6013df9b6 100644 --- a/src/python_pybind11/src/SignalStats.cc +++ b/src/python_pybind11/src/SignalStats.cc @@ -22,7 +22,7 @@ #include "SignalStats.hh" #include -namespace ignition +namespace gz { namespace math { @@ -31,7 +31,7 @@ namespace python ////////////////////////////////////////////////// void defineMathSignalStats(py::module &m, const std::string &typestr) { - using Class = ignition::math::SignalStats; + using Class = gz::math::SignalStats; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -56,7 +56,7 @@ void defineMathSignalStats(py::module &m, const std::string &typestr) } ////////////////////////////////////////////////// -class SignalStatisticTrampoline : public ignition::math::SignalStatistic +class SignalStatisticTrampoline : public gz::math::SignalStatistic { public: SignalStatisticTrampoline() : SignalStatistic() {} @@ -68,7 +68,7 @@ class SignalStatisticTrampoline : public ignition::math::SignalStatistic { PYBIND11_OVERLOAD_PURE( double, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) Value, ); @@ -78,7 +78,7 @@ class SignalStatisticTrampoline : public ignition::math::SignalStatistic { PYBIND11_OVERLOAD_PURE( std::string, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) ShortName, ); @@ -88,7 +88,7 @@ class SignalStatisticTrampoline : public ignition::math::SignalStatistic { PYBIND11_OVERLOAD_PURE( size_t, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) Count, ); @@ -98,7 +98,7 @@ class SignalStatisticTrampoline : public ignition::math::SignalStatistic { PYBIND11_OVERLOAD_PURE( void, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) InsertData, _data // Argument(s) (...) @@ -109,7 +109,7 @@ class SignalStatisticTrampoline : public ignition::math::SignalStatistic { PYBIND11_OVERLOAD_PURE( void, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) Reset, ); @@ -119,7 +119,7 @@ class SignalStatisticTrampoline : public ignition::math::SignalStatistic ////////////////////////////////////////////////// void defineMathSignalStatistic(py::module &m, const std::string &typestr) { - using Class = ignition::math::SignalStatistic; + using Class = gz::math::SignalStatistic; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -145,7 +145,7 @@ void defineMathSignalStatistic(py::module &m, const std::string &typestr) } ////////////////////////////////////////////////// -class SignalVarianceTrampoline : public ignition::math::SignalVariance { +class SignalVarianceTrampoline : public gz::math::SignalVariance { public: // Inherit the constructors SignalVarianceTrampoline(){} @@ -155,7 +155,7 @@ class SignalVarianceTrampoline : public ignition::math::SignalVariance { { PYBIND11_OVERLOAD_PURE( double, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) Value, ); @@ -165,7 +165,7 @@ class SignalVarianceTrampoline : public ignition::math::SignalVariance { { PYBIND11_OVERLOAD_PURE( std::string, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) ShortName, ); @@ -175,7 +175,7 @@ class SignalVarianceTrampoline : public ignition::math::SignalVariance { { PYBIND11_OVERLOAD_PURE( void, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) InsertData, _data // Argument(s) (...) @@ -186,7 +186,7 @@ class SignalVarianceTrampoline : public ignition::math::SignalVariance { ////////////////////////////////////////////////// void defineMathSignalVariance(py::module &m, const std::string &typestr) { - using Class = ignition::math::SignalVariance; + using Class = gz::math::SignalVariance; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -211,7 +211,7 @@ void defineMathSignalVariance(py::module &m, const std::string &typestr) } ////////////////////////////////////////////////// -class SignalMaximumTrampoline : public ignition::math::SignalMaximum +class SignalMaximumTrampoline : public gz::math::SignalMaximum { public: // Inherit the constructors @@ -222,7 +222,7 @@ class SignalMaximumTrampoline : public ignition::math::SignalMaximum { PYBIND11_OVERLOAD_PURE( double, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) Value, ); @@ -232,7 +232,7 @@ class SignalMaximumTrampoline : public ignition::math::SignalMaximum { PYBIND11_OVERLOAD_PURE( std::string, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) ShortName, ); @@ -242,7 +242,7 @@ class SignalMaximumTrampoline : public ignition::math::SignalMaximum { PYBIND11_OVERLOAD_PURE( void, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) InsertData, _data // Argument(s) (...) @@ -253,7 +253,7 @@ class SignalMaximumTrampoline : public ignition::math::SignalMaximum ////////////////////////////////////////////////// void defineMathSignalMaximum(py::module &m, const std::string &typestr) { - using Class = ignition::math::SignalMaximum; + using Class = gz::math::SignalMaximum; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -278,7 +278,7 @@ void defineMathSignalMaximum(py::module &m, const std::string &typestr) } ////////////////////////////////////////////////// -class SignalMinimumTrampoline : public ignition::math::SignalMinimum +class SignalMinimumTrampoline : public gz::math::SignalMinimum { public: // Inherit the constructors @@ -289,7 +289,7 @@ class SignalMinimumTrampoline : public ignition::math::SignalMinimum { PYBIND11_OVERLOAD_PURE( double, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) Value, ); @@ -299,7 +299,7 @@ class SignalMinimumTrampoline : public ignition::math::SignalMinimum { PYBIND11_OVERLOAD_PURE( std::string, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) ShortName, ); @@ -309,7 +309,7 @@ class SignalMinimumTrampoline : public ignition::math::SignalMinimum { PYBIND11_OVERLOAD_PURE( void, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) InsertData, _data // Argument(s) (...) @@ -320,7 +320,7 @@ class SignalMinimumTrampoline : public ignition::math::SignalMinimum ////////////////////////////////////////////////// void defineMathSignalMinimum(py::module &m, const std::string &typestr) { - using Class = ignition::math::SignalMinimum; + using Class = gz::math::SignalMinimum; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -345,7 +345,7 @@ void defineMathSignalMinimum(py::module &m, const std::string &typestr) } ////////////////////////////////////////////////// -class SignalMeanTrampoline : public ignition::math::SignalMean +class SignalMeanTrampoline : public gz::math::SignalMean { public: // Inherit the constructors @@ -356,7 +356,7 @@ class SignalMeanTrampoline : public ignition::math::SignalMean { PYBIND11_OVERLOAD_PURE( double, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) Value, ); @@ -366,7 +366,7 @@ class SignalMeanTrampoline : public ignition::math::SignalMean { PYBIND11_OVERLOAD_PURE( std::string, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) ShortName, ); @@ -376,7 +376,7 @@ class SignalMeanTrampoline : public ignition::math::SignalMean { PYBIND11_OVERLOAD_PURE( void, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) InsertData, _data // Argument(s) (...) @@ -387,7 +387,7 @@ class SignalMeanTrampoline : public ignition::math::SignalMean ////////////////////////////////////////////////// void defineMathSignalMean(py::module &m, const std::string &typestr) { - using Class = ignition::math::SignalMean; + using Class = gz::math::SignalMean; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -413,7 +413,7 @@ void defineMathSignalMean(py::module &m, const std::string &typestr) ////////////////////////////////////////////////// class SignalRootMeanSquareTrampoline : - public ignition::math::SignalRootMeanSquare + public gz::math::SignalRootMeanSquare { public: // Inherit the constructors @@ -424,7 +424,7 @@ class SignalRootMeanSquareTrampoline : { PYBIND11_OVERLOAD_PURE( double, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) Value, ); @@ -434,7 +434,7 @@ class SignalRootMeanSquareTrampoline : { PYBIND11_OVERLOAD_PURE( std::string, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) ShortName ); @@ -444,7 +444,7 @@ class SignalRootMeanSquareTrampoline : { PYBIND11_OVERLOAD_PURE( void, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) InsertData, _data // Argument(s) (...) @@ -455,7 +455,7 @@ class SignalRootMeanSquareTrampoline : ////////////////////////////////////////////////// void defineMathSignalRootMeanSquare(py::module &m, const std::string &typestr) { - using Class = ignition::math::SignalRootMeanSquare; + using Class = gz::math::SignalRootMeanSquare; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -481,7 +481,7 @@ void defineMathSignalRootMeanSquare(py::module &m, const std::string &typestr) ////////////////////////////////////////////////// class SignalMaxAbsoluteValueTrampoline : - public ignition::math::SignalMaxAbsoluteValue + public gz::math::SignalMaxAbsoluteValue { public: // Inherit the constructors @@ -492,7 +492,7 @@ class SignalMaxAbsoluteValueTrampoline : { PYBIND11_OVERLOAD_PURE( double, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) Value, ); @@ -502,7 +502,7 @@ class SignalMaxAbsoluteValueTrampoline : { PYBIND11_OVERLOAD_PURE( std::string, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) ShortName, ); @@ -512,7 +512,7 @@ class SignalMaxAbsoluteValueTrampoline : { PYBIND11_OVERLOAD_PURE( void, // Return type (ret_type) - ignition::math::SignalStatistic, // Parent class (cname) + gz::math::SignalStatistic, // Parent class (cname) // Name of function in C++ (must match Python name) (fn) InsertData, _data // Argument(s) (...) @@ -523,7 +523,7 @@ class SignalMaxAbsoluteValueTrampoline : ////////////////////////////////////////////////// void defineMathSignalMaxAbsoluteValue(py::module &m, const std::string &typestr) { - using Class = ignition::math::SignalMaxAbsoluteValue; + using Class = gz::math::SignalMaxAbsoluteValue; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -548,4 +548,4 @@ void defineMathSignalMaxAbsoluteValue(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/SignalStats.hh b/src/python_pybind11/src/SignalStats.hh index 7e92e1940..aac09d63e 100644 --- a/src/python_pybind11/src/SignalStats.hh +++ b/src/python_pybind11/src/SignalStats.hh @@ -15,56 +15,56 @@ * */ -#ifndef IGNITION_MATH_PYTHON__SIGNALSTATS_HH_ -#define IGNITION_MATH_PYTHON__SIGNALSTATS_HH_ +#ifndef GZ_MATH_PYTHON__SIGNALSTATS_HH_ +#define GZ_MATH_PYTHON__SIGNALSTATS_HH_ #include #include namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::SignalStats +/// Define a pybind11 wrapper for an gz::math::SignalStats /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python */ void defineMathSignalStats(py::module &m, const std::string &typestr); -/// Define a pybind11 wrapper for an ignition::math::SignalStatistic +/// Define a pybind11 wrapper for an gz::math::SignalStatistic /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python */ void defineMathSignalStatistic(py::module &m, const std::string &typestr); -/// Define a pybind11 wrapper for an ignition::math::SignalMaximum +/// Define a pybind11 wrapper for an gz::math::SignalMaximum /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python */ void defineMathSignalMaximum(py::module &m, const std::string &typestr); -/// Define a pybind11 wrapper for an ignition::math::SignalMinimum +/// Define a pybind11 wrapper for an gz::math::SignalMinimum /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python */ void defineMathSignalMinimum(py::module &m, const std::string &typestr); -/// Define a pybind11 wrapper for an ignition::math::SignalVariance +/// Define a pybind11 wrapper for an gz::math::SignalVariance /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python */ void defineMathSignalVariance(py::module &m, const std::string &typestr); -/// Define a pybind11 wrapper for an ignition::math::SignalMaxAbsoluteValue +/// Define a pybind11 wrapper for an gz::math::SignalMaxAbsoluteValue /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -72,14 +72,14 @@ void defineMathSignalVariance(py::module &m, const std::string &typestr); void defineMathSignalMaxAbsoluteValue( py::module &m, const std::string &typestr); -/// Define a pybind11 wrapper for an ignition::math::SignalRootMeanSquare +/// Define a pybind11 wrapper for an gz::math::SignalRootMeanSquare /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python */ void defineMathSignalRootMeanSquare(py::module &m, const std::string &typestr); -/// Define a pybind11 wrapper for an ignition::math::SignalMean +/// Define a pybind11 wrapper for an gz::math::SignalMean /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -87,6 +87,6 @@ void defineMathSignalRootMeanSquare(py::module &m, const std::string &typestr); void defineMathSignalMean(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__SIGNALSTATS_HH_ +#endif // GZ_MATH_PYTHON__SIGNALSTATS_HH_ diff --git a/src/python_pybind11/src/Sphere.hh b/src/python_pybind11/src/Sphere.hh index a6294cf97..fcc8e4be6 100644 --- a/src/python_pybind11/src/Sphere.hh +++ b/src/python_pybind11/src/Sphere.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__SPHERE_HH_ -#define IGNITION_MATH_PYTHON__SPHERE_HH_ +#ifndef GZ_MATH_PYTHON__SPHERE_HH_ +#define GZ_MATH_PYTHON__SPHERE_HH_ #include #include @@ -29,13 +29,13 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Sphere +/// Define a pybind11 wrapper for an gz::math::Sphere /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -44,7 +44,7 @@ template void defineMathSphere(py::module &m, const std::string &typestr) { - using Class = ignition::math::Sphere; + using Class = gz::math::Sphere; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -52,7 +52,7 @@ void defineMathSphere(py::module &m, const std::string &typestr) py::dynamic_attr()) .def(py::init<>()) .def(py::init()) - .def(py::init()) + .def(py::init()) .def(py::self != py::self) .def(py::self == py::self) .def("radius", @@ -98,6 +98,6 @@ void defineMathSphere(py::module &m, const std::string &typestr) } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__SPHERE_HH_ +#endif // GZ_MATH_PYTHON__SPHERE_HH_ diff --git a/src/python_pybind11/src/SphericalCoordinates.cc b/src/python_pybind11/src/SphericalCoordinates.cc index 211e6b517..69e5046e5 100644 --- a/src/python_pybind11/src/SphericalCoordinates.cc +++ b/src/python_pybind11/src/SphericalCoordinates.cc @@ -20,7 +20,7 @@ #include #include -namespace ignition +namespace gz { namespace math { @@ -28,7 +28,7 @@ namespace python { void defineMathSphericalCoordinates(py::module &m, const std::string &typestr) { - using Class = ignition::math::SphericalCoordinates; + using Class = gz::math::SphericalCoordinates; std::string pyclass_name = typestr; py::class_ sphericalCoordinates(m, @@ -39,9 +39,9 @@ void defineMathSphericalCoordinates(py::module &m, const std::string &typestr) .def(py::init<>()) .def(py::init()) .def(py::init()) - .def(py::init()) + .def(py::init()) .def(py::self != py::self) .def(py::self == py::self) .def("spherical_from_local_position", @@ -129,4 +129,4 @@ void defineMathSphericalCoordinates(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/SphericalCoordinates.hh b/src/python_pybind11/src/SphericalCoordinates.hh index e7a2b83cd..34e0e0262 100644 --- a/src/python_pybind11/src/SphericalCoordinates.hh +++ b/src/python_pybind11/src/SphericalCoordinates.hh @@ -15,21 +15,21 @@ * */ -#ifndef IGNITION_MATH_PYTHON__SPHERICALCOORDINATES_HH_ -#define IGNITION_MATH_PYTHON__SPHERICALCOORDINATES_HH_ +#ifndef GZ_MATH_PYTHON__SPHERICALCOORDINATES_HH_ +#define GZ_MATH_PYTHON__SPHERICALCOORDINATES_HH_ #include #include namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::SphericalCoordinates +/// Define a pybind11 wrapper for an gz::math::SphericalCoordinates /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -37,6 +37,6 @@ namespace python void defineMathSphericalCoordinates(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__SPHERICALCOORDINATES_HH_ +#endif // GZ_MATH_PYTHON__SPHERICALCOORDINATES_HH_ diff --git a/src/python_pybind11/src/Spline.cc b/src/python_pybind11/src/Spline.cc index 0c7314208..246e1cdfa 100644 --- a/src/python_pybind11/src/Spline.cc +++ b/src/python_pybind11/src/Spline.cc @@ -18,7 +18,7 @@ #include "Spline.hh" #include -namespace ignition +namespace gz { namespace math { @@ -26,7 +26,7 @@ namespace python { void defineMathSpline(py::module &m, const std::string &typestr) { - using Class = ignition::math::Spline; + using Class = gz::math::Spline; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -131,4 +131,4 @@ void defineMathSpline(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/Spline.hh b/src/python_pybind11/src/Spline.hh index b0fbd17d8..6ee996424 100644 --- a/src/python_pybind11/src/Spline.hh +++ b/src/python_pybind11/src/Spline.hh @@ -15,21 +15,21 @@ * */ -#ifndef IGNITION_MATH_PYTHON__SPLINE_HH_ -#define IGNITION_MATH_PYTHON__SPLINE_HH_ +#ifndef GZ_MATH_PYTHON__SPLINE_HH_ +#define GZ_MATH_PYTHON__SPLINE_HH_ #include #include namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::RollingMean +/// Define a pybind11 wrapper for an gz::math::RollingMean /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -37,6 +37,6 @@ namespace python void defineMathSpline(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__SPLINE_HH_ +#endif // GZ_MATH_PYTHON__SPLINE_HH_ diff --git a/src/python_pybind11/src/StopWatch.cc b/src/python_pybind11/src/StopWatch.cc index 2587a66b2..de5efcdef 100644 --- a/src/python_pybind11/src/StopWatch.cc +++ b/src/python_pybind11/src/StopWatch.cc @@ -23,7 +23,7 @@ #include -namespace ignition +namespace gz { namespace math { @@ -31,7 +31,7 @@ namespace python { void defineMathStopwatch(py::module &m, const std::string &typestr) { - using Class = ignition::math::Stopwatch; + using Class = gz::math::Stopwatch; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -74,4 +74,4 @@ void defineMathStopwatch(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/StopWatch.hh b/src/python_pybind11/src/StopWatch.hh index 672ee00f1..c0628e97a 100644 --- a/src/python_pybind11/src/StopWatch.hh +++ b/src/python_pybind11/src/StopWatch.hh @@ -15,21 +15,21 @@ * */ -#ifndef IGNITION_MATH_PYTHON__STOPWATCH_HH_ -#define IGNITION_MATH_PYTHON__STOPWATCH_HH_ +#ifndef GZ_MATH_PYTHON__STOPWATCH_HH_ +#define GZ_MATH_PYTHON__STOPWATCH_HH_ #include #include namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Stopwatch +/// Define a pybind11 wrapper for an gz::math::Stopwatch /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -37,6 +37,6 @@ namespace python void defineMathStopwatch(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__STOPWATCH_HH_ +#endif // GZ_MATH_PYTHON__STOPWATCH_HH_ diff --git a/src/python_pybind11/src/Temperature.cc b/src/python_pybind11/src/Temperature.cc index 3affb0066..e27965e74 100644 --- a/src/python_pybind11/src/Temperature.cc +++ b/src/python_pybind11/src/Temperature.cc @@ -25,7 +25,7 @@ using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { @@ -33,7 +33,7 @@ namespace python { void defineMathTemperature(py::module &m, const std::string &typestr) { - using Class = ignition::math::Temperature; + using Class = gz::math::Temperature; std::string pyclass_name = typestr; auto toString = [](const Class &si) { std::stringstream stream; @@ -127,4 +127,4 @@ void defineMathTemperature(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/Temperature.hh b/src/python_pybind11/src/Temperature.hh index 9307a1f05..8bd1e1883 100644 --- a/src/python_pybind11/src/Temperature.hh +++ b/src/python_pybind11/src/Temperature.hh @@ -15,21 +15,21 @@ * */ -#ifndef IGNITION_MATH_PYTHON__TEMPERATURE_HH_ -#define IGNITION_MATH_PYTHON__TEMPERATURE_HH_ +#ifndef GZ_MATH_PYTHON__TEMPERATURE_HH_ +#define GZ_MATH_PYTHON__TEMPERATURE_HH_ #include #include namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Temperature +/// Define a pybind11 wrapper for an gz::math::Temperature /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -37,6 +37,6 @@ namespace python void defineMathTemperature(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__TEMPERATURE_HH_ +#endif // GZ_MATH_PYTHON__TEMPERATURE_HH_ diff --git a/src/python_pybind11/src/Triangle.cc b/src/python_pybind11/src/Triangle.cc index 12a843218..abca118e2 100644 --- a/src/python_pybind11/src/Triangle.cc +++ b/src/python_pybind11/src/Triangle.cc @@ -19,7 +19,7 @@ #include "Triangle.hh" -namespace ignition +namespace gz { namespace math { @@ -33,5 +33,5 @@ void defineMathTriangle(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz diff --git a/src/python_pybind11/src/Triangle.hh b/src/python_pybind11/src/Triangle.hh index 7502f13cf..c6a9e4112 100644 --- a/src/python_pybind11/src/Triangle.hh +++ b/src/python_pybind11/src/Triangle.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__TRIANGLE_HH_ -#define IGNITION_MATH_PYTHON__TRIANGLE_HH_ +#ifndef GZ_MATH_PYTHON__TRIANGLE_HH_ +#define GZ_MATH_PYTHON__TRIANGLE_HH_ #include @@ -28,20 +28,20 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Triangle +/// Define a pybind11 wrapper for an gz::math::Triangle /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python */ void defineMathTriangle(py::module &m, const std::string &typestr); -/// Help define a pybind11 wrapper for an ignition::math::Triangle +/// Help define a pybind11 wrapper for an gz::math::Triangle /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -49,7 +49,7 @@ void defineMathTriangle(py::module &m, const std::string &typestr); template void helpDefineMathTriangle(py::module &m, const std::string &typestr) { - using Class = ignition::math::Triangle; + using Class = gz::math::Triangle; py::class_(m, typestr.c_str(), py::buffer_protocol(), @@ -106,7 +106,7 @@ void helpDefineMathTriangle(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz -#endif // IGNITION_MATH_PYTHON__TRIANGLE_HH_ +#endif // GZ_MATH_PYTHON__TRIANGLE_HH_ diff --git a/src/python_pybind11/src/Triangle3.cc b/src/python_pybind11/src/Triangle3.cc index 52083b61a..5fb99a8a4 100644 --- a/src/python_pybind11/src/Triangle3.cc +++ b/src/python_pybind11/src/Triangle3.cc @@ -19,7 +19,7 @@ #include "Triangle3.hh" -namespace ignition +namespace gz { namespace math { @@ -33,5 +33,5 @@ void defineMathTriangle3(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz diff --git a/src/python_pybind11/src/Triangle3.hh b/src/python_pybind11/src/Triangle3.hh index 923c8c7e6..2310cdce0 100644 --- a/src/python_pybind11/src/Triangle3.hh +++ b/src/python_pybind11/src/Triangle3.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__TRIANGLE3_HH_ -#define IGNITION_MATH_PYTHON__TRIANGLE3_HH_ +#ifndef GZ_MATH_PYTHON__TRIANGLE3_HH_ +#define GZ_MATH_PYTHON__TRIANGLE3_HH_ #include @@ -28,20 +28,20 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Triangle3 +/// Define a pybind11 wrapper for an gz::math::Triangle3 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python */ void defineMathTriangle3(py::module &m, const std::string &typestr); -/// Help define a pybind11 wrapper for an ignition::math::Triangle3 +/// Help define a pybind11 wrapper for an gz::math::Triangle3 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -49,7 +49,7 @@ void defineMathTriangle3(py::module &m, const std::string &typestr); template void helpDefineMathTriangle3(py::module &m, const std::string &typestr) { - using Class = ignition::math::Triangle3; + using Class = gz::math::Triangle3; py::class_(m, typestr.c_str(), py::buffer_protocol(), @@ -107,7 +107,7 @@ void helpDefineMathTriangle3(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz -#endif // IGNITION_MATH_PYTHON__TRIANGLE3_HH_ +#endif // GZ_MATH_PYTHON__TRIANGLE3_HH_ diff --git a/src/python_pybind11/src/Vector2.cc b/src/python_pybind11/src/Vector2.cc index 09de45755..d97eaccca 100644 --- a/src/python_pybind11/src/Vector2.cc +++ b/src/python_pybind11/src/Vector2.cc @@ -19,7 +19,7 @@ #include "Vector2.hh" -namespace ignition +namespace gz { namespace math { @@ -33,5 +33,5 @@ void defineMathVector2(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz diff --git a/src/python_pybind11/src/Vector2.hh b/src/python_pybind11/src/Vector2.hh index 864586f7e..ddaeae0d0 100644 --- a/src/python_pybind11/src/Vector2.hh +++ b/src/python_pybind11/src/Vector2.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__VECTOR2_HH_ -#define IGNITION_MATH_PYTHON__VECTOR2_HH_ +#ifndef GZ_MATH_PYTHON__VECTOR2_HH_ +#define GZ_MATH_PYTHON__VECTOR2_HH_ #include #include @@ -29,20 +29,20 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Help define a pybind11 wrapper for an ignition::math::Vector2 +/// Help define a pybind11 wrapper for an gz::math::Vector2 /** * \param[in] module a pybind11 module to add the definition to */ template void helpDefineMathVector2(py::module &m, const std::string &typestr) { - using Class = ignition::math::Vector2; + using Class = gz::math::Vector2; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -140,13 +140,13 @@ void helpDefineMathVector2(py::module &m, const std::string &typestr) .def("__repr__", toString); } -/// Define a pybind11 wrapper for an ignition::math::Vector2 +/// Define a pybind11 wrapper for an gz::math::Vector2 /** * \param[in] module a pybind11 module to add the definition to */ void defineMathVector2(py::module &m, const std::string &typestr); } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz -#endif // IGNITION_MATH_PYTHON__VECTOR2_HH_ +#endif // GZ_MATH_PYTHON__VECTOR2_HH_ diff --git a/src/python_pybind11/src/Vector3.cc b/src/python_pybind11/src/Vector3.cc index a38f0e07a..4dddb91a2 100644 --- a/src/python_pybind11/src/Vector3.cc +++ b/src/python_pybind11/src/Vector3.cc @@ -19,7 +19,7 @@ #include "Vector3.hh" -namespace ignition +namespace gz { namespace math { @@ -33,5 +33,5 @@ void defineMathVector3(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz diff --git a/src/python_pybind11/src/Vector3.hh b/src/python_pybind11/src/Vector3.hh index 3e25e2584..e3d73a0c1 100644 --- a/src/python_pybind11/src/Vector3.hh +++ b/src/python_pybind11/src/Vector3.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__VECTOR3_HH_ -#define IGNITION_MATH_PYTHON__VECTOR3_HH_ +#ifndef GZ_MATH_PYTHON__VECTOR3_HH_ +#define GZ_MATH_PYTHON__VECTOR3_HH_ #include #include @@ -29,20 +29,20 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Help define a pybind11 wrapper for an ignition::math::Vector3 +/// Help define a pybind11 wrapper for an gz::math::Vector3 /** * \param[in] module a pybind11 module to add the definition to */ template void helpDefineMathVector3(py::module &m, const std::string &typestr) { - using Class = ignition::math::Vector3; + using Class = gz::math::Vector3; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -167,13 +167,13 @@ void helpDefineMathVector3(py::module &m, const std::string &typestr) .def("__repr__", toString); } -/// Define a pybind11 wrapper for an ignition::math::Vector2 +/// Define a pybind11 wrapper for an gz::math::Vector2 /** * \param[in] module a pybind11 module to add the definition to */ void defineMathVector3(py::module &m, const std::string &typestr); } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz -#endif // IGNITION_MATH_PYTHON__VECTOR3_HH_ +#endif // GZ_MATH_PYTHON__VECTOR3_HH_ diff --git a/src/python_pybind11/src/Vector3Stats.cc b/src/python_pybind11/src/Vector3Stats.cc index a92fe085a..d7979dd3a 100644 --- a/src/python_pybind11/src/Vector3Stats.cc +++ b/src/python_pybind11/src/Vector3Stats.cc @@ -23,7 +23,7 @@ using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { @@ -31,7 +31,7 @@ namespace python { void defineMathVector3Stats(py::module &m, const std::string &typestr) { - using Class = ignition::math::Vector3Stats; + using Class = gz::math::Vector3Stats; std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), @@ -75,4 +75,4 @@ void defineMathVector3Stats(py::module &m, const std::string &typestr) } } // namespace python } // namespace math -} // namespace ignition +} // namespace gz diff --git a/src/python_pybind11/src/Vector3Stats.hh b/src/python_pybind11/src/Vector3Stats.hh index bd1848ac3..cdb3ad6e8 100644 --- a/src/python_pybind11/src/Vector3Stats.hh +++ b/src/python_pybind11/src/Vector3Stats.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__VECTOR3STATS_HH_ -#define IGNITION_MATH_PYTHON__VECTOR3STATS_HH_ +#ifndef GZ_MATH_PYTHON__VECTOR3STATS_HH_ +#define GZ_MATH_PYTHON__VECTOR3STATS_HH_ #include @@ -24,13 +24,13 @@ namespace py = pybind11; -namespace ignition +namespace gz { namespace math { namespace python { -/// Define a pybind11 wrapper for an ignition::math::Vector3Stats +/// Define a pybind11 wrapper for an gz::math::Vector3Stats /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -38,6 +38,6 @@ namespace python void defineMathVector3Stats(py::module &m, const std::string &typestr); } // namespace python } // namespace math -} // namespace ignition +} // namespace gz -#endif // IGNITION_MATH_PYTHON__VECTOR3STATS_HH_ +#endif // GZ_MATH_PYTHON__VECTOR3STATS_HH_ diff --git a/src/python_pybind11/src/Vector4.cc b/src/python_pybind11/src/Vector4.cc index f50718756..5e960638b 100644 --- a/src/python_pybind11/src/Vector4.cc +++ b/src/python_pybind11/src/Vector4.cc @@ -19,7 +19,7 @@ #include "Vector4.hh" -namespace ignition +namespace gz { namespace math { @@ -33,5 +33,5 @@ void defineMathVector4(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz diff --git a/src/python_pybind11/src/Vector4.hh b/src/python_pybind11/src/Vector4.hh index 6f7bff8da..744bc4c96 100644 --- a/src/python_pybind11/src/Vector4.hh +++ b/src/python_pybind11/src/Vector4.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__VECTOR4_HH_ -#define IGNITION_MATH_PYTHON__VECTOR4_HH_ +#ifndef GZ_MATH_PYTHON__VECTOR4_HH_ +#define GZ_MATH_PYTHON__VECTOR4_HH_ #include #include @@ -29,20 +29,20 @@ namespace py = pybind11; using namespace pybind11::literals; -namespace ignition +namespace gz { namespace math { namespace python { -/// Help define a pybind11 wrapper for an ignition::math::Vector4 +/// Help define a pybind11 wrapper for an gz::math::Vector4 /** * \param[in] module a pybind11 module to add the definition to */ template void helpDefineMathVector4(py::module &m, const std::string &typestr) { - using Class = ignition::math::Vector4; + using Class = gz::math::Vector4; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -147,13 +147,13 @@ void helpDefineMathVector4(py::module &m, const std::string &typestr) .def("__repr__", toString); } -/// Define a pybind11 wrapper for an ignition::math::Vector4 +/// Define a pybind11 wrapper for an gz::math::Vector4 /** * \param[in] module a pybind11 module to add the definition to */ void defineMathVector4(py::module &m, const std::string &typestr); } // namespace python -} // namespace gazebo -} // namespace ignition +} // namespace math +} // namespace gz -#endif // IGNITION_MATH_PYTHON__VECTOR4_HH_ +#endif // GZ_MATH_PYTHON__VECTOR4_HH_ diff --git a/src/python_pybind11/src/_ignition_math_pybind11.cc b/src/python_pybind11/src/_ignition_math_pybind11.cc index 00497c61c..07f33188e 100644 --- a/src/python_pybind11/src/_ignition_math_pybind11.cc +++ b/src/python_pybind11/src/_ignition_math_pybind11.cc @@ -61,115 +61,115 @@ namespace py = pybind11; PYBIND11_MODULE(math, m) { - m.doc() = "Ignition Math Python Library."; + m.doc() = "Gazebo Math Python Library."; - ignition::math::python::defineMathAngle(m, "Angle"); + gz::math::python::defineMathAngle(m, "Angle"); - ignition::math::python::defineMathAxisAlignedBox(m, "AxisAlignedBox"); + gz::math::python::defineMathAxisAlignedBox(m, "AxisAlignedBox"); - ignition::math::python::defineMathCapsule(m, "Capsule"); + gz::math::python::defineMathCapsule(m, "Capsule"); - ignition::math::python::defineMathColor(m, "Color"); + gz::math::python::defineMathColor(m, "Color"); - ignition::math::python::defineMathDiffDriveOdometry( + gz::math::python::defineMathDiffDriveOdometry( m, "DiffDriveOdometry"); - ignition::math::python::defineMathEllipsoid( + gz::math::python::defineMathEllipsoid( m, "Ellipsoid"); - ignition::math::python::defineMathGaussMarkovProcess( + gz::math::python::defineMathGaussMarkovProcess( m, "GaussMarkovProcess"); - ignition::math::python::defineMathHelpers(m); + gz::math::python::defineMathHelpers(m); - ignition::math::python::defineMathKmeans(m, "Kmeans"); + gz::math::python::defineMathKmeans(m, "Kmeans"); - ignition::math::python::defineMathMaterial(m, "Material"); + gz::math::python::defineMathMaterial(m, "Material"); - ignition::math::python::defineMathMovingWindowFilter(m, "MovingWindowFilter"); + gz::math::python::defineMathMovingWindowFilter(m, "MovingWindowFilter"); - ignition::math::python::defineMathPID(m, "PID"); + gz::math::python::defineMathPID(m, "PID"); - ignition::math::python::defineMathRand(m, "Rand"); + gz::math::python::defineMathRand(m, "Rand"); - ignition::math::python::defineMathRollingMean(m, "RollingMean"); + gz::math::python::defineMathRollingMean(m, "RollingMean"); - ignition::math::python::defineMathSignalStats(m, "SignalStats"); - ignition::math::python::defineMathSignalStatistic(m, "SignalStatistic"); - ignition::math::python::defineMathSignalVariance(m, "SignalVariance"); - ignition::math::python::defineMathSignalMaximum(m, "SignalMaximum"); - ignition::math::python::defineMathSignalMinimum(m, "SignalMinimum"); - ignition::math::python::defineMathSignalMaxAbsoluteValue( + gz::math::python::defineMathSignalStats(m, "SignalStats"); + gz::math::python::defineMathSignalStatistic(m, "SignalStatistic"); + gz::math::python::defineMathSignalVariance(m, "SignalVariance"); + gz::math::python::defineMathSignalMaximum(m, "SignalMaximum"); + gz::math::python::defineMathSignalMinimum(m, "SignalMinimum"); + gz::math::python::defineMathSignalMaxAbsoluteValue( m, "SignalMaxAbsoluteValue"); - ignition::math::python::defineMathSignalRootMeanSquare( + gz::math::python::defineMathSignalRootMeanSquare( m, "SignalRootMeanSquare"); - ignition::math::python::defineMathSignalMean(m, "SignalMean"); + gz::math::python::defineMathSignalMean(m, "SignalMean"); - ignition::math::python::defineMathRotationSpline(m, "RotationSpline"); + gz::math::python::defineMathRotationSpline(m, "RotationSpline"); - ignition::math::python::defineMathVector3Stats(m, "Vector3Stats"); + gz::math::python::defineMathVector3Stats(m, "Vector3Stats"); - ignition::math::python::defineMathSemanticVersion(m, "SemanticVersion"); + gz::math::python::defineMathSemanticVersion(m, "SemanticVersion"); - ignition::math::python::defineMathSphericalCoordinates( + gz::math::python::defineMathSphericalCoordinates( m, "SphericalCoordinates"); - ignition::math::python::defineMathSpline(m, "Spline"); + gz::math::python::defineMathSpline(m, "Spline"); - ignition::math::python::defineMathStopwatch(m, "Stopwatch"); + gz::math::python::defineMathStopwatch(m, "Stopwatch"); - ignition::math::python::defineMathTemperature(m, "Temperature"); + gz::math::python::defineMathTemperature(m, "Temperature"); - ignition::math::python::defineMathVector2(m, "Vector2"); + gz::math::python::defineMathVector2(m, "Vector2"); - ignition::math::python::defineMathVector3(m, "Vector3"); + gz::math::python::defineMathVector3(m, "Vector3"); - ignition::math::python::defineMathPlane(m, "Planed"); + gz::math::python::defineMathPlane(m, "Planed"); - ignition::math::python::defineMathBox(m, "Boxd"); - ignition::math::python::defineMathBox(m, "Boxf"); + gz::math::python::defineMathBox(m, "Boxd"); + gz::math::python::defineMathBox(m, "Boxf"); - ignition::math::python::defineMathVector4(m, "Vector4"); + gz::math::python::defineMathVector4(m, "Vector4"); - ignition::math::python::defineMathLine2(m, "Line2"); + gz::math::python::defineMathLine2(m, "Line2"); - ignition::math::python::defineMathLine3(m, "Line3"); + gz::math::python::defineMathLine3(m, "Line3"); - ignition::math::python::defineMathMatrix3(m, "Matrix3"); + gz::math::python::defineMathMatrix3(m, "Matrix3"); - ignition::math::python::defineMathMatrix4(m, "Matrix4"); + gz::math::python::defineMathMatrix4(m, "Matrix4"); - ignition::math::python::defineMathTriangle(m, "Triangle"); + gz::math::python::defineMathTriangle(m, "Triangle"); - ignition::math::python::defineMathTriangle3(m, "Triangle3"); + gz::math::python::defineMathTriangle3(m, "Triangle3"); - ignition::math::python::defineMathQuaternion(m, "Quaternion"); + gz::math::python::defineMathQuaternion(m, "Quaternion"); - ignition::math::python::defineMathOrientedBox(m, "OrientedBoxd"); + gz::math::python::defineMathOrientedBox(m, "OrientedBoxd"); - ignition::math::python::defineMathPose3(m, "Pose3"); + gz::math::python::defineMathPose3(m, "Pose3"); - ignition::math::python::defineMathMassMatrix3(m, "MassMatrix3"); + gz::math::python::defineMathMassMatrix3(m, "MassMatrix3"); - ignition::math::python::defineMathSphere(m, "Sphered"); + gz::math::python::defineMathSphere(m, "Sphered"); - ignition::math::python::defineMathCylinder(m, "Cylinderd"); + gz::math::python::defineMathCylinder(m, "Cylinderd"); - ignition::math::python::defineMathInertial(m, "Inertiald"); + gz::math::python::defineMathInertial(m, "Inertiald"); - ignition::math::python::defineMathFrustum(m, "Frustum"); + gz::math::python::defineMathFrustum(m, "Frustum"); - ignition::math::python::defineMathFilter(m, "Filter"); + gz::math::python::defineMathFilter(m, "Filter"); - ignition::math::python::defineMathBiQuad(m, "BiQuad"); + gz::math::python::defineMathBiQuad(m, "BiQuad"); - ignition::math::python::defineMathBiQuadVector3( + gz::math::python::defineMathBiQuadVector3( m, "BiQuadVector3"); - ignition::math::python::defineMathOnePole(m, "OnePole"); + gz::math::python::defineMathOnePole(m, "OnePole"); - ignition::math::python::defineMathOnePoleQuaternion( + gz::math::python::defineMathOnePoleQuaternion( m, "OnePoleQuaternion"); - ignition::math::python::defineMathOnePoleVector3( + gz::math::python::defineMathOnePoleVector3( m, "OnePoleVector3"); } diff --git a/src/python_pybind11/test/Vector3_TEST.py b/src/python_pybind11/test/Vector3_TEST.py index 4b0e1a6ee..ea2b9fdb6 100644 --- a/src/python_pybind11/test/Vector3_TEST.py +++ b/src/python_pybind11/test/Vector3_TEST.py @@ -142,7 +142,7 @@ def test_length(self): self.assertEqual(Vector3d.ZERO.length(), 0.0) self.assertEqual(Vector3d.ZERO.squared_length(), 0.0) - # UnitXYZ vectorsIgnition:: + # UnitXYZ vectorsGz:: self.assertEqual(Vector3d.UNIT_X.length(), 1.0) self.assertEqual(Vector3d.UNIT_Y.length(), 1.0) self.assertEqual(Vector3d.UNIT_Z.length(), 1.0) diff --git a/src/ruby/Angle.i b/src/ruby/Angle.i index 47f72905e..5f832e113 100644 --- a/src/ruby/Angle.i +++ b/src/ruby/Angle.i @@ -20,7 +20,7 @@ #include %} -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/Angle_TEST.rb b/src/ruby/Angle_TEST.rb index 0c227288c..ea047277d 100644 --- a/src/ruby/Angle_TEST.rb +++ b/src/ruby/Angle_TEST.rb @@ -20,77 +20,77 @@ class Angle_TEST < Test::Unit::TestCase def test_construction - angle1 = Ignition::Math::Angle.new + angle1 = Gz::Math::Angle.new assert(angle1.Radian() == 0.0, "Angle::Radian() should equal zero") angle1.SetDegree(180.0) - assert(angle1 == Ignition::Math::Angle.Pi, + assert(angle1 == Gz::Math::Angle.Pi, "180.0 degrees should equal PI") - assert(angle1 != Ignition::Math::Angle.Pi + Ignition::Math::Angle.new(0.1), + assert(angle1 != Gz::Math::Angle.Pi + Gz::Math::Angle.new(0.1), "180.0 degrees should not equal PI + 0.1") - assert(angle1 == Ignition::Math::Angle.Pi + - Ignition::Math::Angle.new(0.0001), + assert(angle1 == Gz::Math::Angle.Pi + + Gz::Math::Angle.new(0.0001), "180.0 degrees should equal PI + 0.0001") - assert(angle1 == Ignition::Math::Angle.Pi - - Ignition::Math::Angle.new(0.0001), + assert(angle1 == Gz::Math::Angle.Pi - + Gz::Math::Angle.new(0.0001), "180.0 degrees should equal PI - 0.0001") - assert(Ignition::Math::Angle.new(0) == Ignition::Math::Angle.new(0), + assert(Gz::Math::Angle.new(0) == Gz::Math::Angle.new(0), "Zero angle should equal zero angle") - assert(Ignition::Math::Angle.new(0) == Ignition::Math::Angle.new(0.001), + assert(Gz::Math::Angle.new(0) == Gz::Math::Angle.new(0.001), "Zero should equal 0.001") - angle1 = Ignition::Math::Angle.new(0.1) - Ignition::Math::Angle.new(0.3) - assert(angle1 == Ignition::Math::Angle.new(-0.2), + angle1 = Gz::Math::Angle.new(0.1) - Gz::Math::Angle.new(0.3) + assert(angle1 == Gz::Math::Angle.new(-0.2), "Angle1 should equal -0.2") - angle = Ignition::Math::Angle.new(0.5) + angle = Gz::Math::Angle.new(0.5) assert(0.5 == angle.Radian, "Angle should equal 0.5") angle.SetRadian(Math::PI) - assert(Ignition::Math::Angle.Pi.Degree == angle.Degree, + assert(Gz::Math::Angle.Pi.Degree == angle.Degree, "Pi in degrees should equal Angle.SetRadian(Pi).Degree") angleNorm = angle.Normalized() angle.Normalize() - assert(Ignition::Math::Angle.new(Math::PI).Degree == angle.Degree, + assert(Gz::Math::Angle.new(Math::PI).Degree == angle.Degree, "Normalized angle should equal PI") assert(angleNorm == angle, "Normalized angles should be equal") - angle = Ignition::Math::Angle.new(0.1) + Ignition::Math::Angle.new(0.2) + angle = Gz::Math::Angle.new(0.1) + Gz::Math::Angle.new(0.2) assert((angle.Radian - 0.3).abs < 1e-6, "Angle should equal 0.3") - angle = Ignition::Math::Angle.new(0.1) * Ignition::Math::Angle.new(0.2) + angle = Gz::Math::Angle.new(0.1) * Gz::Math::Angle.new(0.2) assert((angle.Radian - 0.02).abs < 1e-6, "Angle should equal 0.02") - angle = Ignition::Math::Angle.new(0.1) / Ignition::Math::Angle.new(0.2) + angle = Gz::Math::Angle.new(0.1) / Gz::Math::Angle.new(0.2) assert((angle.Radian - 0.5).abs < 1e-6, "Angle should equal 0.5") - angle -= Ignition::Math::Angle.new(0.1) + angle -= Gz::Math::Angle.new(0.1) assert((angle.Radian - 0.4).abs < 1e-6, "Angle should equal 0.1") - angle += Ignition::Math::Angle.new(0.2) + angle += Gz::Math::Angle.new(0.2) assert((angle.Radian - 0.6).abs < 1e-6, "Angle should equal 0.6") - angle *= Ignition::Math::Angle.new(0.5) + angle *= Gz::Math::Angle.new(0.5) assert((angle.Radian - 0.3).abs < 1e-6, "Angle should equal 0.5") - angle /= Ignition::Math::Angle.new(0.1) + angle /= Gz::Math::Angle.new(0.1) assert((angle.Radian() - 3.0).abs < 1e-6, "Angle should equal 3.0") - assert(angle == Ignition::Math::Angle.new(3), "Angle should equal Angle(3)") - assert(angle != Ignition::Math::Angle.new(2), + assert(angle == Gz::Math::Angle.new(3), "Angle should equal Angle(3)") + assert(angle != Gz::Math::Angle.new(2), "Angle should not equal Angle(2)") - assert(angle < Ignition::Math::Angle.new(4), "Angle should be < Angle(4)") - assert(angle > Ignition::Math::Angle.new(2), "Angle should be > Angle(2)") - assert(angle >= Ignition::Math::Angle.new(3), "Angle should be >= Angle(3)") - assert(angle <= Ignition::Math::Angle.new(3), "Angle should be <= 3") + assert(angle < Gz::Math::Angle.new(4), "Angle should be < Angle(4)") + assert(angle > Gz::Math::Angle.new(2), "Angle should be > Angle(2)") + assert(angle >= Gz::Math::Angle.new(3), "Angle should be >= Angle(3)") + assert(angle <= Gz::Math::Angle.new(3), "Angle should be <= 3") angle = 1.2 assert(angle <= 1.21, "Angle should be less than or equal to 1.21") @@ -98,11 +98,11 @@ def test_construction assert(angle <= 1.2, "Angle should be less than or equal to 1.2") assert(!(angle <= -1.19), "Angle should not be less than or equal to -1.19") - assert(Ignition::Math::Angle.new(1.2) <= - Ignition::Math::Angle.new(1.2000000001), + assert(Gz::Math::Angle.new(1.2) <= + Gz::Math::Angle.new(1.2000000001), "1.2 should be less than or equal to 1.2000000001") - assert(Ignition::Math::Angle.new(1.2000000001) <= - Ignition::Math::Angle.new(1.2), + assert(Gz::Math::Angle.new(1.2000000001) <= + Gz::Math::Angle.new(1.2), "1.2000000001 should be less than or equal to 1.2") angle = 1.2 @@ -111,11 +111,11 @@ def test_construction assert(angle >= 1.2, "Angle should be greater or equal to 1.2") assert(angle >= -1.19, "Angle should be greater or equal to -1.19") - assert(Ignition::Math::Angle.new(1.2) >= - Ignition::Math::Angle.new(1.2000000001), + assert(Gz::Math::Angle.new(1.2) >= + Gz::Math::Angle.new(1.2000000001), "1.2 should be greater than or equal to 1.2000000001") - assert(Ignition::Math::Angle.new(1.2000000001) >= - Ignition::Math::Angle.new(1.2), + assert(Gz::Math::Angle.new(1.2000000001) >= + Gz::Math::Angle.new(1.2), "1.2000000001 should be greater than or equal to 1.2") end end diff --git a/src/ruby/AxisAlignedBox.i b/src/ruby/AxisAlignedBox.i index 9c2c50874..c9fa0e6f9 100644 --- a/src/ruby/AxisAlignedBox.i +++ b/src/ruby/AxisAlignedBox.i @@ -34,19 +34,19 @@ PyTuple_SET_ITEM($result, 1, PyFloat_FromDouble(std::get<1>($1))); } -%typemap(out) (std::tuple >) { +%typemap(out) (std::tuple >) { $result = PyTuple_New(3); - std::tuple > tuplecpp($1); + std::tuple > tuplecpp($1); PyTuple_SET_ITEM($result, 0, PyBool_FromLong(std::get<0>(tuplecpp))); PyTuple_SET_ITEM($result, 1, PyFloat_FromDouble(std::get<1>(tuplecpp))); - ignition::math::Vector3 vector3 = std::get<2>(tuplecpp); - PyObject *pyobject = SWIG_NewPointerObj((new ignition::math::Vector3< double >(static_cast< const ignition::math::Vector3< double >& >(vector3))), SWIGTYPE_p_ignition__math__Vector3T_double_t, SWIG_POINTER_OWN | 0 ); + gz::math::Vector3 vector3 = std::get<2>(tuplecpp); + PyObject *pyobject = SWIG_NewPointerObj((new gz::math::Vector3< double >(static_cast< const gz::math::Vector3< double >& >(vector3))), SWIGTYPE_p_ignition__math__Vector3T_double_t, SWIG_POINTER_OWN | 0 ); PyTuple_SET_ITEM(resultobj, 2, pyobject); } -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/Box.i b/src/ruby/Box.i index 2d801601b..f9854ed21 100644 --- a/src/ruby/Box.i +++ b/src/ruby/Box.i @@ -31,10 +31,10 @@ %} %include "typemaps.i" -%typemap(out) (std::optional< ignition::math::Vector3< double > >) %{ +%typemap(out) (std::optional< gz::math::Vector3< double > >) %{ if((*(&result)).has_value()) { $result = SWIG_NewPointerObj( - (new ignition::math::Vector3< double >(static_cast< const ignition::math::Vector3< double >& >((*(&result)).value()))), + (new gz::math::Vector3< double >(static_cast< const gz::math::Vector3< double >& >((*(&result)).value()))), SWIGTYPE_p_ignition__math__Vector3T_double_t, SWIG_POINTER_OWN | 0 ); } else { @@ -43,10 +43,10 @@ } %} -%typemap(out) (std::optional< ignition::math::Vector3< int > >) %{ +%typemap(out) (std::optional< gz::math::Vector3< int > >) %{ if((*(&result)).has_value()) { $result = SWIG_NewPointerObj( - (new ignition::math::Vector3< int >(static_cast< const ignition::math::Vector3< int >& >((*(&result)).value()))), + (new gz::math::Vector3< int >(static_cast< const gz::math::Vector3< int >& >((*(&result)).value()))), SWIGTYPE_p_ignition__math__Vector3T_int_t, SWIG_POINTER_OWN | 0 ); } else { @@ -56,10 +56,10 @@ %} #include "std_set.i" -%template(SetBoxDouble) std::set, ignition::math::WellOrderedVectors>; -%template(SetBoxInt) std::set, ignition::math::WellOrderedVectors>; +%template(SetBoxDouble) std::set, gz::math::WellOrderedVectors>; +%template(SetBoxInt) std::set, gz::math::WellOrderedVectors>; -namespace ignition +namespace gz { namespace math { @@ -76,18 +76,18 @@ namespace ignition public: Box(const Precision _length, const Precision _width, const Precision _height, - const ignition::math::Material &_mat); + const gz::math::Material &_mat); - public: explicit Box(const ignition::math::Vector3 &_size); + public: explicit Box(const gz::math::Vector3 &_size); - public: Box(const ignition::math::Vector3 &_size, - const ignition::math::Material &_mat); + public: Box(const gz::math::Vector3 &_size, + const gz::math::Material &_mat); public: virtual ~Box() = default; - public: ignition::math::Vector3 Size() const; + public: gz::math::Vector3 Size() const; - public: void SetSize(const ignition::math::Vector3 &_size); + public: void SetSize(const gz::math::Vector3 &_size); public: void SetSize(const Precision _length, const Precision _width, @@ -97,32 +97,32 @@ namespace ignition public: bool operator!=(const Box &_b) const; - public: const ignition::math::Material &Material() const; + public: const gz::math::Material &Material() const; - public: void SetMaterial(const ignition::math::Material &_mat); + public: void SetMaterial(const gz::math::Material &_mat); public: Precision Volume() const; - public: Precision VolumeBelow(const ignition::math::Plane &_plane) const; + public: Precision VolumeBelow(const gz::math::Plane &_plane) const; - public: std::optional> - CenterOfVolumeBelow(const ignition::math::Plane &_plane) const; + public: std::optional> + CenterOfVolumeBelow(const gz::math::Plane &_plane) const; - public: std::set, ignition::math::WellOrderedVectors> - VerticesBelow(const ignition::math::Plane &_plane) const; + public: std::set, gz::math::WellOrderedVectors> + VerticesBelow(const gz::math::Plane &_plane) const; public: Precision DensityFromMass(const Precision _mass) const; public: bool SetDensityFromMass(const Precision _mass); - public: bool MassMatrix(ignition::math::MassMatrix3 &_massMat) const; + public: bool MassMatrix(gz::math::MassMatrix3 &_massMat) const; - public: std::set, ignition::math::WellOrderedVectors> Intersections( - const ignition::math::Plane &_plane) const; + public: std::set, gz::math::WellOrderedVectors> Intersections( + const gz::math::Plane &_plane) const; - private: ignition::math::Vector3 size = ignition::math::Vector3::Zero; + private: gz::math::Vector3 size = gz::math::Vector3::Zero; - private: ignition::math::Material material; + private: gz::math::Material material; }; %template(Boxi) Box; diff --git a/src/ruby/CMakeLists.txt b/src/ruby/CMakeLists.txt index 568e1f41e..ddf609768 100644 --- a/src/ruby/CMakeLists.txt +++ b/src/ruby/CMakeLists.txt @@ -26,7 +26,7 @@ endif() # Create and install Ruby interfaces # Example usage # $ export RUBYLIB=/usr/local/lib/ruby -# $ ruby -e "require 'ignition/math'; a = Ignition::Math::Angle.new(20); puts a.Degree()" +# $ ruby -e "require 'ignition/math'; a = Gz::Math::Angle.new(20); puts a.Degree()" if (RUBY_FOUND) foreach (swig_file ${swig_files}) # Assuming that each swig file has a test diff --git a/src/ruby/Color.i b/src/ruby/Color.i index cb8b254f8..482c5ed2b 100644 --- a/src/ruby/Color.i +++ b/src/ruby/Color.i @@ -26,7 +26,7 @@ %include "std_string.i" -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/Cylinder.i b/src/ruby/Cylinder.i index 3799d932f..ac1be6bf1 100644 --- a/src/ruby/Cylinder.i +++ b/src/ruby/Cylinder.i @@ -24,7 +24,7 @@ #include %} -namespace ignition +namespace gz { namespace math { @@ -36,13 +36,13 @@ namespace ignition public: Cylinder() = default; public: Cylinder(const Precision _length, const Precision _radius, - const ignition::math::Quaternion &_rotOffset = - ignition::math::Quaternion::Identity); + const gz::math::Quaternion &_rotOffset = + gz::math::Quaternion::Identity); public: Cylinder(const Precision _length, const Precision _radius, - const ignition::math::Material &_mat, - const ignition::math::Quaternion &_rotOffset = - ignition::math::Quaternion::Identity); + const gz::math::Material &_mat, + const gz::math::Quaternion &_rotOffset = + gz::math::Quaternion::Identity); public: ~Cylinder() = default; @@ -54,16 +54,16 @@ namespace ignition public: void SetLength(const Precision _length); - public: ignition::math::Quaternion RotationalOffset() const; + public: gz::math::Quaternion RotationalOffset() const; public: void SetRotationalOffset( - const ignition::math::Quaternion &_rotOffset); + const gz::math::Quaternion &_rotOffset); - public: const ignition::math::Material &Mat() const; + public: const gz::math::Material &Mat() const; - public: void SetMat(const ignition::math::Material &_mat); + public: void SetMat(const gz::math::Material &_mat); - public: bool MassMatrix(ignition::math::MassMatrix3 &_massMat) const; + public: bool MassMatrix(gz::math::MassMatrix3 &_massMat) const; public: bool operator==(const Cylinder &_cylinder) const; diff --git a/src/ruby/DiffDriveOdometry.i b/src/ruby/DiffDriveOdometry.i index efb7d5901..62c326341 100644 --- a/src/ruby/DiffDriveOdometry.i +++ b/src/ruby/DiffDriveOdometry.i @@ -36,7 +36,7 @@ $1 = new std::chrono::steady_clock::time_point(); *$1 += duration_cast(std::chrono::milliseconds(PyInt_AsLong($input))); %} -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/Filter.i b/src/ruby/Filter.i index dfcef607e..ef7ef0073 100644 --- a/src/ruby/Filter.i +++ b/src/ruby/Filter.i @@ -26,7 +26,7 @@ %import Quaternion.i -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/Frustum.i b/src/ruby/Frustum.i index 76de59152..82b123e27 100644 --- a/src/ruby/Frustum.i +++ b/src/ruby/Frustum.i @@ -25,7 +25,7 @@ #include %} -namespace ignition +namespace gz { namespace math { @@ -57,9 +57,9 @@ namespace ignition public: Frustum(double _near, double _far, - const ignition::math::Angle &_fov, + const gz::math::Angle &_fov, double _aspectRatio, - const ignition::math::Pose3 &_pose = ignition::math::Pose3::Zero); + const gz::math::Pose3 &_pose = gz::math::Pose3::Zero); public: Frustum(const Frustum &_p); @@ -71,23 +71,23 @@ namespace ignition public: void SetFar(double _far); - public: ignition::math::Angle FOV() const; + public: gz::math::Angle FOV() const; - public: void SetFOV(const ignition::math::Angle &_fov); + public: void SetFOV(const gz::math::Angle &_fov); public: double AspectRatio() const; public: void SetAspectRatio(double _aspectRatio); - public: ignition::math::Plane Plane(const FrustumPlane _plane) const; + public: gz::math::Plane Plane(const FrustumPlane _plane) const; - public: bool Contains(const ignition::math::AxisAlignedBox &_b) const; + public: bool Contains(const gz::math::AxisAlignedBox &_b) const; - public: bool Contains(const ignition::math::Vector3 &_p) const; + public: bool Contains(const gz::math::Vector3 &_p) const; - public: ignition::math::Pose3 Pose() const; + public: gz::math::Pose3 Pose() const; - public: void SetPose(const ignition::math::Pose3 &_pose); + public: void SetPose(const gz::math::Pose3 &_pose); }; } } diff --git a/src/ruby/GaussMarkovProcess.i b/src/ruby/GaussMarkovProcess.i index 412840e3e..ba5b39171 100644 --- a/src/ruby/GaussMarkovProcess.i +++ b/src/ruby/GaussMarkovProcess.i @@ -20,7 +20,7 @@ #include %} -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/GaussMarkovProcess_TEST.rb b/src/ruby/GaussMarkovProcess_TEST.rb index 4e26bdf53..2b8d79e72 100644 --- a/src/ruby/GaussMarkovProcess_TEST.rb +++ b/src/ruby/GaussMarkovProcess_TEST.rb @@ -20,7 +20,7 @@ class GaussMarkovProcess_TEST < Test::Unit::TestCase def test_construction - gmp = Ignition::Math::GaussMarkovProcess.new + gmp = Gz::Math::GaussMarkovProcess.new assert(gmp.Start() == 0.0, "Start value should equal zero") assert(gmp.Value() == 0.0, "Initial value should equal zero") @@ -30,7 +30,7 @@ def test_construction end def test_no_noise - gmp = Ignition::Math::GaussMarkovProcess.new(-1.2, 1.0, 2.5, 0) + gmp = Gz::Math::GaussMarkovProcess.new(-1.2, 1.0, 2.5, 0) assert(gmp.Start() == -1.2, "Start value should equal zero") assert(gmp.Value() == -1.2, "Initial value should equal zero") assert(gmp.Theta() == 1.0, "Theta should equal zero") @@ -47,13 +47,13 @@ def test_no_noise end def test_noise - gmp = Ignition::Math::GaussMarkovProcess.new(20.2, 0.1, 0, 0.5) + gmp = Gz::Math::GaussMarkovProcess.new(20.2, 0.1, 0, 0.5) assert(gmp.Start() == 20.2, "Start value should equal zero") assert(gmp.Value() == 20.2, "Initial value should equal zero") assert(gmp.Theta() == 0.1, "Theta should equal zero") assert(gmp.Mu() == 0, "Mu should equal zero") assert(gmp.Sigma() == 0.5, "Sigma should equal zero") - Ignition::Math::Rand::Seed(1001); + Gz::Math::Rand::Seed(1001); for i in 0..1000 do value = gmp.Update(0.1); diff --git a/src/ruby/Helpers.i b/src/ruby/Helpers.i index 97f8d88f0..7aabfbb17 100644 --- a/src/ruby/Helpers.i +++ b/src/ruby/Helpers.i @@ -82,7 +82,7 @@ def sort3(_a, _b, _c): // Because then you'll get // error : Template 'myfunction' undefined. // Workaround it's to split the template functions and the normal ones -namespace ignition +namespace gz { /// \brief Math classes and function useful in robot applications. namespace math @@ -155,7 +155,7 @@ namespace ignition } } -namespace ignition +namespace gz { /// \brief Math classes and function useful in robot applications. namespace math diff --git a/src/ruby/Inertial.i b/src/ruby/Inertial.i index 630408d36..a514ac4c4 100644 --- a/src/ruby/Inertial.i +++ b/src/ruby/Inertial.i @@ -23,7 +23,7 @@ #include "gz/math/Pose3.hh" %} -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/Kmeans.i b/src/ruby/Kmeans.i index 5c7fd2ca8..d1af33492 100644 --- a/src/ruby/Kmeans.i +++ b/src/ruby/Kmeans.i @@ -23,18 +23,18 @@ %} %include "std_vector.i" -%template(vector_vector3d) std::vector>; +%template(vector_vector3d) std::vector>; %template(vector_uint) std::vector; %inline %{ struct ClusterOutput { bool result; - std::vector> centroids; + std::vector> centroids; std::vector labels; }; %} -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/Line2.i b/src/ruby/Line2.i index 8ac12703a..45baccb97 100644 --- a/src/ruby/Line2.i +++ b/src/ruby/Line2.i @@ -25,7 +25,7 @@ %include "std_string.i" -namespace ignition +namespace gz { namespace math { @@ -62,7 +62,7 @@ namespace ignition %extend Line2 { - ignition::math::Vector2 __getitem__(unsigned int i) const + gz::math::Vector2 __getitem__(unsigned int i) const { return (*$self)[i]; } diff --git a/src/ruby/Line3.i b/src/ruby/Line3.i index 0a5b8b6c3..4ab93a137 100644 --- a/src/ruby/Line3.i +++ b/src/ruby/Line3.i @@ -25,7 +25,7 @@ %include "std_string.i" -namespace ignition +namespace gz { namespace math { @@ -71,7 +71,7 @@ namespace ignition %extend Line3 { - ignition::math::Vector3 __getitem__(const unsigned int i) const + gz::math::Vector3 __getitem__(const unsigned int i) const { return (*$self)[i]; } diff --git a/src/ruby/MassMatrix3.i b/src/ruby/MassMatrix3.i index 1727e525d..32c02a8cd 100644 --- a/src/ruby/MassMatrix3.i +++ b/src/ruby/MassMatrix3.i @@ -27,7 +27,7 @@ #include "gz/math/Matrix3.hh" %} -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/Material.i b/src/ruby/Material.i index 80f08fcdf..0aa1edbef 100644 --- a/src/ruby/Material.i +++ b/src/ruby/Material.i @@ -27,9 +27,9 @@ %include "std_map.i" %template(map_material_type) std::map; + gz::math::Material>; -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/MaterialType.i b/src/ruby/MaterialType.i index f7a10ccac..d1eb8730d 100644 --- a/src/ruby/MaterialType.i +++ b/src/ruby/MaterialType.i @@ -22,7 +22,7 @@ #include %} -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/Matrix3.i b/src/ruby/Matrix3.i index e7a98abe4..c4a76d588 100644 --- a/src/ruby/Matrix3.i +++ b/src/ruby/Matrix3.i @@ -27,7 +27,7 @@ %include "std_string.i" %include Quaternion.i -namespace ignition +namespace gz { namespace math { @@ -85,8 +85,8 @@ namespace ignition } %extend Matrix3 { - ignition::math::Quaternion to_quaternion() { - return ignition::math::Quaternion(*$self); + gz::math::Quaternion to_quaternion() { + return gz::math::Quaternion(*$self); } } diff --git a/src/ruby/Matrix4.i b/src/ruby/Matrix4.i index 3a6238ef6..f47c98c1b 100644 --- a/src/ruby/Matrix4.i +++ b/src/ruby/Matrix4.i @@ -27,7 +27,7 @@ %include "std_string.i" -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/MovingWindowFilter.i b/src/ruby/MovingWindowFilter.i index bd9f26428..dc45f39ab 100644 --- a/src/ruby/MovingWindowFilter.i +++ b/src/ruby/MovingWindowFilter.i @@ -20,7 +20,7 @@ #include "gz/math/Vector3.hh" %} -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/OrientedBox.i b/src/ruby/OrientedBox.i index 6c6ee9587..fe2815d82 100644 --- a/src/ruby/OrientedBox.i +++ b/src/ruby/OrientedBox.i @@ -28,28 +28,28 @@ #include %} -namespace ignition +namespace gz { namespace math { template - class ignition::math::OrientedBox + class gz::math::OrientedBox { %rename("%(undercase)s", %$isfunction, %$ismember, %$not %$isconstructor) ""; public: OrientedBox(); public: OrientedBox( - const ignition::math::Vector3 &_size, const ignition::math::Pose3 &_pose); + const gz::math::Vector3 &_size, const gz::math::Pose3 &_pose); - public: OrientedBox(const ignition::math::Vector3 &_size, const ignition::math::Pose3 &_pose, - const ignition::math::Material &_mat); + public: OrientedBox(const gz::math::Vector3 &_size, const gz::math::Pose3 &_pose, + const gz::math::Material &_mat); - public: explicit OrientedBox(const ignition::math::Vector3 &_size); + public: explicit OrientedBox(const gz::math::Vector3 &_size); - public: explicit OrientedBox(const ignition::math::Vector3 &_size, - const ignition::math::Material &_mat); + public: explicit OrientedBox(const gz::math::Vector3 &_size, + const gz::math::Material &_mat); - public: OrientedBox(const ignition::math::OrientedBox &_b); + public: OrientedBox(const gz::math::OrientedBox &_b); public: virtual ~OrientedBox(); @@ -62,23 +62,23 @@ namespace ignition %rename(z_length) ZLength; public: T ZLength() const; - public: const ignition::math::Vector3 &Size() const; + public: const gz::math::Vector3 &Size() const; - public: const ignition::math::Pose3 &Pose() const; + public: const gz::math::Pose3 &Pose() const; - public: void Size(ignition::math::Vector3 &_size); + public: void Size(gz::math::Vector3 &_size); - public: void Pose(ignition::math::Pose3 &_pose); + public: void Pose(gz::math::Pose3 &_pose); - public: bool operator==(const ignition::math::OrientedBox &_b) const; + public: bool operator==(const gz::math::OrientedBox &_b) const; - public: bool operator!=(const ignition::math::OrientedBox &_b) const; + public: bool operator!=(const gz::math::OrientedBox &_b) const; - public: bool Contains(const ignition::math::Vector3 &_p) const; + public: bool Contains(const gz::math::Vector3 &_p) const; - public: const ignition::math::ignition::math::Material &ignition::math::Material() const; + public: const gz::math::gz::math::Material &gz::math::Material() const; - public: void ignition::math::SetMaterial(const ignition::math::ignition::math::Material &_mat); + public: void gz::math::SetMaterial(const gz::math::gz::math::Material &_mat); public: T Volume() const; diff --git a/src/ruby/PID.i b/src/ruby/PID.i index 7861cfcc2..300804a9b 100644 --- a/src/ruby/PID.i +++ b/src/ruby/PID.i @@ -22,7 +22,7 @@ %include "typemaps.i" %apply double *OUTPUT { double &_pe, double &_ie, double &_de }; -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/Plane.i b/src/ruby/Plane.i index 892e3fe91..ceb646975 100644 --- a/src/ruby/Plane.i +++ b/src/ruby/Plane.i @@ -28,10 +28,10 @@ %} %include "typemaps.i" -%typemap(out) (std::optional< ignition::math::Vector3< double > >) %{ +%typemap(out) (std::optional< gz::math::Vector3< double > >) %{ if((*(&result)).has_value()) { $result = SWIG_NewPointerObj( - (new ignition::math::Vector3< double >(static_cast< const ignition::math::Vector3< double >& >((*(&result)).value()))), + (new gz::math::Vector3< double >(static_cast< const gz::math::Vector3< double >& >((*(&result)).value()))), SWIGTYPE_p_ignition__math__Vector3T_double_t, SWIG_POINTER_OWN | 0 ); } else { @@ -41,7 +41,7 @@ %} -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/Pose3.i b/src/ruby/Pose3.i index 8d3407b01..ab32b621c 100644 --- a/src/ruby/Pose3.i +++ b/src/ruby/Pose3.i @@ -27,7 +27,7 @@ %include "Quaternion.i" -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/Quaternion.i b/src/ruby/Quaternion.i index a7d4a1612..f58be9efd 100644 --- a/src/ruby/Quaternion.i +++ b/src/ruby/Quaternion.i @@ -28,12 +28,12 @@ %inline %{ template struct AxisAngleOutput { - ignition::math::Vector3 axis; + gz::math::Vector3 axis; D angle; }; %} -namespace ignition +namespace gz { namespace math { @@ -123,7 +123,7 @@ namespace ignition %extend Quaternion{ inline AxisAngleOutput _axis_angle() { - ignition::math::Vector3 axis; + gz::math::Vector3 axis; T angle; (*$self).AxisAngle(axis, angle); AxisAngleOutput output; diff --git a/src/ruby/Rand.i b/src/ruby/Rand.i index 3ef19f5a7..7716b8bbe 100644 --- a/src/ruby/Rand.i +++ b/src/ruby/Rand.i @@ -20,7 +20,7 @@ #include %} -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/Rand_TEST.rb b/src/ruby/Rand_TEST.rb index 46ebcb3d9..90293d33f 100644 --- a/src/ruby/Rand_TEST.rb +++ b/src/ruby/Rand_TEST.rb @@ -20,15 +20,15 @@ class Rand_TEST < Test::Unit::TestCase def test_rand - d = Ignition::Math::Rand::DblUniform(1, 2) + d = Gz::Math::Rand::DblUniform(1, 2) assert(d >= 1 && d <= 2, "The value should be 1 <= d <= 2") - i = Ignition::Math::Rand::IntUniform(1, 2) + i = Gz::Math::Rand::IntUniform(1, 2) assert(i >= 1 && i <= 2, "The value should be 1 <= i <= 2") - Ignition::Math::Rand::Seed(1001) + Gz::Math::Rand::Seed(1001) - i = Ignition::Math::Rand::IntNormal(10, 5) + i = Gz::Math::Rand::IntNormal(10, 5) assert(i == 11, "The value should be 11") end end diff --git a/src/ruby/RollingMean.i b/src/ruby/RollingMean.i index 0788de76c..3b82fd18e 100644 --- a/src/ruby/RollingMean.i +++ b/src/ruby/RollingMean.i @@ -20,7 +20,7 @@ #include %} -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/RotationSpline.i b/src/ruby/RotationSpline.i index 8af437de5..3b5a8a769 100644 --- a/src/ruby/RotationSpline.i +++ b/src/ruby/RotationSpline.i @@ -22,7 +22,7 @@ #include %} -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/SemanticVersion.i b/src/ruby/SemanticVersion.i index b63b84e0d..5d854605d 100644 --- a/src/ruby/SemanticVersion.i +++ b/src/ruby/SemanticVersion.i @@ -23,7 +23,7 @@ %include "std_string.i" -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/SignalStats.i b/src/ruby/SignalStats.i index 406f922f8..501954b45 100644 --- a/src/ruby/SignalStats.i +++ b/src/ruby/SignalStats.i @@ -25,7 +25,7 @@ %include "std_map.i" %template(map_string_double) std::map; -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/Sphere.i b/src/ruby/Sphere.i index 3c67ab3d5..6bf441dc8 100644 --- a/src/ruby/Sphere.i +++ b/src/ruby/Sphere.i @@ -25,10 +25,10 @@ %} %include "typemaps.i" -%typemap(out) (std::optional< ignition::math::Vector3< double > >) %{ +%typemap(out) (std::optional< gz::math::Vector3< double > >) %{ if((*(&result)).has_value()) { $result = SWIG_NewPointerObj( - (new ignition::math::Vector3< double >(static_cast< const ignition::math::Vector3< double >& >((*(&result)).value()))), + (new gz::math::Vector3< double >(static_cast< const gz::math::Vector3< double >& >((*(&result)).value()))), SWIGTYPE_p_ignition__math__Vector3T_double_t, SWIG_POINTER_OWN | 0 ); } else { @@ -37,7 +37,7 @@ } %} -namespace ignition +namespace gz { namespace math { @@ -48,7 +48,7 @@ namespace ignition public: explicit Sphere(const Precision _radius); - public: Sphere(const Precision _radius, const ignition::math::Material &_mat); + public: Sphere(const Precision _radius, const gz::math::Material &_mat); public: ~Sphere() = default; @@ -56,11 +56,11 @@ namespace ignition public: void SetRadius(const Precision _radius); - public: const ignition::math::Material &Material() const; + public: const gz::math::Material &Material() const; - public: void SetMaterial(const ignition::math::Material &_mat); + public: void SetMaterial(const gz::math::Material &_mat); - public: bool MassMatrix(ignition::math::MassMatrix3 &_massMat) const; + public: bool MassMatrix(gz::math::MassMatrix3 &_massMat) const; public: bool operator==(const Sphere &_sphere) const; @@ -68,10 +68,10 @@ namespace ignition public: Precision Volume() const; - public: Precision VolumeBelow(const ignition::math::Plane &_plane) const; + public: Precision VolumeBelow(const gz::math::Plane &_plane) const; - public: std::optional> - CenterOfVolumeBelow(const ignition::math::Plane &_plane) const; + public: std::optional> + CenterOfVolumeBelow(const gz::math::Plane &_plane) const; public: Precision DensityFromMass(const Precision _mass) const; diff --git a/src/ruby/SphericalCoordinates.i b/src/ruby/SphericalCoordinates.i index ce98ad306..801536e2e 100644 --- a/src/ruby/SphericalCoordinates.i +++ b/src/ruby/SphericalCoordinates.i @@ -26,7 +26,7 @@ #include %} -namespace ignition +namespace gz { namespace math { @@ -64,66 +64,66 @@ namespace ignition public: explicit SphericalCoordinates(const SurfaceType _type); public: SphericalCoordinates(const SurfaceType _type, - const ignition::math::Angle &_latitude, - const ignition::math::Angle &_longitude, + const gz::math::Angle &_latitude, + const gz::math::Angle &_longitude, const double _elevation, - const ignition::math::Angle &_heading); + const gz::math::Angle &_heading); public: SphericalCoordinates(const SphericalCoordinates &_sc); /// \brief Destructor. public: ~SphericalCoordinates(); - public: ignition::math::Vector3 SphericalFromLocalPosition( - const ignition::math::Vector3 &_xyz) const; + public: gz::math::Vector3 SphericalFromLocalPosition( + const gz::math::Vector3 &_xyz) const; - public: ignition::math::Vector3 GlobalFromLocalVelocity( - const ignition::math::Vector3 &_xyz) const; + public: gz::math::Vector3 GlobalFromLocalVelocity( + const gz::math::Vector3 &_xyz) const; public: static SurfaceType Convert(const std::string &_str); public: static std::string Convert(SurfaceType _type); - public: static double Distance(const ignition::math::Angle &_latA, - const ignition::math::Angle &_lonA, - const ignition::math::Angle &_latB, - const ignition::math::Angle &_lonB); + public: static double Distance(const gz::math::Angle &_latA, + const gz::math::Angle &_lonA, + const gz::math::Angle &_latB, + const gz::math::Angle &_lonB); public: SurfaceType Surface() const; - public: ignition::math::Angle LatitudeReference() const; + public: gz::math::Angle LatitudeReference() const; - public: ignition::math::Angle LongitudeReference() const; + public: gz::math::Angle LongitudeReference() const; public: double ElevationReference() const; - public: ignition::math::Angle HeadingOffset() const; + public: gz::math::Angle HeadingOffset() const; public: void SetSurface(const SurfaceType &_type); - public: void SetLatitudeReference(const ignition::math::Angle &_angle); + public: void SetLatitudeReference(const gz::math::Angle &_angle); - public: void SetLongitudeReference(const ignition::math::Angle &_angle); + public: void SetLongitudeReference(const gz::math::Angle &_angle); public: void SetElevationReference(const double _elevation); - public: void SetHeadingOffset(const ignition::math::Angle &_angle); + public: void SetHeadingOffset(const gz::math::Angle &_angle); - public: ignition::math::Vector3 LocalFromSphericalPosition( - const ignition::math::Vector3 &_latLonEle) const; + public: gz::math::Vector3 LocalFromSphericalPosition( + const gz::math::Vector3 &_latLonEle) const; - public: ignition::math::Vector3 LocalFromGlobalVelocity( - const ignition::math::Vector3 &_xyz) const; + public: gz::math::Vector3 LocalFromGlobalVelocity( + const gz::math::Vector3 &_xyz) const; public: void UpdateTransformationMatrix(); - public: ignition::math::Vector3 - PositionTransform(const ignition::math::Vector3 &_pos, + public: gz::math::Vector3 + PositionTransform(const gz::math::Vector3 &_pos, const CoordinateType &_in, const CoordinateType &_out) const; /// \return Transformed velocity vector - public: ignition::math::Vector3 VelocityTransform( - const ignition::math::Vector3 &_vel, + public: gz::math::Vector3 VelocityTransform( + const gz::math::Vector3 &_vel, const CoordinateType &_in, const CoordinateType &_out) const; public: bool operator==(const SphericalCoordinates &_sc) const; diff --git a/src/ruby/Spline.i b/src/ruby/Spline.i index f68c181ae..cf644e6f5 100644 --- a/src/ruby/Spline.i +++ b/src/ruby/Spline.i @@ -23,7 +23,7 @@ #include %} -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/StopWatch.i b/src/ruby/StopWatch.i index 7a640767d..1095f869d 100644 --- a/src/ruby/StopWatch.i +++ b/src/ruby/StopWatch.i @@ -34,7 +34,7 @@ $result = SWIG_From_long((&result)->count()); %} -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/Temperature.i b/src/ruby/Temperature.i index dcaa13c65..d6bb06eb1 100644 --- a/src/ruby/Temperature.i +++ b/src/ruby/Temperature.i @@ -23,7 +23,7 @@ %include "std_string.i" -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/Triangle.i b/src/ruby/Triangle.i index 966b29e7e..99376ceb1 100644 --- a/src/ruby/Triangle.i +++ b/src/ruby/Triangle.i @@ -25,7 +25,7 @@ #include %} -namespace ignition +namespace gz { namespace math { @@ -54,7 +54,7 @@ namespace math %extend Triangle { - ignition::math::Vector2 __getitem__(const unsigned int i) const + gz::math::Vector2 __getitem__(const unsigned int i) const { return (*$self)[i]; } diff --git a/src/ruby/Triangle3.i b/src/ruby/Triangle3.i index 2ad52da92..7f8e5d326 100644 --- a/src/ruby/Triangle3.i +++ b/src/ruby/Triangle3.i @@ -25,7 +25,7 @@ #include %} -namespace ignition +namespace gz { namespace math { @@ -34,27 +34,27 @@ namespace math { %rename("%(undercase)s", %$isfunction, %$ismember, %$not %$isconstructor) ""; public: Triangle3() = default; - public: Triangle3(const ignition::math::Vector3 &_pt1, - const ignition::math::Vector3 &_pt2, - const ignition::math::Vector3 &_pt3); + public: Triangle3(const gz::math::Vector3 &_pt1, + const gz::math::Vector3 &_pt2, + const gz::math::Vector3 &_pt3); public: void Set(const unsigned int _index, const math::Vector3 &_pt); - public: void Set(const ignition::math::Vector3 &_pt1, - const ignition::math::Vector3 &_pt2, - const ignition::math::Vector3 &_pt3); + public: void Set(const gz::math::Vector3 &_pt1, + const gz::math::Vector3 &_pt2, + const gz::math::Vector3 &_pt3); public: bool Valid() const; public: Line3 Side(const unsigned int _index) const; public: bool Contains(const Line3 &_line) const; - public: bool Contains(const ignition::math::Vector3 &_pt) const; - public: ignition::math::Vector3d Normal() const; + public: bool Contains(const gz::math::Vector3 &_pt) const; + public: gz::math::Vector3d Normal() const; public: bool Intersects(const Line3 &_line, - ignition::math::Vector3 &_ipt1) const; + gz::math::Vector3 &_ipt1) const; public: T Perimeter() const; public: double Area() const; }; %extend Triangle3 { - ignition::math::Vector3 __getitem__(const unsigned int i) const + gz::math::Vector3 __getitem__(const unsigned int i) const { return (*$self)[i]; } diff --git a/src/ruby/Vector2.i b/src/ruby/Vector2.i index e37b1083a..ae3352658 100644 --- a/src/ruby/Vector2.i +++ b/src/ruby/Vector2.i @@ -26,7 +26,7 @@ #include %} -namespace ignition +namespace gz { namespace math { @@ -38,15 +38,15 @@ namespace ignition public: %extend { static Vector2 Zero() { - return ignition::math::Vector2::Zero; + return gz::math::Vector2::Zero; } static Vector2 One() { - return ignition::math::Vector2::One; + return gz::math::Vector2::One; } static Vector2 NaN() { - return ignition::math::Vector2::NaN; + return gz::math::Vector2::NaN; } } public: Vector2(); diff --git a/src/ruby/Vector2_TEST.rb b/src/ruby/Vector2_TEST.rb index cdc350e2c..cf1a97ee8 100644 --- a/src/ruby/Vector2_TEST.rb +++ b/src/ruby/Vector2_TEST.rb @@ -20,69 +20,69 @@ class Vector2_TEST < Test::Unit::TestCase def test_construction - v = Ignition::Math::Vector2d.new + v = Gz::Math::Vector2d.new assert(v.X.zero?, "v.X should equal zero") assert(v.Y.zero?, "v.Y should equal zero") - v2 = Ignition::Math::Vector2d.new(1, 2) + v2 = Gz::Math::Vector2d.new(1, 2) assert(v2.X == 1, "v2.X should equal 1") assert(v2.Y == 2, "v2.Y should equal 2") end def test_functions - v = Ignition::Math::Vector2d.new(1, 2) + v = Gz::Math::Vector2d.new(1, 2) # ::Distance - assert((v.Distance(Ignition::Math::Vector2d.Zero) - 2.236).abs < 1e-2, + assert((v.Distance(Gz::Math::Vector2d.Zero) - 2.236).abs < 1e-2, "Distance from (1,2)->(0,0) should equal 2.236") # ::Normalize v.Normalize() - assert(v == Ignition::Math::Vector2d.new(0.447214, 0.894427), + assert(v == Gz::Math::Vector2d.new(0.447214, 0.894427), "v should equal (0.447214, 0.894427)") # ::Set v.Set(4, 5) - assert(v == Ignition::Math::Vector2d.new(4, 5), + assert(v == Gz::Math::Vector2d.new(4, 5), "v should equal (4, 5)") # ::operator= - v = Ignition::Math::Vector2d.new(7, 8) - assert(v == Ignition::Math::Vector2d.new(7, 8), + v = Gz::Math::Vector2d.new(7, 8) + assert(v == Gz::Math::Vector2d.new(7, 8), "v should equal (7, 8)") # ::operator+ - v = Ignition::Math::Vector2d.new(1, 2) + 5 - assert(v == Ignition::Math::Vector2d.new(6, 7), + v = Gz::Math::Vector2d.new(1, 2) + 5 + assert(v == Gz::Math::Vector2d.new(6, 7), "v should equal (6, 7) after addition") # ::operator - - v = v - Ignition::Math::Vector2d.new(2, 4) - assert(v == Ignition::Math::Vector2d.new(4, 3), + v = v - Gz::Math::Vector2d.new(2, 4) + assert(v == Gz::Math::Vector2d.new(4, 3), "v should equal (4, 3)") # ::operator / v.Set(10, 6) - v = v / Ignition::Math::Vector2d.new(2, 3) - assert(v == Ignition::Math::Vector2d.new(5, 2), + v = v / Gz::Math::Vector2d.new(2, 3) + assert(v == Gz::Math::Vector2d.new(5, 2), "v should equal (5, 2)") # ::operator / int v.Set(10, 6) v = v / 2 - assert(v == Ignition::Math::Vector2d.new(5, 3), + assert(v == Gz::Math::Vector2d.new(5, 3), "v should equal (5, 3)") # ::operator * int v.Set(10, 6) v = v * 2 - assert(v == Ignition::Math::Vector2d.new(20, 12), + assert(v == Gz::Math::Vector2d.new(20, 12), "v should equal (20, 12)") # ::operator * vector2i v.Set(10, 6) - v = v * Ignition::Math::Vector2d.new(2, 4) - assert(v == Ignition::Math::Vector2d.new(20, 24), + v = v * Gz::Math::Vector2d.new(2, 4) + assert(v == Gz::Math::Vector2d.new(20, 24), "v should equal (20, 24)") # ::IsFinite @@ -90,80 +90,80 @@ def test_functions end def test_equal_tolerance - assert(!Ignition::Math::Vector2d.Zero.Equal( - Ignition::Math::Vector2d.One, 1e-6), + assert(!Gz::Math::Vector2d.Zero.Equal( + Gz::Math::Vector2d.One, 1e-6), "Zero should not equal 1 with 1e-6 tolerance") - assert(!Ignition::Math::Vector2d.Zero.Equal( - Ignition::Math::Vector2d.One, 1e-3), + assert(!Gz::Math::Vector2d.Zero.Equal( + Gz::Math::Vector2d.One, 1e-3), "Zero should not equal 1 with 1e-3 tolerance") - assert(!Ignition::Math::Vector2d.Zero.Equal( - Ignition::Math::Vector2d.One, 1e-1), + assert(!Gz::Math::Vector2d.Zero.Equal( + Gz::Math::Vector2d.One, 1e-1), "Zero should not equal 1 with 1e-1 tolerance") - assert(Ignition::Math::Vector2d.Zero.Equal( - Ignition::Math::Vector2d.One, 1), + assert(Gz::Math::Vector2d.Zero.Equal( + Gz::Math::Vector2d.One, 1), "Zero should equal 1 with 1 tolerance") - assert(Ignition::Math::Vector2d.Zero.Equal( - Ignition::Math::Vector2d.One, 1.1), + assert(Gz::Math::Vector2d.Zero.Equal( + Gz::Math::Vector2d.One, 1.1), "Zero should equal 1 with 1.1 tolerance") end def test_max - vec1 = Ignition::Math::Vector2d.new(0.1, 0.2) - vec2 = Ignition::Math::Vector2d.new(0.3, 0.5) - vec3 = Ignition::Math::Vector2d.new(0.4, 0.2) + vec1 = Gz::Math::Vector2d.new(0.1, 0.2) + vec2 = Gz::Math::Vector2d.new(0.3, 0.5) + vec3 = Gz::Math::Vector2d.new(0.4, 0.2) assert((vec1.Max() - 0.2).abs() < 1e-10, "Vector2 vec1.Max should equal 0.2") vec1.Max(vec2) - assert(vec1 == Ignition::Math::Vector2d.new(0.3, 0.5), + assert(vec1 == Gz::Math::Vector2d.new(0.3, 0.5), "Vector2 vec1 should equal [0.3, 0.5]") vec1.Max(vec3) - assert(vec1 == Ignition::Math::Vector2d.new(0.4, 0.5), + assert(vec1 == Gz::Math::Vector2d.new(0.4, 0.5), "Vector2 vec1 should equal [0.4, 0.5]") end def test_min - vec1 = Ignition::Math::Vector2d.new(0.3, 0.5) - vec2 = Ignition::Math::Vector2d.new(0.1, 0.2) - vec3 = Ignition::Math::Vector2d.new(0.05, 0.1) + vec1 = Gz::Math::Vector2d.new(0.3, 0.5) + vec2 = Gz::Math::Vector2d.new(0.1, 0.2) + vec3 = Gz::Math::Vector2d.new(0.05, 0.1) assert((vec1.Min() - 0.3).abs() < 1e-10, "Vector2 vec1.Min should equal 0.3") vec1.Min(vec2) - assert(vec1 == Ignition::Math::Vector2d.new(0.1, 0.2), + assert(vec1 == Gz::Math::Vector2d.new(0.1, 0.2), "Vector2 vec1 should equal [0.1, 0.2]") vec3.Max(vec2) - assert(vec3 == Ignition::Math::Vector2d.new(0.1, 0.2), + assert(vec3 == Gz::Math::Vector2d.new(0.1, 0.2), "Vector2 vec3 should equal [0.1, 0.2]") end def test_dot - v = Ignition::Math::Vector2d.new(1, 2) + v = Gz::Math::Vector2d.new(1, 2) - assert(v.Dot(Ignition::Math::Vector2d.new(3, 4)) == 11.0, + assert(v.Dot(Gz::Math::Vector2d.new(3, 4)) == 11.0, "v.dot((3,4)) should equal 11") - assert(v.Dot(Ignition::Math::Vector2d.new(0, 0)) == 0.0, + assert(v.Dot(Gz::Math::Vector2d.new(0, 0)) == 0.0, "v.dot((0,0)) should equal 0") - assert(v.Dot(Ignition::Math::Vector2d.new(1, 0)) == 1.0, + assert(v.Dot(Gz::Math::Vector2d.new(1, 0)) == 1.0, "v.dot((1,0)) should equal 1") - assert(v.Dot(Ignition::Math::Vector2d.new(0, 1)) == 2.0, + assert(v.Dot(Gz::Math::Vector2d.new(0, 1)) == 2.0, "v.dot((0,1)) should equal 2") end def test_add - vec1 = Ignition::Math::Vector2d.new(0.1, 0.2) - vec2 = Ignition::Math::Vector2d.new(1.1, 2.2) + vec1 = Gz::Math::Vector2d.new(0.1, 0.2) + vec2 = Gz::Math::Vector2d.new(1.1, 2.2) vec3 = vec1 vec3 += vec2 - assert(vec1 + vec2 == Ignition::Math::Vector2d.new(1.2, 2.4), + assert(vec1 + vec2 == Gz::Math::Vector2d.new(1.2, 2.4), "vec1 + vec2 should equal (1.2, 2.4") - assert(vec3 == Ignition::Math::Vector2d.new(1.2, 2.4), + assert(vec3 == Gz::Math::Vector2d.new(1.2, 2.4), "vec3 should equal (1.2, 2.4)") # Add zeros @@ -172,86 +172,86 @@ def test_add assert(vec1 + 0 == vec1, "vec1 should equal vec1 + 0") # Vector left and right - assert(Ignition::Math::Vector2d.Zero + vec1 == vec1, - "Ignition::Math::Vector2d.Zero + vec1 should equal vec1") - assert(vec1 + Ignition::Math::Vector2d.Zero == vec1, - "vec1 + Ignition::Math::Vector2d.Zero should equal vec1") + assert(Gz::Math::Vector2d.Zero + vec1 == vec1, + "Gz::Math::Vector2d.Zero + vec1 should equal vec1") + assert(vec1 + Gz::Math::Vector2d.Zero == vec1, + "vec1 + Gz::Math::Vector2d.Zero should equal vec1") end # Add non-trivial scalar values left and right - assert(vec1 + 2.5 == Ignition::Math::Vector2d.new(2.6, 2.7), + assert(vec1 + 2.5 == Gz::Math::Vector2d.new(2.6, 2.7), "vec1 + 2.5 should equal (2.6, 2.7)") end def test_sub - vec1 = Ignition::Math::Vector2d.new(0.1, 0.2) - vec2 = Ignition::Math::Vector2d.new(1.1, 2.2) + vec1 = Gz::Math::Vector2d.new(0.1, 0.2) + vec2 = Gz::Math::Vector2d.new(1.1, 2.2) vec3 = vec2 vec3 -= vec1 - assert(vec2 - vec1 == Ignition::Math::Vector2d.new(1.0, 2.0), + assert(vec2 - vec1 == Gz::Math::Vector2d.new(1.0, 2.0), "vec2 - vec1 should equal (1.0, 2.0)") - assert(vec3 == Ignition::Math::Vector2d.new(1.0, 2.0), + assert(vec3 == Gz::Math::Vector2d.new(1.0, 2.0), "vec3 should equal (1.0, 2.0)") # Scalar left and right assert(vec1 - 0 == vec1, "vec1 - 0 should equal vec1") # Vector left and right - assert(Ignition::Math::Vector2d.Zero - vec1 == -vec1, - "Ignition::Math::Vector2d.Zero - vec1 should equal -vec1") - assert(vec1 - Ignition::Math::Vector2d.Zero == vec1, - "vec1 - Ignition::Math::Vector2d.Zero should equal vec1") + assert(Gz::Math::Vector2d.Zero - vec1 == -vec1, + "Gz::Math::Vector2d.Zero - vec1 should equal -vec1") + assert(vec1 - Gz::Math::Vector2d.Zero == vec1, + "vec1 - Gz::Math::Vector2d.Zero should equal vec1") # Subtract non-trivial scalar values left and right - assert(vec1 - 2.5 == -Ignition::Math::Vector2d.new(2.4, 2.3), + assert(vec1 - 2.5 == -Gz::Math::Vector2d.new(2.4, 2.3), "vec1 - 2.5 should equal (2.4, 2.3)") end def test_multiply - v = Ignition::Math::Vector2d.new(0.1, -4.2) + v = Gz::Math::Vector2d.new(0.1, -4.2) # Scalar left and right - assert(v * 0 == Ignition::Math::Vector2d.Zero, + assert(v * 0 == Gz::Math::Vector2d.Zero, "v * 0 should equal Zero") # Element-wise vector multiplication - assert(v * Ignition::Math::Vector2d.Zero == Ignition::Math::Vector2d.Zero, - "v * Ignition::Math::Vector2d::Zero should equal zero") + assert(v * Gz::Math::Vector2d.Zero == Gz::Math::Vector2d.Zero, + "v * Gz::Math::Vector2d::Zero should equal zero") # Scalar left and right assert(v * 1 == v, "v * 1 should equal v") # Element-wise vector multiplication - assert(v * Ignition::Math::Vector2d.One == v, - "v * Ignition::Math::Vector2d.One should equal v") + assert(v * Gz::Math::Vector2d.One == v, + "v * Gz::Math::Vector2d.One should equal v") # Multiply by non-trivial scalar value scalar = 2.5 - expect = Ignition::Math::Vector2d.new(0.25, -10.5) + expect = Gz::Math::Vector2d.new(0.25, -10.5) assert(v * scalar == expect, "v * 2.5 should equal (0.25, -10.5)") # Multiply by itself element-wise - assert(v*v == Ignition::Math::Vector2d.new(0.01, 17.64), + assert(v*v == Gz::Math::Vector2d.new(0.01, 17.64), "v*v should equal (0.01, 17.64)") end def test_length # Zero vector - assert(Ignition::Math::Vector2d.Zero.Length() == 0.0, + assert(Gz::Math::Vector2d.Zero.Length() == 0.0, "Length of zero should equal 0.0") - assert(Ignition::Math::Vector2d.Zero.SquaredLength() == 0.0, + assert(Gz::Math::Vector2d.Zero.SquaredLength() == 0.0, "Squared length of zero should equal 0.0") # One vector - assert((Ignition::Math::Vector2d.One.Length() - Math.sqrt(2)).abs < 1e-10, + assert((Gz::Math::Vector2d.One.Length() - Math.sqrt(2)).abs < 1e-10, "Length of one should be near square root of 2") - assert(Ignition::Math::Vector2d.One.SquaredLength() == 2.0, + assert(Gz::Math::Vector2d.One.SquaredLength() == 2.0, "Squared lenght of one should equal 2") # Arbitrary vector - v = Ignition::Math::Vector2d.new(0.1, -4.2) + v = Gz::Math::Vector2d.new(0.1, -4.2) assert((v.Length() - 4.20119030752).abs < 1e-10, "Length should be near 4.20119030752") assert((v.SquaredLength() - 17.65).abs < 1e-8, @@ -259,24 +259,24 @@ def test_length end def test_nan - nanVec = Ignition::Math::Vector2d.NaN + nanVec = Gz::Math::Vector2d.NaN assert(!nanVec.IsFinite(), "NaN vector shouldn't be finite") assert(nanVec.X().nan?, "X should be NaN") assert(nanVec.Y().nan?, "Y should be NaN") nanVec.Correct() - assert(Ignition::Math::Vector2d.Zero == nanVec, + assert(Gz::Math::Vector2d.Zero == nanVec, "Corrected vector should equal zero") - nanVecF = Ignition::Math::Vector2f.NaN + nanVecF = Gz::Math::Vector2f.NaN assert(!nanVecF.IsFinite(), "NaN vector shouldn't be finite") assert(nanVecF.X().nan?, "X should be NaN") assert(nanVecF.Y().nan?, "Y should be NaN") nanVecF.Correct() - assert(Ignition::Math::Vector2f.Zero == nanVecF, + assert(Gz::Math::Vector2f.Zero == nanVecF, "Corrected vector should equal zero") end end diff --git a/src/ruby/Vector3.i b/src/ruby/Vector3.i index 8870d5612..b2b1fe9dd 100644 --- a/src/ruby/Vector3.i +++ b/src/ruby/Vector3.i @@ -26,7 +26,7 @@ #include %} -namespace ignition +namespace gz { namespace math { @@ -38,27 +38,27 @@ namespace ignition public: %extend { static Vector3 Zero() { - return ignition::math::Vector3::Zero; + return gz::math::Vector3::Zero; } static Vector3 One() { - return ignition::math::Vector3::One; + return gz::math::Vector3::One; } static Vector3 UnitX() { - return ignition::math::Vector3::UnitX; + return gz::math::Vector3::UnitX; } static Vector3 UnitY() { - return ignition::math::Vector3::UnitY; + return gz::math::Vector3::UnitY; } static Vector3 UnitZ() { - return ignition::math::Vector3::UnitZ; + return gz::math::Vector3::UnitZ; } static Vector3 NaN() { - return ignition::math::Vector3::NaN; + return gz::math::Vector3::NaN; } } public: Vector3(); diff --git a/src/ruby/Vector3Stats.i b/src/ruby/Vector3Stats.i index ba0060cb4..dffb2c664 100644 --- a/src/ruby/Vector3Stats.i +++ b/src/ruby/Vector3Stats.i @@ -25,7 +25,7 @@ %include "std_string.i" -namespace ignition +namespace gz { namespace math { diff --git a/src/ruby/Vector3_TEST.rb b/src/ruby/Vector3_TEST.rb index 97782e0e6..b84f56d08 100755 --- a/src/ruby/Vector3_TEST.rb +++ b/src/ruby/Vector3_TEST.rb @@ -21,92 +21,92 @@ class Vector3_TEST < Test::Unit::TestCase def test_construction - v = Ignition::Math::Vector3d.new + v = Gz::Math::Vector3d.new # ::Distance, ::Length() v.Set(1, 2, 3) - assert(v.Length() == v.Distance(Ignition::Math::Vector3d.Zero), + assert(v.Length() == v.Distance(Gz::Math::Vector3d.Zero), "Vector3d::Lenth() should equal Vector3d::Distance(zero)") # ::Rounded v.Set(1.23, 2.34, 3.55) - assert(v.Rounded() == Ignition::Math::Vector3d.new(1, 2, 4), + assert(v.Rounded() == Gz::Math::Vector3d.new(1, 2, 4), "Vector3d::Rounded() should equal [1, 2, 4]") # ::Round v.Round() - assert(v.Round() == Ignition::Math::Vector3d.new(1, 2, 4), + assert(v.Round() == Gz::Math::Vector3d.new(1, 2, 4), "Vector3d::Round should equal [1,2,4]") # ::DotProd - assert(v.Dot(Ignition::Math::Vector3d.new(1, 2, 3)) == 17.0, + assert(v.Dot(Gz::Math::Vector3d.new(1, 2, 3)) == 17.0, "Vector3d::Dot([1,2,3]) should equal 17.0") # ::DistToLine v.Set(0, 0, 0) - assert(1.0 == v.DistToLine(Ignition::Math::Vector3d.new(1, -1, 0), - Ignition::Math::Vector3d.new(1, 1, 0)), + assert(1.0 == v.DistToLine(Gz::Math::Vector3d.new(1, -1, 0), + Gz::Math::Vector3d.new(1, 1, 0)), "Vector3d::DistToLine([1, -1, 0], [1, 1, 0]) should equal 1") # ::operator/ vector3 v.Set(4, 4, 4) - v = v / Ignition::Math::Vector3d.new(1, 2, 4) - assert(v == Ignition::Math::Vector3d.new(4, 2, 1), + v = v / Gz::Math::Vector3d.new(1, 2, 4) + assert(v == Gz::Math::Vector3d.new(4, 2, 1), "v / Vector3d(1, 2, 4) should equal Vector3d(4, 2, 1)") # ::operator / double v = v / 2 - assert(v == Ignition::Math::Vector3d.new(2, 1, 0.5), + assert(v == Gz::Math::Vector3d.new(2, 1, 0.5), "v / 2 should equal Vector3d(2, 1, .5)") # ::operator * vector3 - v = v * Ignition::Math::Vector3d.new(2, 3, 4) - assert(v == Ignition::Math::Vector3d.new(4, 3, 2), + v = v * Gz::Math::Vector3d.new(2, 3, 4) + assert(v == Gz::Math::Vector3d.new(4, 3, 2), "v * Vector3d(2, 3, 4) should equal Vector3d(4, 3, 2)") v.Set(1.23, 2.35, 3.654321) v.Round(1) - assert(v == Ignition::Math::Vector3d.new(1.2, 2.4, 3.7)) + assert(v == Gz::Math::Vector3d.new(1.2, 2.4, 3.7)) # operator GetAbs v.Set(-1, -2, -3) - assert(v.Abs() == Ignition::Math::Vector3d.new(1, 2, 3)) + assert(v.Abs() == Gz::Math::Vector3d.new(1, 2, 3)) # operator /= v.Set(1, 2, 4) - v /= Ignition::Math::Vector3d.new(1, 4, 4) - assert(v == Ignition::Math::Vector3d.new(1, 0.5, 1)) + v /= Gz::Math::Vector3d.new(1, 4, 4) + assert(v == Gz::Math::Vector3d.new(1, 0.5, 1)) # operator *= v.Set(1, 2, 4) - v *= Ignition::Math::Vector3d.new(2, 0.5, 0.1) - assert(v.Equal(Ignition::Math::Vector3d.new(2, 1, 0.4))) + v *= Gz::Math::Vector3d.new(2, 0.5, 0.1) + assert(v.Equal(Gz::Math::Vector3d.new(2, 1, 0.4))) # Test the static defines. - assert(Ignition::Math::Vector3d.Zero == - Ignition::Math::Vector3d.new(0, 0, 0), + assert(Gz::Math::Vector3d.Zero == + Gz::Math::Vector3d.new(0, 0, 0), "Vector3d::Zero should equal [0, 0, 0]") - assert(Ignition::Math::Vector3d.One == - Ignition::Math::Vector3d.new(1, 1, 1), + assert(Gz::Math::Vector3d.One == + Gz::Math::Vector3d.new(1, 1, 1), "Vector3d::One should equal [1, 1, 1]") - assert(Ignition::Math::Vector3d.UnitX == - Ignition::Math::Vector3d.new(1, 0, 0), + assert(Gz::Math::Vector3d.UnitX == + Gz::Math::Vector3d.new(1, 0, 0), "Vector3d::UnitX should equal [1, 0, 0]") - assert(Ignition::Math::Vector3d.UnitY == - Ignition::Math::Vector3d.new(0, 1, 0), + assert(Gz::Math::Vector3d.UnitY == + Gz::Math::Vector3d.new(0, 1, 0), "Vector3d::UnitY should equal [0, 1, 0]") - assert(Ignition::Math::Vector3d.UnitZ == - Ignition::Math::Vector3d.new(0, 0, 1), + assert(Gz::Math::Vector3d.UnitZ == + Gz::Math::Vector3d.new(0, 0, 1), "Vector3d::UnitZ should equal [0, 0, 1]") end def test_distance - vec1 = Ignition::Math::Vector3d.new(0, 0, 0) - vec2 = Ignition::Math::Vector3d.new(1, 2, 3) + vec1 = Gz::Math::Vector3d.new(0, 0, 0) + vec2 = Gz::Math::Vector3d.new(1, 2, 3) dist = vec1.Distance(vec2) assert((dist - 3.74165738677).abs() < 1e-6, @@ -118,8 +118,8 @@ def test_distance end def test_sum - vec1 = Ignition::Math::Vector3d.new(0, 0, 0) - vec2 = Ignition::Math::Vector3d.new(1, 2, 3) + vec1 = Gz::Math::Vector3d.new(0, 0, 0) + vec2 = Gz::Math::Vector3d.new(1, 2, 3) sum1 = vec1.Sum() sum2 = vec2.Sum() @@ -129,8 +129,8 @@ def test_sum end def test_squared_length - vec1 = Ignition::Math::Vector3d.new(0, 0, 0) - vec2 = Ignition::Math::Vector3d.new(1, 2, 3) + vec1 = Gz::Math::Vector3d.new(0, 0, 0) + vec2 = Gz::Math::Vector3d.new(1, 2, 3) sum1 = vec1.SquaredLength() sum2 = vec2.SquaredLength() @@ -141,35 +141,35 @@ def test_squared_length def test_length # Zero vector - assert(Ignition::Math::Vector3d.Zero.Length() == 0.0, + assert(Gz::Math::Vector3d.Zero.Length() == 0.0, "Vector3 length of [0, 0, 0] should equal 0") - assert(Ignition::Math::Vector3d.Zero.SquaredLength() == 0.0, + assert(Gz::Math::Vector3d.Zero.SquaredLength() == 0.0, "Vector3 squared length of [0, 0, 0] should equal 0") - # UnitXYZ vectorsIgnition:: - assert(Ignition::Math::Vector3d.UnitX.Length() == 1.0, + # UnitXYZ vectorsGz:: + assert(Gz::Math::Vector3d.UnitX.Length() == 1.0, "Vector3 length of unitx should equal 1") - assert(Ignition::Math::Vector3d.UnitY.Length() == 1.0, + assert(Gz::Math::Vector3d.UnitY.Length() == 1.0, "Vector3 length of unity should equal 1") - assert(Ignition::Math::Vector3d.UnitZ.Length() == 1.0, + assert(Gz::Math::Vector3d.UnitZ.Length() == 1.0, "Vector3 length of unitz should equal 1") - assert(Ignition::Math::Vector3d.UnitX.SquaredLength() == 1.0, + assert(Gz::Math::Vector3d.UnitX.SquaredLength() == 1.0, "Vector3 squared length of unitx should equal 1") - assert(Ignition::Math::Vector3d.UnitY.SquaredLength() == 1.0, + assert(Gz::Math::Vector3d.UnitY.SquaredLength() == 1.0, "Vector3 squared length of unity should equal 1") - assert(Ignition::Math::Vector3d.UnitZ.SquaredLength() == 1.0, + assert(Gz::Math::Vector3d.UnitZ.SquaredLength() == 1.0, "Vector3 squared length of unitz should equal 1") # One vector - assert((Ignition::Math::Vector3d.One.Length() - + assert((Gz::Math::Vector3d.One.Length() - Math.sqrt(3.0)).abs() < 1e-10, "Vector3 length of [1, 1, 1] should equal sqrt(3.0)") - assert(Ignition::Math::Vector3d.One.SquaredLength() == 3.0, + assert(Gz::Math::Vector3d.One.SquaredLength() == 3.0, "Vector3 squared lenght of [1, 1, 1] should equal 3.0") # Arbitrary vector - v = Ignition::Math::Vector3d.new(0.1, -4.2, 2.5) + v = Gz::Math::Vector3d.new(0.1, -4.2, 2.5) assert((v.Length() - 4.88876262463).abs() < 1e-10, "Vector3 v length should equal 4.88876262463") @@ -178,88 +178,88 @@ def test_length end def test_normalize - vec1 = Ignition::Math::Vector3d.new(0, 0, 0) - vec2 = Ignition::Math::Vector3d.new(1, 2, 3) + vec1 = Gz::Math::Vector3d.new(0, 0, 0) + vec2 = Gz::Math::Vector3d.new(1, 2, 3) vec3 = vec1.Normalize() assert(vec3 == vec1, "Vector3 vec3 should equal vec1") - assert(vec1 == Ignition::Math::Vector3d.Zero, + assert(vec1 == Gz::Math::Vector3d.Zero, "Vector3 should equal [0, 0, 0]") vec3 = vec2.Normalize() assert(vec3 == vec2, "Vector3 vec3 should equal vec2") - assert(vec2 == Ignition::Math::Vector3d.new(0.267261, 0.534522, 0.801784), + assert(vec2 == Gz::Math::Vector3d.new(0.267261, 0.534522, 0.801784), "Vector3 vec2 should equal [0.267261, 0.534522, 0.801784]") - vecConst = Ignition::Math::Vector3d.new(1, 2, 3) + vecConst = Gz::Math::Vector3d.new(1, 2, 3) assert(vecConst.Normalized() == vec3, "Vector3 vecConst should equal vec3") - assert(vecConst == Ignition::Math::Vector3d.new(1, 2, 3), + assert(vecConst == Gz::Math::Vector3d.new(1, 2, 3), "Vector3 vecConst should euqal [1, 2, 3]") end def test_ge_normal - vec1 = Ignition::Math::Vector3d.new(0, 0, 0) - vec2 = Ignition::Math::Vector3d.new(0, 1, 0) - vec3 = Ignition::Math::Vector3d.new(1, 1, 0) + vec1 = Gz::Math::Vector3d.new(0, 0, 0) + vec2 = Gz::Math::Vector3d.new(0, 1, 0) + vec3 = Gz::Math::Vector3d.new(1, 1, 0) - norm = Ignition::Math::Vector3d::Normal(vec1, vec2, vec3) - assert(norm == Ignition::Math::Vector3d.new(0, 0, -1), + norm = Gz::Math::Vector3d::Normal(vec1, vec2, vec3) + assert(norm == Gz::Math::Vector3d.new(0, 0, -1), "Vector3 norm should equal [0, 0, -1]") end def test_perpendicular - vec1 = Ignition::Math::Vector3d.new(1, 1, 0) - vec2 = Ignition::Math::Vector3d.new(0, 1, 1) - vec3 = Ignition::Math::Vector3d.new(1e-7, 1e-7, 1e-7) - vec4 = Ignition::Math::Vector3d.new(1, 0, 0) + vec1 = Gz::Math::Vector3d.new(1, 1, 0) + vec2 = Gz::Math::Vector3d.new(0, 1, 1) + vec3 = Gz::Math::Vector3d.new(1e-7, 1e-7, 1e-7) + vec4 = Gz::Math::Vector3d.new(1, 0, 0) - assert(vec1.Perpendicular() == Ignition::Math::Vector3d.new(0, 0, -1), + assert(vec1.Perpendicular() == Gz::Math::Vector3d.new(0, 0, -1), "Vector3 vec1.Perpendicular() should equal [0, 0, -1]") - assert(vec2.Perpendicular() == Ignition::Math::Vector3d.new(0, 1, -1), + assert(vec2.Perpendicular() == Gz::Math::Vector3d.new(0, 1, -1), "Vector3 vec2.Perpendicular() should equal [0, 1, -1]") - assert(vec3.Perpendicular() == Ignition::Math::Vector3d.new(0, 0, 0), + assert(vec3.Perpendicular() == Gz::Math::Vector3d.new(0, 0, 0), "Vector3 vec3.Perpendicular() should equal [0, 0, 0]") - assert(vec4.Perpendicular() == Ignition::Math::Vector3d.new(0, 0, 1), + assert(vec4.Perpendicular() == Gz::Math::Vector3d.new(0, 0, 1), "Vector3 vec4.Perpendicular() should equal [0, 0, 1]") end def test_max - vec1 = Ignition::Math::Vector3d.new(0.1, 0.2, 0.3) - vec2 = Ignition::Math::Vector3d.new(0.2, 0.3, 0.4) - vec3 = Ignition::Math::Vector3d.new(0.1, 0.2, 0.3) + vec1 = Gz::Math::Vector3d.new(0.1, 0.2, 0.3) + vec2 = Gz::Math::Vector3d.new(0.2, 0.3, 0.4) + vec3 = Gz::Math::Vector3d.new(0.1, 0.2, 0.3) assert((vec1.Max() - 0.3).abs() < 1e-10, "Vector3 vec1.Max should equal 0.3") vec1.Max(vec2) - assert(vec1 == Ignition::Math::Vector3d.new(0.2, 0.3, 0.4), + assert(vec1 == Gz::Math::Vector3d.new(0.2, 0.3, 0.4), "Vector3 vec1 should equal [0.2, 0.3, 0.4]") vec1.Max(vec3) - assert(vec1 == Ignition::Math::Vector3d.new(0.2, 0.3, 0.4), + assert(vec1 == Gz::Math::Vector3d.new(0.2, 0.3, 0.4), "Vector3 vec1 should equal [0.2, 0.3, 0.4]") end def test_min - vec1 = Ignition::Math::Vector3d.new(0.1, 0.2, 0.3) - vec2 = Ignition::Math::Vector3d.new(0.2, 0.3, 0.4) - vec3 = Ignition::Math::Vector3d.new(0.05, 0.1, 0.2) + vec1 = Gz::Math::Vector3d.new(0.1, 0.2, 0.3) + vec2 = Gz::Math::Vector3d.new(0.2, 0.3, 0.4) + vec3 = Gz::Math::Vector3d.new(0.05, 0.1, 0.2) assert((vec1.Min() - 0.1).abs < 1e-10, "Vector3 vec1.Min should equal 0.1") vec1.Min(vec2) - assert(vec1 == Ignition::Math::Vector3d.new(0.1, 0.2, 0.3), + assert(vec1 == Gz::Math::Vector3d.new(0.1, 0.2, 0.3), "Vector3 vec1 should equal [0.1, 0.2, 0.3]") vec1.Min(vec3) - assert(vec1 == Ignition::Math::Vector3d.new(0.05, 0.1, 0.2), + assert(vec1 == Gz::Math::Vector3d.new(0.05, 0.1, 0.2), "Vector3 vec1 should equal [0.05, 0.1, 0.2]") end def test_max_abs - vec1 = Ignition::Math::Vector3d.new(0.1, 0.2, 0.05) + vec1 = Gz::Math::Vector3d.new(0.1, 0.2, 0.05) assert((vec1.MaxAbs() - 0.2).abs() < 1e-10, "Vector3 vec1.MaxAbs should equal 0.2") @@ -267,7 +267,7 @@ def test_max_abs end def test_min_abs - vec1 = Ignition::Math::Vector3d.new(-0.2, -0.1, -0.4) + vec1 = Gz::Math::Vector3d.new(-0.2, -0.1, -0.4) assert((vec1.MinAbs() - 0.1).abs < 1e-10, "Vector3 vec1.MinAbs should equal 0.1") @@ -275,15 +275,15 @@ def test_min_abs end def test_add - vec1 = Ignition::Math::Vector3d.new(0.1, 0.2, 0.4) - vec2 = Ignition::Math::Vector3d.new(1.1, 2.2, 3.4) + vec1 = Gz::Math::Vector3d.new(0.1, 0.2, 0.4) + vec2 = Gz::Math::Vector3d.new(1.1, 2.2, 3.4) vec3 = vec1 vec3 += vec2 - assert(vec1 + vec2 == Ignition::Math::Vector3d.new(1.2, 2.4, 3.8), + assert(vec1 + vec2 == Gz::Math::Vector3d.new(1.2, 2.4, 3.8), "Vector3 vec1 + vec2 should equal [1.2, 2.4, 3.8]") - assert(vec3 == Ignition::Math::Vector3d.new(1.2, 2.4, 3.8), + assert(vec3 == Gz::Math::Vector3d.new(1.2, 2.4, 3.8), "Vector3 vec3 should equal [1.2, 2.4, 3.8]") # Add zeros @@ -291,38 +291,38 @@ def test_add assert(vec1 + 0 == vec1, "Vector3 vec1+0 should equal vec1") # Vector left and right - assert(Ignition::Math::Vector3d.Zero + vec1 == vec1, + assert(Gz::Math::Vector3d.Zero + vec1 == vec1, "Vector3 Zero + vec1 should equal vec1") - assert(vec1 + Ignition::Math::Vector3d.Zero == vec1, + assert(vec1 + Gz::Math::Vector3d.Zero == vec1, "Vector3 vec1 + Zero should equal vec1") # Addition assignment vec4 = vec1 vec4 += 0 assert(vec4 == vec1, "Vector3 vec4 should equal vec1") - vec4 += Ignition::Math::Vector3d.Zero + vec4 += Gz::Math::Vector3d.Zero assert(vec4 == vec1, "Vector3 vec4 should equal vec1") # Add non-trivial scalar values left and right - assert(vec1 + 2.5 == Ignition::Math::Vector3d.new(2.6, 2.7, 2.9), + assert(vec1 + 2.5 == Gz::Math::Vector3d.new(2.6, 2.7, 2.9), "Vector3 vec1 + 2.5 should equal [2.6, 2.7, 2.9]") vec1 = vec4 vec4 += 2.5 - assert(vec4 == Ignition::Math::Vector3d.new(2.6, 2.7, 2.9), + assert(vec4 == Gz::Math::Vector3d.new(2.6, 2.7, 2.9), "Vector3 vec4 should equal [2.6, 2.7, 2.9]") end def test_sub - vec1 = Ignition::Math::Vector3d.new(0.1, 0.2, 0.4) - vec2 = Ignition::Math::Vector3d.new(1.1, 2.2, 3.4) + vec1 = Gz::Math::Vector3d.new(0.1, 0.2, 0.4) + vec2 = Gz::Math::Vector3d.new(1.1, 2.2, 3.4) vec3 = vec2 vec3 -= vec1 - assert(vec2 - vec1 === Ignition::Math::Vector3d.new(1.0, 2.0, 3.0), + assert(vec2 - vec1 === Gz::Math::Vector3d.new(1.0, 2.0, 3.0), "Vector3 vec2 - vec1 should equal [1.0, 2.0 3.0]") - assert(vec3 == Ignition::Math::Vector3d.new(1.0, 2.0, 3.0), + assert(vec3 == Gz::Math::Vector3d.new(1.0, 2.0, 3.0), "Vector3 vec3 should equal [1.0 2.0 3.0]") #Subtraction with zeros @@ -331,59 +331,59 @@ def test_sub assert(vec1 - 0 == vec1, "Vector3 vec1 - 0 should equal vec1") # Vector left and right - assert(Ignition::Math::Vector3d.Zero - vec1 == -vec1, + assert(Gz::Math::Vector3d.Zero - vec1 == -vec1, "Vector3 Zero - vec1 should equal -vec1") - assert(vec1 - Ignition::Math::Vector3d.Zero == vec1, + assert(vec1 - Gz::Math::Vector3d.Zero == vec1, "Vector3 vec1 - Zero should equal vec1") # Subtraction assignment vec4 = vec1 vec4 -= 0 assert(vec4 == vec1, "Vector3 vec4 should equal vec1") - vec4 -= Ignition::Math::Vector3d.Zero + vec4 -= Gz::Math::Vector3d.Zero assert(vec4 == vec1, "Vector3 vec4 should equal vec1") # Subtract non-trivial scalar values left and right - assert(vec1 - 2.5 == -Ignition::Math::Vector3d.new(2.4, 2.3, 2.1), + assert(vec1 - 2.5 == -Gz::Math::Vector3d.new(2.4, 2.3, 2.1), "Vecetor3 vec1 - 2.5 should equal [2.4, 2.3, 2.1]") vec4 = vec1 vec4 -= 2.5 - assert(vec4 == -Ignition::Math::Vector3d.new(2.4, 2.3, 2.1), + assert(vec4 == -Gz::Math::Vector3d.new(2.4, 2.3, 2.1), "Vector3 vec4 should equal [2.4, 2.3, 2.1]") end def test_divide - vec1 = Ignition::Math::Vector3d.new(0.1, 0.2, 0.4) + vec1 = Gz::Math::Vector3d.new(0.1, 0.2, 0.4) vec3 = vec1 / 2.0 - assert(vec3 == Ignition::Math::Vector3d.new(0.05, 0.1, 0.2), + assert(vec3 == Gz::Math::Vector3d.new(0.05, 0.1, 0.2), "Vector3 vec3 should equal [0.05, 0.1, 0.2]") vec3 /= 4.0 - assert(vec3 == Ignition::Math::Vector3d.new(0.0125, 0.025, 0.05), + assert(vec3 == Gz::Math::Vector3d.new(0.0125, 0.025, 0.05), "Vector3 vec3 should qual [0.0125, 0.025, 0.05]") end def test_multiply - v = Ignition::Math::Vector3d.new(0.1, 0.2, 0.3) + v = Gz::Math::Vector3d.new(0.1, 0.2, 0.3) vec3 = v * 2.0 - assert(vec3 == Ignition::Math::Vector3d.new(0.2, 0.4, 0.6), + assert(vec3 == Gz::Math::Vector3d.new(0.2, 0.4, 0.6), "Vector3 vec3 should equal[0.2, 0.4, 0.6]") vec3 *= 4.0 - assert(vec3 == Ignition::Math::Vector3d.new(0.8, 1.6, 2.4), + assert(vec3 == Gz::Math::Vector3d.new(0.8, 1.6, 2.4), "Vector3 vec3 should equal [0.8, 1.6, 2.4]") # Multiply by zero # Scalar left and right - assert(v * 0 == Ignition::Math::Vector3d.Zero, + assert(v * 0 == Gz::Math::Vector3d.Zero, "Vector3 v * 0 should equal Zero") # Element-wise vector multiplication - assert(v * Ignition::Math::Vector3d.Zero == Ignition::Math::Vector3d.Zero, + assert(v * Gz::Math::Vector3d.Zero == Gz::Math::Vector3d.Zero, "Vector3 v * Zero should equal Zero") # Multiply by one @@ -392,57 +392,57 @@ def test_multiply assert(v * 1 == v, "Vector3 v * 1 should equal v") # Element-wise vector multiplication - assert(v * Ignition::Math::Vector3d.One == v, + assert(v * Gz::Math::Vector3d.One == v, "Vector3 v * One should equal v") # Multiply by non-trivial scalar value scalar = 2.5 - expect = Ignition::Math::Vector3d.new(0.25, 0.5, 0.75) + expect = Gz::Math::Vector3d.new(0.25, 0.5, 0.75) assert(v * scalar == expect, "Vector3 v * scalar should equal [0.25, 0.5, 0.75]") # Multiply by itself element-wise - assert(v*v == Ignition::Math::Vector3d.new(0.01, 0.04, 0.09), + assert(v*v == Gz::Math::Vector3d.new(0.01, 0.04, 0.09), "Vector3 v * v should euqal [0.01, 0.04, 0.09]") end def test_not_equal - vec1 = Ignition::Math::Vector3d.new(0.1, 0.2, 0.3) - vec2 = Ignition::Math::Vector3d.new(0.2, 0.2, 0.3) - vec3 = Ignition::Math::Vector3d.new(0.1, 0.2, 0.3) + vec1 = Gz::Math::Vector3d.new(0.1, 0.2, 0.3) + vec2 = Gz::Math::Vector3d.new(0.2, 0.2, 0.3) + vec3 = Gz::Math::Vector3d.new(0.1, 0.2, 0.3) assert(vec1 != vec2, "Vector3 vec1 should not equal vec2") assert(!(vec1 != vec3), "Vector3 vec1 should not equal vec3" ) end def test_equal - assert(!Ignition::Math::Vector3d.Zero.Equal( - Ignition::Math::Vector3d.One, 1e-6), + assert(!Gz::Math::Vector3d.Zero.Equal( + Gz::Math::Vector3d.One, 1e-6), "Vector3 Zero should not equal 1 with tolerance of 1e-6") - assert(!Ignition::Math::Vector3d.Zero.Equal( - Ignition::Math::Vector3d.One, 1e-3), + assert(!Gz::Math::Vector3d.Zero.Equal( + Gz::Math::Vector3d.One, 1e-3), "Vector3 Zero should not equal 1 with tolerance of 1e-3") - assert(!Ignition::Math::Vector3d.Zero.Equal( - Ignition::Math::Vector3d.One, 1e-1), + assert(!Gz::Math::Vector3d.Zero.Equal( + Gz::Math::Vector3d.One, 1e-1), "Vector3 Zero should not equal 1 with tolerance of 1e-1") - assert(Ignition::Math::Vector3d.Zero.Equal( - Ignition::Math::Vector3d.One, 1), + assert(Gz::Math::Vector3d.Zero.Equal( + Gz::Math::Vector3d.One, 1), "Vector3 Zero should equal 1 with tolerance of 1") - assert(Ignition::Math::Vector3d.Zero.Equal( - Ignition::Math::Vector3d.One, 1.1), + assert(Gz::Math::Vector3d.Zero.Equal( + Gz::Math::Vector3d.One, 1.1), "Vector3 Zero should equal 1 with tolerance of 1.1") end def test_finite - vec1 = Ignition::Math::Vector3d.new(0.1, 0.2, 0.3) + vec1 = Gz::Math::Vector3d.new(0.1, 0.2, 0.3) assert(vec1.IsFinite(), "Vector3 vec1 should be be finite") end def test_nan - nanVec = Ignition::Math::Vector3d.NaN + nanVec = Gz::Math::Vector3d.NaN assert(!nanVec.IsFinite(), "NaN vector shouldn't be finite") assert(nanVec.X().nan?, "X should be NaN") @@ -450,10 +450,10 @@ def test_nan assert(nanVec.Z().nan?, "Z should be NaN") nanVec.Correct() - assert(Ignition::Math::Vector3d.Zero == nanVec, + assert(Gz::Math::Vector3d.Zero == nanVec, "Corrected vector should equal zero") - nanVecF = Ignition::Math::Vector3f.NaN + nanVecF = Gz::Math::Vector3f.NaN assert(!nanVecF.IsFinite(), "NaN vector shouldn't be finite") assert(nanVecF.X().nan?, "X should be NaN") @@ -461,7 +461,7 @@ def test_nan assert(nanVecF.Z().nan?, "Z should be NaN") nanVecF.Correct() - assert(Ignition::Math::Vector3f.Zero == nanVecF, + assert(Gz::Math::Vector3f.Zero == nanVecF, "Corrected vector should equal zero") end end diff --git a/src/ruby/Vector4.i b/src/ruby/Vector4.i index 1cd8f0287..a45386939 100644 --- a/src/ruby/Vector4.i +++ b/src/ruby/Vector4.i @@ -26,7 +26,7 @@ #include %} -namespace ignition +namespace gz { namespace math { @@ -38,15 +38,15 @@ namespace ignition public: %extend { static Vector4 Zero() { - return ignition::math::Vector4::Zero; + return gz::math::Vector4::Zero; } static Vector4 One() { - return ignition::math::Vector4::One; + return gz::math::Vector4::One; } static Vector4 NaN() { - return ignition::math::Vector4::NaN; + return gz::math::Vector4::NaN; } } public: Vector4(); diff --git a/src/ruby/Vector4_TEST.rb b/src/ruby/Vector4_TEST.rb index c594bcc16..6b64f813c 100644 --- a/src/ruby/Vector4_TEST.rb +++ b/src/ruby/Vector4_TEST.rb @@ -21,7 +21,7 @@ class Vector4_TEST < Test::Unit::TestCase def test_construction - v = Ignition::Math::Vector4d.new + v = Gz::Math::Vector4d.new # ::operator== vector4 assert(true, @@ -29,48 +29,48 @@ def test_construction # ::Distance, ::Length() v.Set(1, 2, 3, 4) - assert(v.Length() == v.Distance(Ignition::Math::Vector4d.Zero), + assert(v.Length() == v.Distance(Gz::Math::Vector4d.Zero), "Vector4d::Lenth() should equal Vector4d::Distance(zero)") # ::operator/ vector4 v.Set(4, 4, 4, 4) - v = v / Ignition::Math::Vector4d.new(1, 2, 2, 4) - assert(v == Ignition::Math::Vector4d.new(4, 2, 2, 1), + v = v / Gz::Math::Vector4d.new(1, 2, 2, 4) + assert(v == Gz::Math::Vector4d.new(4, 2, 2, 1), "v / Vector4d(1, 2, 2, 4) should equal Vector4d(4, 2, 2, 1)") # ::operator / double v = v / 2 - assert(v == Ignition::Math::Vector4d.new(2, 1, 1, 0.5), + assert(v == Gz::Math::Vector4d.new(2, 1, 1, 0.5), "v / 2 should equal Vector4d(2, 1, 1, .5)") # ::operator * vector4 - v = v * Ignition::Math::Vector4d.new(2, 3, 3, 4) - assert(v == Ignition::Math::Vector4d.new(4, 3, 3, 2), + v = v * Gz::Math::Vector4d.new(2, 3, 3, 4) + assert(v == Gz::Math::Vector4d.new(4, 3, 3, 2), "v * Vector4d(2, 3, 3, 4) should equal Vector4d(4, 3, 3, 2)") # operator /= v.Set(1, 2, 2, 4) - v /= Ignition::Math::Vector4d.new(1, 4, 8, 4) - assert(v == Ignition::Math::Vector4d.new(1, 0.5, 0.25, 1)) + v /= Gz::Math::Vector4d.new(1, 4, 8, 4) + assert(v == Gz::Math::Vector4d.new(1, 0.5, 0.25, 1)) # operator *= v.Set(1, 2, 2, 4) - v *= Ignition::Math::Vector4d.new(2, 0.5, 0.25, 0.1) - assert(v == Ignition::Math::Vector4d.new(2, 1, 0.5, 0.4)) + v *= Gz::Math::Vector4d.new(2, 0.5, 0.25, 0.1) + assert(v == Gz::Math::Vector4d.new(2, 1, 0.5, 0.4)) # Test the static defines. - assert(Ignition::Math::Vector4d.Zero == - Ignition::Math::Vector4d.new(0, 0, 0, 0), + assert(Gz::Math::Vector4d.Zero == + Gz::Math::Vector4d.new(0, 0, 0, 0), "Vector4d::Zero should equal [0, 0, 0, 0]") - assert(Ignition::Math::Vector4d.One == - Ignition::Math::Vector4d.new(1, 1, 1, 1), + assert(Gz::Math::Vector4d.One == + Gz::Math::Vector4d.new(1, 1, 1, 1), "Vector4d::One should equal [1, 1, 1, 1]") end def test_distance - vec1 = Ignition::Math::Vector4d.new(0, 0, 0, 0) - vec2 = Ignition::Math::Vector4d.new(1, 2, 3, 4) + vec1 = Gz::Math::Vector4d.new(0, 0, 0, 0) + vec2 = Gz::Math::Vector4d.new(1, 2, 3, 4) dist = vec1.Distance(vec2) assert((dist - 5.47722557505).abs() < 1e-6, @@ -78,8 +78,8 @@ def test_distance end def test_squared_length - vec1 = Ignition::Math::Vector4d.new(0, 0, 0, 0) - vec2 = Ignition::Math::Vector4d.new(1, 2, 3, 4) + vec1 = Gz::Math::Vector4d.new(0, 0, 0, 0) + vec2 = Gz::Math::Vector4d.new(1, 2, 3, 4) sum1 = vec1.SquaredLength() sum2 = vec2.SquaredLength() @@ -90,21 +90,21 @@ def test_squared_length def test_length # Zero vector - assert(Ignition::Math::Vector4d.Zero.Length() == 0.0, + assert(Gz::Math::Vector4d.Zero.Length() == 0.0, "Vector4 length of [0, 0, 0, 0] should equal 0") - assert(Ignition::Math::Vector4d.Zero.SquaredLength() == 0.0, + assert(Gz::Math::Vector4d.Zero.SquaredLength() == 0.0, "Vector4 squared length of [0, 0, 0, 0] should equal 0") # One vector - assert((Ignition::Math::Vector4d.One.Length() - + assert((Gz::Math::Vector4d.One.Length() - Math.sqrt(4.0)).abs() < 1e-10, "Vector4 length of [1, 1, 1, 1] should equal sqrt(4.0)") - assert(Ignition::Math::Vector4d.One.SquaredLength() == 4.0, + assert(Gz::Math::Vector4d.One.SquaredLength() == 4.0, "Vector4 squared lenght of [1, 1, 1, 1] should equal 4.0") # Arbitrary vector - v = Ignition::Math::Vector4d.new(0.1, -4.2, 2.5, -1.2) + v = Gz::Math::Vector4d.new(0.1, -4.2, 2.5, -1.2) assert((v.Length() - 5.03388517946).abs() < 1e-10, "Vector4 v length should equal 5.03388517946") @@ -113,31 +113,31 @@ def test_length end def test_normalize - vec1 = Ignition::Math::Vector4d.new(0, 0, 0, 0) - vec2 = Ignition::Math::Vector4d.new(1, 2, 3, 4) + vec1 = Gz::Math::Vector4d.new(0, 0, 0, 0) + vec2 = Gz::Math::Vector4d.new(1, 2, 3, 4) vec3 = vec1 vec3.Normalize() assert(vec3 == vec1, "Vector4 vec3 should equal vec1") - assert(vec1 == Ignition::Math::Vector4d.Zero, + assert(vec1 == Gz::Math::Vector4d.Zero, "Vector4 should equal [0, 0, 0, 0]") vec3 = vec2 vec2.Normalize() - assert(vec2.Equal(Ignition::Math::Vector4d.new(0.182575, 0.365150, 0.547725, 0.730300), 1e-5), + assert(vec2.Equal(Gz::Math::Vector4d.new(0.182575, 0.365150, 0.547725, 0.730300), 1e-5), "Vector4 vec3 should equal [0.182575, 0.365150, 0.547725, 0.730300]") end def test_add - vec1 = Ignition::Math::Vector4d.new(0.1, 0.2, 0.4, 0.8) - vec2 = Ignition::Math::Vector4d.new(1.1, 2.2, 3.4, 4.3) + vec1 = Gz::Math::Vector4d.new(0.1, 0.2, 0.4, 0.8) + vec2 = Gz::Math::Vector4d.new(1.1, 2.2, 3.4, 4.3) vec3 = vec1 vec3 += vec2 - assert(vec1 + vec2 == Ignition::Math::Vector4d.new(1.2, 2.4, 3.8, 5.1), + assert(vec1 + vec2 == Gz::Math::Vector4d.new(1.2, 2.4, 3.8, 5.1), "Vector4 vec1 + vec2 should equal [1.2, 2.4, 3.8, 4.9]") - assert(vec3 == Ignition::Math::Vector4d.new(1.2, 2.4, 3.8, 5.1), + assert(vec3 == Gz::Math::Vector4d.new(1.2, 2.4, 3.8, 5.1), "Vector4 vec3 should equal [1.2, 2.4, 3.8, 4.9]") # Addition with zeros @@ -146,38 +146,38 @@ def test_add assert(vec1 + 0 == vec1, "Vector4 vec1+0 should equal vec1") # Vector left and right - assert(Ignition::Math::Vector4d.Zero + vec1 == vec1, + assert(Gz::Math::Vector4d.Zero + vec1 == vec1, "Vector4 Zero + vec1 should equal vec1") - assert(vec1 + Ignition::Math::Vector4d.Zero == vec1, + assert(vec1 + Gz::Math::Vector4d.Zero == vec1, "Vector4 vec1 + Zero should equal vec1") # Addition assignment vec4 = vec1 vec4 += 0 assert(vec4 == vec1, "Vector4 vec4 should equal vec1") - vec4 += Ignition::Math::Vector4d.Zero + vec4 += Gz::Math::Vector4d.Zero assert(vec4 == vec1, "Vector4 vec4 should equal vec1") # Add non-trivial scalar values left and right - assert(vec1 + 2.5 == Ignition::Math::Vector4d.new(2.6, 2.7, 2.9, 3.3), + assert(vec1 + 2.5 == Gz::Math::Vector4d.new(2.6, 2.7, 2.9, 3.3), "Vector4 vec1 + 2.5 should equal [2.6, 2.7, 2.9, 3.3]") vec1 = vec4 vec4 += 2.5 - assert(vec4 == Ignition::Math::Vector4d.new(2.6, 2.7, 2.9, 3.3), + assert(vec4 == Gz::Math::Vector4d.new(2.6, 2.7, 2.9, 3.3), "Vector4 vec4 should equal [2.6, 2.7, 2.9, 3.3]") end def test_sub - vec1 = Ignition::Math::Vector4d.new(0.1, 0.2, 0.4, 0.8) - vec2 = Ignition::Math::Vector4d.new(1.1, 2.2, 3.4, 4.3) + vec1 = Gz::Math::Vector4d.new(0.1, 0.2, 0.4, 0.8) + vec2 = Gz::Math::Vector4d.new(1.1, 2.2, 3.4, 4.3) vec3 = vec2 vec3 -= vec1 - assert(vec2 - vec1 === Ignition::Math::Vector4d.new(1.0, 2.0, 3.0, 3.5), + assert(vec2 - vec1 === Gz::Math::Vector4d.new(1.0, 2.0, 3.0, 3.5), "Vector4 vec2 - vec1 should equal [1.0, 2.0, 3.0, 3.5]") - assert(vec3 == Ignition::Math::Vector4d.new(1.0, 2.0, 3.0, 3.5), + assert(vec3 == Gz::Math::Vector4d.new(1.0, 2.0, 3.0, 3.5), "Vector4 vec3 should equal [1.0, 2.0, 3.0, 3.5]") # Subtraction with zeros @@ -186,59 +186,59 @@ def test_sub assert(vec1 - 0 == vec1, "Vector4 vec1 - 0 should equal vec1") # Vector left and right - assert(Ignition::Math::Vector4d.Zero - vec1 == -vec1, + assert(Gz::Math::Vector4d.Zero - vec1 == -vec1, "Vector4 Zero - vec1 should equal -vec1") - assert(vec1 - Ignition::Math::Vector4d.Zero == vec1, + assert(vec1 - Gz::Math::Vector4d.Zero == vec1, "Vector4 vec1 - Zero should equal vec1") # Subtraction assignment vec4 = vec1 vec4 -= 0 assert(vec4 == vec1, "Vector4 vec4 should equal vec1") - vec4 -= Ignition::Math::Vector4d.Zero + vec4 -= Gz::Math::Vector4d.Zero assert(vec4 == vec1, "Vector4 vec4 should equal vec1") # Subtract non-trivial scalar values left and right - assert(vec1 - 2.5 == -Ignition::Math::Vector4d.new(2.4, 2.3, 2.1, 1.7), + assert(vec1 - 2.5 == -Gz::Math::Vector4d.new(2.4, 2.3, 2.1, 1.7), "Vecetor3 vec1 - 2.5 should equal [2.4, 2.3, 2.1, 1.7]") vec4 = vec1 vec4 -= 2.5 - assert(vec4 == -Ignition::Math::Vector4d.new(2.4, 2.3, 2.1, 1.7), + assert(vec4 == -Gz::Math::Vector4d.new(2.4, 2.3, 2.1, 1.7), "Vector4 vec4 - 2.5 should equal [2.4, 2.3, 2.1, 1.7]") end def test_divide - vec1 = Ignition::Math::Vector4d.new(0.1, 0.2, 0.4, 0.8) + vec1 = Gz::Math::Vector4d.new(0.1, 0.2, 0.4, 0.8) vec3 = vec1 / 2.0 - assert(vec3 == Ignition::Math::Vector4d.new(0.05, 0.1, 0.2, 0.4), + assert(vec3 == Gz::Math::Vector4d.new(0.05, 0.1, 0.2, 0.4), "Vector4 vec3 should equal [0.05, 0.1, 0.2, 0.4]") vec3 /= 4.0 - assert(vec3 == Ignition::Math::Vector4d.new(0.0125, 0.025, 0.05, 0.1), + assert(vec3 == Gz::Math::Vector4d.new(0.0125, 0.025, 0.05, 0.1), "Vector4 vec3 should qual [0.0125, 0.025, 0.05, 0.1]") end def test_multiply - v = Ignition::Math::Vector4d.new(0.1, 0.2, 0.3, 0.4) + v = Gz::Math::Vector4d.new(0.1, 0.2, 0.3, 0.4) vec3 = v * 2.0 - assert(vec3 == Ignition::Math::Vector4d.new(0.2, 0.4, 0.6, 0.8), + assert(vec3 == Gz::Math::Vector4d.new(0.2, 0.4, 0.6, 0.8), "Vector4 vec3 should equal[0.2, 0.4, 0.6, 0.8]") vec3 *= 4.0 - assert(vec3 == Ignition::Math::Vector4d.new(0.8, 1.6, 2.4, 3.2), + assert(vec3 == Gz::Math::Vector4d.new(0.8, 1.6, 2.4, 3.2), "Vector4 vec3 should equal [0.8, 1.6, 2.4, 3.2]") # Multiply by zero # Scalar left and right - assert(v * 0 == Ignition::Math::Vector4d.Zero, + assert(v * 0 == Gz::Math::Vector4d.Zero, "Vector4 v * 0 should equal Zero") # Element-wise vector multiplication - assert(v * Ignition::Math::Vector4d.Zero == Ignition::Math::Vector4d.Zero, + assert(v * Gz::Math::Vector4d.Zero == Gz::Math::Vector4d.Zero, "Vector4 v * Zero should equal Zero") # Multiply by one @@ -247,57 +247,57 @@ def test_multiply assert(v * 1 == v, "Vector4 v * 1 should equal v") # Element-wise vector multiplication - assert(v * Ignition::Math::Vector4d.One == v, + assert(v * Gz::Math::Vector4d.One == v, "Vector4 v * One should equal v") # Multiply by non-trivial scalar value scalar = 2.5 - expect = Ignition::Math::Vector4d.new(0.25, 0.5, 0.75, 1.0) + expect = Gz::Math::Vector4d.new(0.25, 0.5, 0.75, 1.0) assert(v * scalar == expect, "Vector4 v * scalar should equal [0.25, 0.5, 0.75, 1.0]") # Multiply by itself element-wise - assert(v*v == Ignition::Math::Vector4d.new(0.01, 0.04, 0.09, 0.16), + assert(v*v == Gz::Math::Vector4d.new(0.01, 0.04, 0.09, 0.16), "Vector4 v * v should euqal [0.01, 0.04, 0.09, 0.16]") end def test_not_equal - vec1 = Ignition::Math::Vector4d.new(0.1, 0.2, 0.3, 0.4) - vec2 = Ignition::Math::Vector4d.new(0.2, 0.2, 0.3, 0.4) - vec3 = Ignition::Math::Vector4d.new(0.1, 0.2, 0.3, 0.4) + vec1 = Gz::Math::Vector4d.new(0.1, 0.2, 0.3, 0.4) + vec2 = Gz::Math::Vector4d.new(0.2, 0.2, 0.3, 0.4) + vec3 = Gz::Math::Vector4d.new(0.1, 0.2, 0.3, 0.4) assert(vec1 != vec2, "Vector4 vec1 should not equal vec2") assert(!(vec1 != vec3), "Vector4 vec1 should equal vec3" ) end def test_equal - assert(!Ignition::Math::Vector4d.Zero.Equal( - Ignition::Math::Vector4d.One, 1e-6), + assert(!Gz::Math::Vector4d.Zero.Equal( + Gz::Math::Vector4d.One, 1e-6), "Vector4 Zero should not equal 1 with tolerance of 1e-6") - assert(!Ignition::Math::Vector4d.Zero.Equal( - Ignition::Math::Vector4d.One, 1e-3), + assert(!Gz::Math::Vector4d.Zero.Equal( + Gz::Math::Vector4d.One, 1e-3), "Vector4 Zero should not equal 1 with tolerance of 1e-3") - assert(!Ignition::Math::Vector4d.Zero.Equal( - Ignition::Math::Vector4d.One, 1e-1), + assert(!Gz::Math::Vector4d.Zero.Equal( + Gz::Math::Vector4d.One, 1e-1), "Vector4 Zero should not equal 1 with tolerance of 1e-1") - assert(Ignition::Math::Vector4d.Zero.Equal( - Ignition::Math::Vector4d.One, 1), + assert(Gz::Math::Vector4d.Zero.Equal( + Gz::Math::Vector4d.One, 1), "Vector4 Zero should equal 1 with tolerance of 1") - assert(Ignition::Math::Vector4d.Zero.Equal( - Ignition::Math::Vector4d.One, 1.1), + assert(Gz::Math::Vector4d.Zero.Equal( + Gz::Math::Vector4d.One, 1.1), "Vector4 Zero should equal 1 with tolerance of 1.1") end def test_finite - vec1 = Ignition::Math::Vector4d.new(0.1, 0.2, 0.3, 0.4) + vec1 = Gz::Math::Vector4d.new(0.1, 0.2, 0.3, 0.4) assert(vec1.IsFinite(), "Vector4 vec1 should be be finite") end def test_nan - nanVec = Ignition::Math::Vector4d.NaN + nanVec = Gz::Math::Vector4d.NaN assert(!nanVec.IsFinite(), "NaN vector shouldn't be finite") assert(nanVec.X().nan?, "X should be NaN") @@ -306,10 +306,10 @@ def test_nan assert(nanVec.W().nan?, "W should be NaN") nanVec.Correct() - assert(Ignition::Math::Vector4d.Zero == nanVec, + assert(Gz::Math::Vector4d.Zero == nanVec, "Corrected vector should equal zero") - nanVecF = Ignition::Math::Vector4f.NaN + nanVecF = Gz::Math::Vector4f.NaN assert(!nanVecF.IsFinite(), "NaN vector shouldn't be finite") assert(nanVecF.X().nan?, "X should be NaN") @@ -318,7 +318,7 @@ def test_nan assert(nanVecF.W().nan?, "W should be NaN") nanVecF.Correct() - assert(Ignition::Math::Vector4f.Zero == nanVecF, + assert(Gz::Math::Vector4f.Zero == nanVecF, "Corrected vector should equal zero") end end diff --git a/src/ruby/ruby.i b/src/ruby/ruby.i index 31168b833..301e98f73 100644 --- a/src/ruby/ruby.i +++ b/src/ruby/ruby.i @@ -1,4 +1,4 @@ -%module "ignition::math" +%module "gz::math" %include Angle.i %include GaussMarkovProcess.i %include Rand.i diff --git a/src/ruby/ruby_TEST.rb b/src/ruby/ruby_TEST.rb index 9951917d5..4b329efee 100644 --- a/src/ruby/ruby_TEST.rb +++ b/src/ruby/ruby_TEST.rb @@ -23,19 +23,19 @@ class Ruby_TEST < Test::Unit::TestCase # This test just uses a few classes to make sure multiple ruby interfaces # work together. def test_construction - angle1 = Ignition::Math::Angle.new + angle1 = Gz::Math::Angle.new assert(angle1.Radian() == 0.0, "Angle::Radian() should equal zero") - v = Ignition::Math::Vector3d.new + v = Gz::Math::Vector3d.new # ::Distance, ::Length() v.Set(1, 2, 3) - assert(v.Length() == v.Distance(Ignition::Math::Vector3d.Zero), + assert(v.Length() == v.Distance(Gz::Math::Vector3d.Zero), "Vector3d::Lenth() should equal Vector3d::Distance(zero)") - v2 = Ignition::Math::Vector2d.new(1, 2) + v2 = Gz::Math::Vector2d.new(1, 2) assert(v2.X == 1, "v2.X should equal 1") assert(v2.Y == 2, "v2.Y should equal 2") end diff --git a/test/integration/ExamplesBuild_TEST.cc b/test/integration/ExamplesBuild_TEST.cc index 486e2491b..5149297c4 100644 --- a/test/integration/ExamplesBuild_TEST.cc +++ b/test/integration/ExamplesBuild_TEST.cc @@ -23,18 +23,18 @@ #include "test_config.h" // NOLINT(build/include) #ifdef _WIN32 -# define IGN_PATH_MAX _MAX_PATH +# define GZ_PATH_MAX _MAX_PATH #elif defined(PATH_MAX) -# define IGN_PATH_MAX PATH_MAX +# define GZ_PATH_MAX PATH_MAX #elif defined(_XOPEN_PATH_MAX) -# define IGN_PATH_MAX _XOPEN_PATH_MAX +# define GZ_PATH_MAX _XOPEN_PATH_MAX #else -# define IGN_PATH_MAX _POSIX_PATH_MAX +# define GZ_PATH_MAX _POSIX_PATH_MAX #endif // Helper functions copied from -// https://github.com/ignitionrobotics/ign-common/raw/ign-common3/src/Filesystem_TEST.cc +// https://github.com/gazebosim/gz-common/raw/ign-common3/src/Filesystem_TEST.cc #ifndef _WIN32 #include // NOLINT(build/include_order) diff --git a/test/integration/all_symbols_have_version.bash.in b/test/integration/all_symbols_have_version.bash.in index 9be67a78c..f95072554 100644 --- a/test/integration/all_symbols_have_version.bash.in +++ b/test/integration/all_symbols_have_version.bash.in @@ -5,7 +5,7 @@ VERSIONED_NS=v@PROJECT_VERSION_MAJOR@ IGN_PROJECT=@IGN_DESIGNATION@ # Sanity check - there should be at least one symbol -NUM_SYMBOLS=$(nm $LIBPATH | grep -e "ignition.*$IGN_PROJECT" | wc -l) +NUM_SYMBOLS=$(nm $LIBPATH | grep -e "gz.*$IGN_PROJECT" | wc -l) if [ $NUM_SYMBOLS -eq 0 ] then @@ -14,7 +14,7 @@ then fi # There must be no unversioned symbols -UNVERSIONED_SYMBOLS=$(nm $LIBPATH | grep -e "ignition.*$IGN_PROJECT" | grep -e "$VERSIONED_NS" -v) +UNVERSIONED_SYMBOLS=$(nm $LIBPATH | grep -e "gz.*$IGN_PROJECT" | grep -e "$VERSIONED_NS" -v) UNVERSIONED_SYMBOL_CHARS=$(printf "$UNVERSIONED_SYMBOLS" | wc -m) if [ $UNVERSIONED_SYMBOL_CHARS -ne 0 ] diff --git a/test/integration/deprecated_TEST.cc b/test/integration/deprecated_TEST.cc new file mode 100644 index 000000000..9407ad9bf --- /dev/null +++ b/test/integration/deprecated_TEST.cc @@ -0,0 +1,32 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include + +#define SUPPRESS_IGNITION_HEADER_DEPRECATION + +#include +#include + +///////////////////////////////////////////////// +// Make sure the ignition namespace still works +TEST(Deprecated, IgnitionNamespace) +{ + ignition::math::Angle angle; +} + +#undef SUPPRESS_IGNITION_HEADER_DEPRECATION diff --git a/tutorials/angle.md b/tutorials/angle.md index dd8327807..2890bb301 100644 --- a/tutorials/angle.md +++ b/tutorials/angle.md @@ -1,6 +1,6 @@ \page angle Angle example -This tutorial explains how to use the `Angle` class from Ignition Math library. +This tutorial explains how to use the `Angle` class from Gazebo Math library. ## C++ example @@ -9,7 +9,7 @@ This tutorial explains how to use the `Angle` class from Ignition Math library. Go to `ign-math/examples` and use `cmake` to compile the code: ```{.sh} -git clone https://github.com/ignitionrobotics/ign-math/ -b main +git clone https://github.com/gazebosim/gz-math/ -b main cd ign-math/examples mkdir build cd build @@ -57,7 +57,7 @@ Use the method `Normalized` to bound the value between `-PI` and `PI`. ## Ruby example -This example will only work if the Ruby interface library was compiled and installed. Modify the `RUBYLIB` environment variable to include the Ignition Math library install path. For example, if you install to `/usr`: +This example will only work if the Ruby interface library was compiled and installed. Modify the `RUBYLIB` environment variable to include the Gazebo Math library install path. For example, if you install to `/usr`: ```{.sh} export RUBYLIB=/usr/lib/ruby:$RUBYLIB @@ -74,14 +74,14 @@ ruby angle_example.rb There are some predefined values: ```{.rb} -printf("PI in degrees = %f\n", Ignition::Math::Angle.Pi.Degree) +printf("PI in degrees = %f\n", Gz::Math::Angle.Pi.Degree) ``` Create new objects: ```{.rb} -a1 = Ignition::Math::Angle.new(1.5707) -a2 = Ignition::Math::Angle.new(0.7854) +a1 = Gz::Math::Angle.new(1.5707) +a2 = Gz::Math::Angle.new(0.7854) ``` Use the values in radians or degrees: @@ -102,7 +102,7 @@ printf("a1 - a2 = %f radians, %f degrees\n", (a1 - a2).Radian, (a1 - a2).Degree) Normalize the value between `-PI` and `PI`. ```{.rb} -a3 = Ignition::Math::Angle.new(15.707) +a3 = Gz::Math::Angle.new(15.707) printf("a3 = %f radians, %f degrees\n", a3.Radian, a3.Degree) a3.Normalize printf("a3.Normalize = %f radians, %f degrees\n", a3.Radian, a3.Degree) diff --git a/tutorials/color.md b/tutorials/color.md index 076eca46c..c038f4dbf 100644 --- a/tutorials/color.md +++ b/tutorials/color.md @@ -1,13 +1,13 @@ \page color Color example -This tutorial explains how to use the `Color` class from Ignition Math library. +This tutorial explains how to use the `Color` class from Gazebo Math library. ## Compile the code Go to `ign-math/examples` and use `cmake` to compile the code: ```{.sh} -git clone https://github.com/ignitionrobotics/ign-math/ -b ign-math7 +git clone https://github.com/gazebosim/gz-math/ -b ign-math7 cd ign-math/examples mkdir build cd build @@ -54,5 +54,5 @@ You can also set or read a color in HSV. \snippet examples/color_example.cc Set value from HSV -There are more functions in `Color`. Take a look at the [API](https://ignitionrobotics.org/api/math/6.9/classignition_1_1math_1_1Color.html) +There are more functions in `Color`. Take a look at the [API](https://gazebosim.org/api/math/6.9/classignition_1_1math_1_1Color.html) diff --git a/tutorials/cppgetstarted.md b/tutorials/cppgetstarted.md index c9f1fed20..467cf576f 100644 --- a/tutorials/cppgetstarted.md +++ b/tutorials/cppgetstarted.md @@ -4,7 +4,7 @@ Previous Tutorial: \ref install ## Overview -This tutorial describes how to get started using Ignition Math with C++. +This tutorial describes how to get started using Gazebo Math with C++. We will run through an example that determines the distance between two points in 3D space. Start by creating a bare-bones main file using the @@ -17,7 +17,7 @@ int main() } ``` -The easiest way to include Ignition Math is through the `ignition/math.hh` +The easiest way to include Gazebo Math is through the `ignition/math.hh` header file. Alternatively, you can include only the header files you need. For this example, we'll take the short and easy approach. @@ -33,8 +33,8 @@ int main() ``` Now let's create to 3D points with arbitrary values. We will use the -ignition::math::Vector3 class to represent these points. Ignition Math provides a handy -ignition::math::Vector3d type which is a typedef of `Vector3`. The result of this +gz::math::Vector3 class to represent these points. Gazebo Math provides a handy +gz::math::Vector3d type which is a typedef of `Vector3`. The result of this addition will be a main file similar to the following. ```{.cpp} @@ -42,23 +42,23 @@ addition will be a main file similar to the following. int main() { - ignition::math::Vector3d point1(1, 3, 5); - ignition::math::Vector3d point2(2, 4, 6); + gz::math::Vector3d point1(1, 3, 5); + gz::math::Vector3d point2(2, 4, 6); return 0; } ``` Finally, we can compute the distance between `point1` and `point2` using the -ignition::math::Vector3::Distance() function and output the distance value. +gz::math::Vector3::Distance() function and output the distance value. ```{.cpp} #include int main() { - ignition::math::Vector3d point1(1, 3, 5); - ignition::math::Vector3d point2(2, 4, 6); + gz::math::Vector3d point1(1, 3, 5); + gz::math::Vector3d point2(2, 4, 6); double distance = point1.Distance(point2); std::cout << "Distance from " << point1 << " to " << point2 << " is " << diff --git a/tutorials/example_angle.md b/tutorials/example_angle.md index 38764dcd5..eee8bc7a9 100644 --- a/tutorials/example_angle.md +++ b/tutorials/example_angle.md @@ -1,6 +1,6 @@ \page example_angle Angle example -This tutorial explains how to use the `Angle` class from Ignition Math library. +This tutorial explains how to use the `Angle` class from Gazebo Math library. ## C++ example @@ -9,7 +9,7 @@ This tutorial explains how to use the `Angle` class from Ignition Math library. Go to `ign-math/examples` and use `cmake` to compile the code: ```{.sh} -git clone https://github.com/ignitionrobotics/ign-math/ -b master +git clone https://github.com/gazebosim/gz-math/ -b master cd ign-math/examples mkdir build cd build @@ -57,7 +57,7 @@ Use the method `Normalized` to bound the value between `-PI` and `PI`. ## Ruby example -This example will only work if the Ruby interface library was compiled and installed. Modify the `RUBYLIB` environment variable to include the Ignition Math library install path. For example, if you install to `/usr`: +This example will only work if the Ruby interface library was compiled and installed. Modify the `RUBYLIB` environment variable to include the Gazebo Math library install path. For example, if you install to `/usr`: ```{.sh} export RUBYLIB=/usr/lib/ruby:$RUBYLIB @@ -74,14 +74,14 @@ ruby angle_example.rb There are some predefined values: ```{.rb} -printf("PI in degrees = %f\n", Ignition::Math::Angle.Pi.Degree) +printf("PI in degrees = %f\n", Gz::Math::Angle.Pi.Degree) ``` Create new objects: ```{.rb} -a1 = Ignition::Math::Angle.new(1.5707) -a2 = Ignition::Math::Angle.new(0.7854) +a1 = Gz::Math::Angle.new(1.5707) +a2 = Gz::Math::Angle.new(0.7854) ``` Use the values in radians or degrees: @@ -102,7 +102,7 @@ printf("a1 - a2 = %f radians, %f degrees\n", (a1 - a2).Radian, (a1 - a2).Degree) Normalize the value between `-PI` and `PI`. ```{.rb} -a3 = Ignition::Math::Angle.new(15.707) +a3 = Gz::Math::Angle.new(15.707) printf("a3 = %f radians, %f degrees\n", a3.Radian, a3.Degree) a3.Normalize printf("a3.Normalize = %f radians, %f degrees\n", a3.Radian, a3.Degree) diff --git a/tutorials/example_triangle.md b/tutorials/example_triangle.md index 5d6bf4dd2..8089af7ab 100644 --- a/tutorials/example_triangle.md +++ b/tutorials/example_triangle.md @@ -1,13 +1,13 @@ \page example_triangle Triangle example -This tutorial explains how to use the `Triangle` class from Ignition Math library. +This tutorial explains how to use the `Triangle` class from Gazebo Math library. ## Compile the code Go to `ign-math/examples` and use `cmake` to compile the code: ```{.sh} -git clone https://github.com/ignitionrobotics/ign-math/ -b master +git clone https://github.com/gazebosim/gz-math/ -b master cd ign-math/examples mkdir build cd build @@ -69,4 +69,4 @@ The `Intersects` function checks if a line segment intersects the triangle. It a \snippet examples/triangle_example.cc intersect -There are more functions in `Triangle`. Take a look at the [API](https://ignitionrobotics.org/api/math/6.4/index.html) +There are more functions in `Triangle`. Take a look at the [API](https://gazebosim.org/api/math/6.4/index.html) diff --git a/tutorials/example_vector2.md b/tutorials/example_vector2.md index 0fc600554..60b48ee30 100644 --- a/tutorials/example_vector2.md +++ b/tutorials/example_vector2.md @@ -1,6 +1,6 @@ \page example_vector2 Vector example -This tutorial explains how to use the `Vector` class from Ignition Math library. +This tutorial explains how to use the `Vector` class from Gazebo Math library. ## C++ example @@ -9,7 +9,7 @@ This tutorial explains how to use the `Vector` class from Ignition Math library. To compile the code, go to `ign-math/examples` and use `cmake`: ```{.sh} -git clone https://github.com/ignitionrobotics/ign-math/ -b master +git clone https://github.com/gazebosim/gz-math/ -b master cd ign-math/examples mkdir build cd build @@ -47,7 +47,7 @@ Create a `Vector2` called `vec2` of doubles using the typedef `Vector2d`. **The \snippet examples/vector2_example.cc constructor -The `Vector2` class is a template, so you can also create a `Vector2` using `ignition::math::Vector2`: +The `Vector2` class is a template, so you can also create a `Vector2` using `gz::math::Vector2`: \snippet examples/vector2_example.cc constructor2 @@ -71,11 +71,11 @@ There are also many useful function such as finding the distance between two vec \snippet examples/vector2_example.cc distance -**There are more functions in Vector2. Take a look at the [API](https://ignitionrobotics.org/libs/math)** +**There are more functions in Vector2. Take a look at the [API](https://gazebosim.org/libs/math)** ## Ruby examples -This example will only work if the Ruby interface library was compiled and installed. Modify the `RUBYLIB` environment variable to include the Ignition Math library install path. For example, if you install to `/usr`: +This example will only work if the Ruby interface library was compiled and installed. Modify the `RUBYLIB` environment variable to include the Gazebo Math library install path. For example, if you install to `/usr`: ```{.sh} export RUBYLIB=/usr/lib/ruby:$RUBYLIB @@ -93,7 +93,7 @@ ruby vector3_example.rb Create a `Vector2` of doubles using the typedef `Vector2d`. It's possible to set initial values or use another object to create a identical copy. ```{.rb} -va = Ignition::Math::Vector2d.new(1, 2) +va = Gz::Math::Vector2d.new(1, 2) ``` You can get access to each component in the vector using the `X()`, `Y()` accessors. @@ -122,7 +122,7 @@ printf("vb.Distance(va) = %f\n", vb.Distance(va)) You can create vectors with 3 dimensions using the typedef `Vector3d`: ```{.rb} -v1 = Ignition::Math::Vector3d.new(0, 0, 0) +v1 = Gz::Math::Vector3d.new(0, 0, 0) ``` You can also get access to each component in the vector using the `X()`, `Y()` and `Z()` accessors: diff --git a/tutorials/installation.md b/tutorials/installation.md index 2f7b43cdf..d29bb9793 100644 --- a/tutorials/installation.md +++ b/tutorials/installation.md @@ -2,8 +2,8 @@ Next Tutorial: \ref cppgetstarted -These instructions are for installing only Ignition Math. -If you're interested in using all the Ignition libraries, check out this [Ignition installation](https://ignitionrobotics.org/docs/latest/install). +These instructions are for installing only Gazebo Math. +If you're interested in using all the Ignition libraries, check out this [Ignition installation](https://gazebosim.org/docs/latest/install). We recommend following the Binary Installation instructions to get up and running as quickly and painlessly as possible. @@ -24,7 +24,7 @@ Setup keys: wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add - ``` -Install Ignition Math: +Install Gazebo Math: ``` sudo apt install libignition-math<#>-dev ``` @@ -40,7 +40,7 @@ On macOS, add OSRF packages: brew tap osrf/simulation ``` -Install Ignition Math: +Install Gazebo Math: ``` brew install ignition-math<#> ``` @@ -74,20 +74,20 @@ prerequisites followed by building from source. ## Prerequisites -Ignition Math requires: +Gazebo Math requires: -* [Ignition CMake](https://ignitionrobotics.org/libs/cmake) +* [Gazebo CMake](https://gazebosim.org/libs/cmake) ### Ubuntu Linux -The optional Eigen component of Ignition Math requires: +The optional Eigen component of Gazebo Math requires: * [Eigen](http://eigen.tuxfamily.org/index.php?title=Main_Page). Refer to the [Eigen Documentation](http://eigen.tuxfamily.org/index.php?title=Main_Page#Documentation) for installation instructions. On Ubuntu systems, `apt-get` can be used to install Eigen: ``` sudo apt-get install libeigen3-dev ``` -The optional Ruby tests of Ignition Math require: +The optional Ruby tests of Gazebo Math require: * [Ruby](https://www.ruby-lang.org/). Refer to the [Ruby Documentation](https://www.ruby-lang.org/downloads/) for installation instructions. On Ubuntu systems `apt-get` can be used to install Ubuntu Package `ruby-dev`: ``` @@ -101,9 +101,9 @@ The optional Ruby tests of Ignition Math require: ### Windows 10 -First, follow the [ign-cmake](https://github.com/ignitionrobotics/ign-cmake) tutorial for installing Conda, Visual Studio, CMake, and other prerequisites, and also for creating a Conda environment. +First, follow the [ign-cmake](https://github.com/gazebosim/gz-cmake) tutorial for installing Conda, Visual Studio, CMake, and other prerequisites, and also for creating a Conda environment. -The optional Eigen component of Ignition Math requires: +The optional Eigen component of Gazebo Math requires: * [Eigen](http://eigen.tuxfamily.org/index.php?title=Main_Page). Refer to the [Eigen Documentation](http://eigen.tuxfamily.org/index.php?title=Main_Page#Documentation) for installation instructions. On Windows, we will use `conda` to install Eigen: ``` @@ -127,7 +127,7 @@ The optional Eigen component of Ignition Math requires: 3. Clone the repository ``` - git clone https://github.com/ignitionrobotics/ign-math -b ign-math<#> + git clone https://github.com/gazebosim/gz-math -b ign-math<#> ``` Be sure to replace `<#>` with a number value, such as 1 or 2, depending on which version you need. @@ -150,7 +150,7 @@ The optional Eigen component of Ignition Math requires: 1. Clone the repository ``` - git clone https://github.com/ignitionrobotics/ign-math -b ign-math<#> + git clone https://github.com/gazebosim/gz-math -b ign-math<#> ``` Be sure to replace `<#>` with a number value, such as 1 or 2, depending on which version you need. @@ -200,7 +200,7 @@ The optional Eigen component of Ignition Math requires: 3. Navigate to where you would like to build the library, and clone the repository. ``` # Optionally, append `-b ign-math#` (replace # with a number) to check out a specific version - git clone https://github.com/ignitionrobotics/ign-math.git + git clone https://github.com/gazebosim/gz-math.git ``` 4. Configure and build @@ -219,7 +219,7 @@ The optional Eigen component of Ignition Math requires: # Documentation -API and tutorials can be found at [https://ignitionrobotics.org/libs/math](https://ignitionrobotics.org/libs/math). +API and tutorials can be found at [https://gazebosim.org/libs/math](https://gazebosim.org/libs/math). You can also generate the documentation from a clone of this repository by following these steps. @@ -230,7 +230,7 @@ You can also generate the documentation from a clone of this repository by follo 2. Clone the repository ``` - git clone https://github.com/ignitionrobotics/ign-math + git clone https://github.com/gazebosim/gz-math ``` 3. Configure and build the documentation. @@ -247,7 +247,7 @@ You can also generate the documentation from a clone of this repository by follo Follow these steps to run tests and static code analysis in your clone of this repository. -1. Follow the [source install instruction](https://ignitionrobotics.org/libs/math#source-install). +1. Follow the [source install instruction](https://gazebosim.org/libs/math#source-install). 2. Run tests. ``` diff --git a/tutorials/pythongetstarted.md b/tutorials/pythongetstarted.md index 81593dea0..16aca331b 100644 --- a/tutorials/pythongetstarted.md +++ b/tutorials/pythongetstarted.md @@ -4,9 +4,9 @@ Previous Tutorial: \ref cppgetstarted ## Overview -This tutorial describes how to get started using Ignition Math with Python. +This tutorial describes how to get started using Gazebo Math with Python. -**NOTE**: If you have compiled Ignition Math from source, you should export +**NOTE**: If you have compiled Gazebo Math from source, you should export your `PYTHONPATH`. ```bash @@ -25,7 +25,7 @@ if __name__ == "__main__": main() ``` -The easiest way to include Ignition Math is through `import ignition.math`. +The easiest way to include Gazebo Math is through `import ignition.math`. At this point your main file should look like @@ -40,7 +40,7 @@ if __name__ == "__main__": ``` Now let's create two 3D points with arbitrary values. We will use the -`ignition.math.Vector3` class to represent these points. Ignition Math provides +`ignition.math.Vector3` class to represent these points. Gazebo Math provides some `Vector3` types which are: `Vector3d` (Vector3 using doubles), `Vector3f` (Vector3 using floats) and `Vector3i` (Vector3 using integers). The result of this addition will be a main file similar to the following. diff --git a/tutorials/rotation.md b/tutorials/rotation.md index 32dde04de..1b862c726 100644 --- a/tutorials/rotation.md +++ b/tutorials/rotation.md @@ -7,7 +7,7 @@ This example explains how to use quaternions and euler angles, and how to conver Go to `ign-math/examples` and use `cmake` to compile the code: ```{.sh} -git clone https://github.com/ignitionrobotics/ign-math/ -b main +git clone https://github.com/gazebosim/gz-math/ -b main cd ign-math/examples mkdir build cd build diff --git a/tutorials/rotation_example.md b/tutorials/rotation_example.md index c64cb08c1..6ad30abbf 100644 --- a/tutorials/rotation_example.md +++ b/tutorials/rotation_example.md @@ -7,7 +7,7 @@ This example explains how to use quaternions and euler angles, and how to conver Go to `ign-math/examples` and use `cmake` to compile the code: ```{.sh} -git clone https://github.com/ignitionrobotics/ign-math/ -b master +git clone https://github.com/gazebosim/gz-math/ -b master cd ign-math/examples mkdir build cd build diff --git a/tutorials/triangle.md b/tutorials/triangle.md index 2b330b195..5379c48e5 100644 --- a/tutorials/triangle.md +++ b/tutorials/triangle.md @@ -1,13 +1,13 @@ \page triangle Triangle example -This tutorial explains how to use the `Triangle` class from Ignition Math library. +This tutorial explains how to use the `Triangle` class from Gazebo Math library. ## Compile the code Go to `ign-math/examples` and use `cmake` to compile the code: ```{.sh} -git clone https://github.com/ignitionrobotics/ign-math/ -b main +git clone https://github.com/gazebosim/gz-math/ -b main cd ign-math/examples mkdir build cd build @@ -69,4 +69,4 @@ The `Intersects` function checks if a line segment intersects the triangle. It a \snippet examples/triangle_example.cc intersect -There are more functions in `Triangle`. Take a look at the [API](https://ignitionrobotics.org/api/math/6.4/index.html) +There are more functions in `Triangle`. Take a look at the [API](https://gazebosim.org/api/math/6.4/index.html) diff --git a/tutorials/vector.md b/tutorials/vector.md index e0a315b8e..598cf32db 100644 --- a/tutorials/vector.md +++ b/tutorials/vector.md @@ -1,6 +1,6 @@ \page vector Vector example -This tutorial explains how to use the `Vector` classes from Ignition Math library. +This tutorial explains how to use the `Vector` classes from Gazebo Math library. ## C++ example @@ -9,7 +9,7 @@ This tutorial explains how to use the `Vector` classes from Ignition Math librar To compile the code, go to `ign-math/examples` and use `cmake`: ```{.sh} -git clone https://github.com/ignitionrobotics/ign-math/ -b main +git clone https://github.com/gazebosim/gz-math/ -b main cd ign-math/examples mkdir build cd build @@ -47,7 +47,7 @@ Create a `Vector2` called `vec2` of doubles using the typedef `Vector2d`. **The \snippet examples/vector2_example.cc constructor -The `Vector2` class is a template, so you can also create a `Vector2` using `ignition::math::Vector2`: +The `Vector2` class is a template, so you can also create a `Vector2` using `gz::math::Vector2`: \snippet examples/vector2_example.cc constructor2 @@ -71,11 +71,11 @@ There are also many useful function such as finding the distance between two vec \snippet examples/vector2_example.cc distance -**There are more functions in Vector2. Take a look at the [API](https://ignitionrobotics.org/libs/math)** +**There are more functions in Vector2. Take a look at the [API](https://gazebosim.org/libs/math)** ## Ruby examples -This example will only work if the Ruby interface library was compiled and installed. Modify the `RUBYLIB` environment variable to include the Ignition Math library install path. For example, if you install to `/usr`: +This example will only work if the Ruby interface library was compiled and installed. Modify the `RUBYLIB` environment variable to include the Gazebo Math library install path. For example, if you install to `/usr`: ```{.sh} export RUBYLIB=/usr/lib/ruby:$RUBYLIB @@ -93,7 +93,7 @@ ruby vector3_example.rb Create a `Vector2` of doubles using the typedef `Vector2d`. It's possible to set initial values or use another object to create a identical copy. ```{.rb} -va = Ignition::Math::Vector2d.new(1, 2) +va = Gz::Math::Vector2d.new(1, 2) ``` You can get access to each component in the vector using the `X()`, `Y()` accessors. @@ -122,7 +122,7 @@ printf("vb.Distance(va) = %f\n", vb.Distance(va)) You can create vectors with 3 dimensions using the typedef `Vector3d`: ```{.rb} -v1 = Ignition::Math::Vector3d.new(0, 0, 0) +v1 = Gz::Math::Vector3d.new(0, 0, 0) ``` You can also get access to each component in the vector using the `X()`, `Y()` and `Z()` accessors: