From 612cccb65cb78f98066eebcb7cc1a96061639ff3 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Thu, 18 Aug 2022 17:09:56 -0700 Subject: [PATCH] Support migration (#483) Signed-off-by: methylDragon --- BUILD.bazel | 2 +- CMakeLists.txt | 5 +- Changelog.md | 4 +- eigen3/include/CMakeLists.txt | 2 + eigen3/include/gz/math/eigen3/Conversions.hh | 94 +++++++------- eigen3/include/gz/math/eigen3/Util.hh | 20 +-- eigen3/include/ignition/math/eigen3.hh | 19 +++ .../ignition/math/eigen3/Conversions.hh | 19 +++ eigen3/include/ignition/math/eigen3/Util.hh | 19 +++ eigen3/src/Conversions_TEST.cc | 96 +++++++------- eigen3/src/Util_TEST.cc | 4 +- ...itively_separable_scalar_field3_example.cc | 22 ++-- examples/angle_example.cc | 10 +- examples/color_example.cc | 14 +-- examples/diff_drive_odometry.cc | 8 +- examples/gauss_markov_process_example.cc | 4 +- examples/graph_example.cc | 10 +- examples/interval_example.cc | 18 +-- examples/kmeans.cc | 32 ++--- examples/piecewise_scalar_field3_example.cc | 48 +++---- examples/polynomial3_example.cc | 20 +-- examples/quaternion_from_euler.cc | 8 +- examples/quaternion_to_euler.cc | 12 +- examples/rand_example.cc | 6 +- examples/region3_example.cc | 28 ++--- examples/triangle_example.cc | 28 ++--- examples/vector2_example.cc | 10 +- include/CMakeLists.txt | 3 +- include/gz/CMakeLists.txt | 1 + .../math/AdditivelySeparableScalarField3.hh | 12 +- include/gz/math/Angle.hh | 12 +- include/gz/math/AxisAlignedBox.hh | 22 ++-- include/gz/math/Box.hh | 28 ++--- include/gz/math/Capsule.hh | 10 +- include/gz/math/Color.hh | 10 +- include/gz/math/Cylinder.hh | 12 +- include/gz/math/DiffDriveOdometry.hh | 12 +- include/gz/math/Ellipsoid.hh | 10 +- include/gz/math/Filter.hh | 12 +- include/gz/math/Frustum.hh | 16 +-- include/gz/math/GaussMarkovProcess.hh | 8 +- include/gz/math/Helpers.hh | 72 +++++------ include/gz/math/Inertial.hh | 10 +- include/gz/math/Interval.hh | 8 +- include/gz/math/Kmeans.hh | 10 +- include/gz/math/Line2.hh | 8 +- include/gz/math/Line3.hh | 8 +- include/gz/math/MassMatrix3.hh | 18 +-- include/gz/math/Material.hh | 10 +- include/gz/math/MaterialType.hh | 8 +- include/gz/math/Matrix3.hh | 16 +-- include/gz/math/Matrix4.hh | 18 +-- include/gz/math/Matrix6.hh | 10 +- include/gz/math/MovingWindowFilter.hh | 6 +- include/gz/math/OrientedBox.hh | 24 ++-- include/gz/math/PID.hh | 8 +- include/gz/math/PiecewiseScalarField3.hh | 12 +- include/gz/math/Plane.hh | 18 +-- include/gz/math/Polynomial3.hh | 12 +- include/gz/math/Pose3.hh | 14 +-- include/gz/math/Quaternion.hh | 18 +-- include/gz/math/Rand.hh | 8 +- include/gz/math/Region3.hh | 12 +- include/gz/math/RollingMean.hh | 8 +- include/gz/math/RotationSpline.hh | 8 +- include/gz/math/SemanticVersion.hh | 8 +- include/gz/math/SignalStats.hh | 8 +- include/gz/math/SpeedLimiter.hh | 8 +- include/gz/math/Sphere.hh | 20 +-- include/gz/math/SphericalCoordinates.hh | 62 ++++----- include/gz/math/Spline.hh | 10 +- include/gz/math/Stopwatch.hh | 10 +- include/gz/math/Temperature.hh | 18 +-- include/gz/math/Triangle.hh | 12 +- include/gz/math/Triangle3.hh | 14 +-- include/gz/math/Vector2.hh | 8 +- include/gz/math/Vector3.hh | 12 +- include/gz/math/Vector3Stats.hh | 12 +- include/gz/math/Vector4.hh | 14 +-- include/gz/math/config.hh.in | 9 ++ include/gz/math/detail/Box.hh | 14 +-- include/gz/math/detail/Capsule.hh | 8 +- include/gz/math/detail/Cylinder.hh | 4 +- include/gz/math/detail/Ellipsoid.hh | 8 +- include/gz/math/detail/Sphere.hh | 12 +- include/gz/math/detail/WellOrderedVector.hh | 6 +- include/gz/math/graph/Edge.hh | 8 +- include/gz/math/graph/Graph.hh | 18 +-- include/gz/math/graph/GraphAlgorithms.hh | 10 +- include/gz/math/graph/Vertex.hh | 8 +- include/gz/math/math.hh.in | 2 +- include/ignition/math.hh | 19 +++ .../math/AdditivelySeparableScalarField3.hh | 19 +++ include/ignition/math/Angle.hh | 19 +++ include/ignition/math/AxisAlignedBox.hh | 19 +++ include/ignition/math/Box.hh | 19 +++ include/ignition/math/Capsule.hh | 19 +++ include/ignition/math/Color.hh | 19 +++ include/ignition/math/Cylinder.hh | 19 +++ include/ignition/math/DiffDriveOdometry.hh | 19 +++ include/ignition/math/Ellipsoid.hh | 19 +++ include/ignition/math/Export.hh | 19 +++ include/ignition/math/Filter.hh | 19 +++ include/ignition/math/Frustum.hh | 19 +++ include/ignition/math/GaussMarkovProcess.hh | 19 +++ include/ignition/math/Helpers.hh | 19 +++ include/ignition/math/Inertial.hh | 19 +++ include/ignition/math/Interval.hh | 19 +++ include/ignition/math/Kmeans.hh | 19 +++ include/ignition/math/Line2.hh | 19 +++ include/ignition/math/Line3.hh | 19 +++ include/ignition/math/MassMatrix3.hh | 19 +++ include/ignition/math/Material.hh | 19 +++ include/ignition/math/MaterialType.hh | 19 +++ include/ignition/math/Matrix3.hh | 19 +++ include/ignition/math/Matrix4.hh | 19 +++ include/ignition/math/Matrix6.hh | 19 +++ include/ignition/math/MovingWindowFilter.hh | 19 +++ include/ignition/math/OrientedBox.hh | 19 +++ include/ignition/math/PID.hh | 19 +++ .../ignition/math/PiecewiseScalarField3.hh | 19 +++ include/ignition/math/Plane.hh | 19 +++ include/ignition/math/Polynomial3.hh | 19 +++ include/ignition/math/Pose3.hh | 19 +++ include/ignition/math/Quaternion.hh | 19 +++ include/ignition/math/Rand.hh | 19 +++ include/ignition/math/Region3.hh | 19 +++ include/ignition/math/RollingMean.hh | 19 +++ include/ignition/math/RotationSpline.hh | 19 +++ include/ignition/math/SemanticVersion.hh | 19 +++ include/ignition/math/SignalStats.hh | 19 +++ include/ignition/math/SpeedLimiter.hh | 19 +++ include/ignition/math/Sphere.hh | 19 +++ include/ignition/math/SphericalCoordinates.hh | 19 +++ include/ignition/math/Spline.hh | 19 +++ include/ignition/math/Stopwatch.hh | 19 +++ include/ignition/math/Temperature.hh | 19 +++ include/ignition/math/Triangle.hh | 19 +++ include/ignition/math/Triangle3.hh | 19 +++ include/ignition/math/Vector2.hh | 19 +++ include/ignition/math/Vector3.hh | 19 +++ include/ignition/math/Vector3Stats.hh | 19 +++ include/ignition/math/Vector4.hh | 19 +++ include/ignition/math/config.hh | 48 +++++++ include/ignition/math/graph/Edge.hh | 19 +++ include/ignition/math/graph/Graph.hh | 19 +++ .../ignition/math/graph/GraphAlgorithms.hh | 19 +++ include/ignition/math/graph/Vertex.hh | 19 +++ src/AdditivelySeparableScalarField3_TEST.cc | 6 +- src/Angle.cc | 6 +- src/Angle_TEST.cc | 6 +- src/AxisAlignedBox.cc | 6 +- src/AxisAlignedBox_TEST.cc | 4 +- src/Box_TEST.cc | 4 +- src/Capsule_TEST.cc | 6 +- src/Color.cc | 4 +- src/Color_TEST.cc | 4 +- src/Cylinder_TEST.cc | 4 +- src/DiffDriveOdometry.cc | 8 +- src/DiffDriveOdometry_TEST.cc | 8 +- src/Ellipsoid_TEST.cc | 8 +- src/Filter_TEST.cc | 4 +- src/Frustum.cc | 8 +- src/FrustumPrivate.hh | 12 +- src/Frustum_TEST.cc | 6 +- src/GaussMarkovProcess.cc | 8 +- src/GaussMarkovProcess_TEST.cc | 8 +- src/Helpers.cc | 2 +- src/Helpers_TEST.cc | 8 +- src/Inertial_TEST.cc | 4 +- src/Interval_TEST.cc | 4 +- src/Kmeans.cc | 6 +- src/KmeansPrivate.hh | 10 +- src/Kmeans_TEST.cc | 4 +- src/Line2_TEST.cc | 6 +- src/Line3_TEST.cc | 6 +- src/MassMatrix3_TEST.cc | 8 +- src/Material.cc | 8 +- src/MaterialType.hh | 4 +- src/Material_TEST.cc | 8 +- src/Matrix3_TEST.cc | 6 +- src/Matrix4_TEST.cc | 10 +- src/Matrix6_TEST.cc | 4 +- src/MovingWindowFilter_TEST.cc | 6 +- src/OrientedBox_TEST.cc | 6 +- src/PID.cc | 6 +- src/PID_TEST.cc | 6 +- src/PiecewiseScalarField3_TEST.cc | 10 +- src/Plane_TEST.cc | 6 +- src/Polynomial3_TEST.cc | 4 +- src/Pose_TEST.cc | 6 +- src/Quaternion_TEST.cc | 10 +- src/Rand.cc | 4 +- src/Rand_TEST.cc | 6 +- src/Region3_TEST.cc | 4 +- src/RollingMean.cc | 6 +- src/RollingMean_TEST.cc | 6 +- src/RotationSpline.cc | 6 +- src/RotationSplinePrivate.cc | 2 +- src/RotationSplinePrivate.hh | 8 +- src/RotationSpline_TEST.cc | 10 +- src/SemanticVersion.cc | 4 +- src/SemanticVersion_TEST.cc | 4 +- src/SignalStats.cc | 4 +- src/SignalStatsPrivate.hh | 6 +- src/SignalStats_TEST.cc | 6 +- src/SpeedLimiter.cc | 8 +- src/SpeedLimiter_TEST.cc | 6 +- src/Sphere_TEST.cc | 4 +- src/SphericalCoordinates.cc | 8 +- src/SphericalCoordinates_TEST.cc | 4 +- src/Spline.cc | 8 +- src/SplinePrivate.cc | 2 +- src/SplinePrivate.hh | 12 +- src/Spline_TEST.cc | 6 +- src/Stopwatch.cc | 6 +- src/Stopwatch_TEST.cc | 4 +- src/Temperature.cc | 6 +- src/Temperature_TEST.cc | 4 +- src/Triangle3_TEST.cc | 6 +- src/Triangle_TEST.cc | 6 +- src/Vector2_TEST.cc | 6 +- src/Vector3Stats.cc | 4 +- src/Vector3StatsPrivate.hh | 8 +- src/Vector3Stats_TEST.cc | 4 +- src/Vector3_TEST.cc | 6 +- src/Vector4_TEST.cc | 8 +- src/graph/Edge_TEST.cc | 6 +- src/graph/GraphAlgorithms_TEST.cc | 6 +- src/graph/GraphDirected_TEST.cc | 4 +- src/graph/GraphUndirected_TEST.cc | 4 +- src/graph/Graph_TEST.cc | 4 +- src/graph/Vertex_TEST.cc | 4 +- src/python_pybind11/src/Angle.cc | 4 +- src/python_pybind11/src/Angle.hh | 2 +- src/python_pybind11/src/AxisAlignedBox.cc | 14 +-- src/python_pybind11/src/AxisAlignedBox.hh | 2 +- src/python_pybind11/src/Box.hh | 28 ++--- src/python_pybind11/src/Capsule.hh | 16 +-- src/python_pybind11/src/Color.cc | 4 +- src/python_pybind11/src/Color.hh | 8 +- src/python_pybind11/src/Cylinder.hh | 24 ++-- src/python_pybind11/src/DiffDriveOdometry.cc | 4 +- src/python_pybind11/src/DiffDriveOdometry.hh | 12 +- src/python_pybind11/src/Ellipsoid.hh | 22 ++-- src/python_pybind11/src/Filter.cc | 6 +- src/python_pybind11/src/Filter.hh | 36 +++--- src/python_pybind11/src/Frustum.cc | 30 ++--- src/python_pybind11/src/Frustum.hh | 8 +- src/python_pybind11/src/GaussMarkovProcess.cc | 4 +- src/python_pybind11/src/GaussMarkovProcess.hh | 8 +- src/python_pybind11/src/Helpers.cc | 56 ++++----- src/python_pybind11/src/Helpers.hh | 10 +- src/python_pybind11/src/Inertial.hh | 20 +-- src/python_pybind11/src/Interval.hh | 14 +-- src/python_pybind11/src/Kmeans.cc | 10 +- src/python_pybind11/src/Kmeans.hh | 8 +- src/python_pybind11/src/Line2.hh | 32 ++--- src/python_pybind11/src/Line3.hh | 32 ++--- src/python_pybind11/src/MassMatrix3.cc | 2 +- src/python_pybind11/src/MassMatrix3.hh | 66 +++++----- src/python_pybind11/src/Material.cc | 40 +++--- src/python_pybind11/src/Material.hh | 8 +- src/python_pybind11/src/Matrix3.cc | 2 +- src/python_pybind11/src/Matrix3.hh | 18 +-- src/python_pybind11/src/Matrix4.cc | 2 +- src/python_pybind11/src/Matrix4.hh | 36 +++--- src/python_pybind11/src/Matrix6.hh | 2 +- src/python_pybind11/src/MovingWindowFilter.cc | 6 +- src/python_pybind11/src/MovingWindowFilter.hh | 14 +-- src/python_pybind11/src/OrientedBox.hh | 32 ++--- src/python_pybind11/src/PID.cc | 4 +- src/python_pybind11/src/PID.hh | 8 +- src/python_pybind11/src/Plane.hh | 50 ++++---- src/python_pybind11/src/Polynomial3.hh | 16 +-- src/python_pybind11/src/Pose3.cc | 2 +- src/python_pybind11/src/Pose3.hh | 30 ++--- src/python_pybind11/src/Quaternion.cc | 2 +- src/python_pybind11/src/Quaternion.hh | 34 ++--- src/python_pybind11/src/Rand.cc | 18 +-- src/python_pybind11/src/Rand.hh | 10 +- src/python_pybind11/src/Region3.hh | 16 +-- src/python_pybind11/src/RollingMean.cc | 4 +- src/python_pybind11/src/RollingMean.hh | 8 +- src/python_pybind11/src/RotationSpline.cc | 4 +- src/python_pybind11/src/RotationSpline.hh | 8 +- src/python_pybind11/src/SemanticVersion.cc | 4 +- src/python_pybind11/src/SemanticVersion.hh | 8 +- src/python_pybind11/src/SignalStats.cc | 78 ++++++------ src/python_pybind11/src/SignalStats.hh | 22 ++-- src/python_pybind11/src/Sphere.hh | 14 +-- .../src/SphericalCoordinates.cc | 12 +- .../src/SphericalCoordinates.hh | 8 +- src/python_pybind11/src/Spline.cc | 4 +- src/python_pybind11/src/Spline.hh | 8 +- src/python_pybind11/src/StopWatch.cc | 4 +- src/python_pybind11/src/StopWatch.hh | 8 +- src/python_pybind11/src/Temperature.cc | 4 +- src/python_pybind11/src/Temperature.hh | 8 +- src/python_pybind11/src/Triangle.cc | 2 +- src/python_pybind11/src/Triangle.hh | 16 +-- src/python_pybind11/src/Triangle3.cc | 2 +- src/python_pybind11/src/Triangle3.hh | 16 +-- src/python_pybind11/src/Vector2.cc | 2 +- src/python_pybind11/src/Vector2.hh | 16 +-- src/python_pybind11/src/Vector3.cc | 2 +- src/python_pybind11/src/Vector3.hh | 16 +-- src/python_pybind11/src/Vector3Stats.cc | 4 +- src/python_pybind11/src/Vector3Stats.hh | 8 +- src/python_pybind11/src/Vector4.cc | 2 +- src/python_pybind11/src/Vector4.hh | 16 +-- .../src/_ignition_math_pybind11.cc | 118 +++++++++--------- src/ruby/Angle.i | 2 +- src/ruby/AxisAlignedBox.i | 10 +- src/ruby/Box.i | 16 +-- src/ruby/Color.i | 8 +- src/ruby/Cylinder.i | 10 +- src/ruby/DiffDriveOdometry.i | 8 +- src/ruby/Filter.i | 10 +- src/ruby/Frustum.i | 12 +- src/ruby/GaussMarkovProcess.i | 2 +- src/ruby/Helpers.i | 2 +- src/ruby/Inertial.i | 8 +- src/ruby/Kmeans.i | 6 +- src/ruby/Line2.i | 6 +- src/ruby/Line3.i | 6 +- src/ruby/MassMatrix3.i | 14 +-- src/ruby/Material.i | 8 +- src/ruby/MaterialType.i | 6 +- src/ruby/Matrix3.i | 10 +- src/ruby/Matrix4.i | 12 +- src/ruby/MovingWindowFilter.i | 4 +- src/ruby/OrientedBox.i | 16 +-- src/ruby/PID.i | 2 +- src/ruby/Plane.i | 14 +-- src/ruby/Pose3.i | 8 +- src/ruby/Quaternion.i | 8 +- src/ruby/Rand.i | 2 +- src/ruby/RollingMean.i | 2 +- src/ruby/RotationSpline.i | 6 +- src/ruby/SemanticVersion.i | 2 +- src/ruby/SignalStats.i | 2 +- src/ruby/Sphere.i | 10 +- src/ruby/SphericalCoordinates.i | 8 +- src/ruby/Spline.i | 8 +- src/ruby/StopWatch.i | 6 +- src/ruby/Temperature.i | 2 +- src/ruby/Triangle.i | 10 +- src/ruby/Triangle3.i | 10 +- src/ruby/Vector2.i | 2 +- src/ruby/Vector3.i | 2 +- src/ruby/Vector3Stats.i | 8 +- src/ruby/Vector4.i | 2 +- test/integration/deprecated_TEST.cc | 27 ++++ tutorials/cppgetstarted.md | 6 +- 355 files changed, 2905 insertions(+), 1693 deletions(-) create mode 100644 eigen3/include/CMakeLists.txt create mode 100644 eigen3/include/ignition/math/eigen3.hh create mode 100644 eigen3/include/ignition/math/eigen3/Conversions.hh create mode 100644 eigen3/include/ignition/math/eigen3/Util.hh create mode 100644 include/gz/CMakeLists.txt create mode 100644 include/ignition/math.hh create mode 100644 include/ignition/math/AdditivelySeparableScalarField3.hh create mode 100644 include/ignition/math/Angle.hh create mode 100644 include/ignition/math/AxisAlignedBox.hh create mode 100644 include/ignition/math/Box.hh create mode 100644 include/ignition/math/Capsule.hh create mode 100644 include/ignition/math/Color.hh create mode 100644 include/ignition/math/Cylinder.hh create mode 100644 include/ignition/math/DiffDriveOdometry.hh create mode 100644 include/ignition/math/Ellipsoid.hh create mode 100644 include/ignition/math/Export.hh create mode 100644 include/ignition/math/Filter.hh create mode 100644 include/ignition/math/Frustum.hh create mode 100644 include/ignition/math/GaussMarkovProcess.hh create mode 100644 include/ignition/math/Helpers.hh create mode 100644 include/ignition/math/Inertial.hh create mode 100644 include/ignition/math/Interval.hh create mode 100644 include/ignition/math/Kmeans.hh create mode 100644 include/ignition/math/Line2.hh create mode 100644 include/ignition/math/Line3.hh create mode 100644 include/ignition/math/MassMatrix3.hh create mode 100644 include/ignition/math/Material.hh create mode 100644 include/ignition/math/MaterialType.hh create mode 100644 include/ignition/math/Matrix3.hh create mode 100644 include/ignition/math/Matrix4.hh create mode 100644 include/ignition/math/Matrix6.hh create mode 100644 include/ignition/math/MovingWindowFilter.hh create mode 100644 include/ignition/math/OrientedBox.hh create mode 100644 include/ignition/math/PID.hh create mode 100644 include/ignition/math/PiecewiseScalarField3.hh create mode 100644 include/ignition/math/Plane.hh create mode 100644 include/ignition/math/Polynomial3.hh create mode 100644 include/ignition/math/Pose3.hh create mode 100644 include/ignition/math/Quaternion.hh create mode 100644 include/ignition/math/Rand.hh create mode 100644 include/ignition/math/Region3.hh create mode 100644 include/ignition/math/RollingMean.hh create mode 100644 include/ignition/math/RotationSpline.hh create mode 100644 include/ignition/math/SemanticVersion.hh create mode 100644 include/ignition/math/SignalStats.hh create mode 100644 include/ignition/math/SpeedLimiter.hh create mode 100644 include/ignition/math/Sphere.hh create mode 100644 include/ignition/math/SphericalCoordinates.hh create mode 100644 include/ignition/math/Spline.hh create mode 100644 include/ignition/math/Stopwatch.hh create mode 100644 include/ignition/math/Temperature.hh create mode 100644 include/ignition/math/Triangle.hh create mode 100644 include/ignition/math/Triangle3.hh create mode 100644 include/ignition/math/Vector2.hh create mode 100644 include/ignition/math/Vector3.hh create mode 100644 include/ignition/math/Vector3Stats.hh create mode 100644 include/ignition/math/Vector4.hh create mode 100644 include/ignition/math/config.hh create mode 100644 include/ignition/math/graph/Edge.hh create mode 100644 include/ignition/math/graph/Graph.hh create mode 100644 include/ignition/math/graph/GraphAlgorithms.hh create mode 100644 include/ignition/math/graph/Vertex.hh create mode 100644 test/integration/deprecated_TEST.cc diff --git a/BUILD.bazel b/BUILD.bazel index 43d5a6bb8..3f2af6a7a 100644 --- a/BUILD.bazel +++ b/BUILD.bazel @@ -43,7 +43,7 @@ ign_export_header( public_headers_no_gen = glob([ "include/ignition/math/*.hh", - "include/ignition/math/detail/*.hh", + "include/gz/math/detail/*.hh", "include/ignition/math/graph/*.hh", ]) diff --git a/CMakeLists.txt b/CMakeLists.txt index 580ec379f..8116a3793 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -16,7 +16,10 @@ find_package(ignition-cmake2 2.13.0 REQUIRED) #============================================================================ set (c++standard 17) set (CMAKE_CXX_STANDARD 17) -ign_configure_project(VERSION_SUFFIX) +ign_configure_project( + REPLACE_IGNITION_INCLUDE_PATH gz/math + VERSION_SUFFIX +) #============================================================================ # Set project-specific options diff --git a/Changelog.md b/Changelog.md index a99d12b96..722c5127b 100644 --- a/Changelog.md +++ b/Changelog.md @@ -516,7 +516,7 @@ ### Ignition Math 6.1.0 -1. eigen3: add conversion functions for Eigen::AlignedBox3d <=> ignition::math::AxisAlignedBox +1. eigen3: add conversion functions for Eigen::AlignedBox3d <=> gz::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 @@ -547,7 +547,7 @@ * [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) -1. eigen3: add conversion functions for Eigen::AlignedBox3d <=> ignition::math::AxisAlignedBox +1. eigen3: add conversion functions for Eigen::AlignedBox3d <=> gz::math::AxisAlignedBox * [BitBucket pull request 302](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-math/pull-requests/302) diff --git a/eigen3/include/CMakeLists.txt b/eigen3/include/CMakeLists.txt new file mode 100644 index 000000000..4b2bdd7bb --- /dev/null +++ b/eigen3/include/CMakeLists.txt @@ -0,0 +1,2 @@ +add_subdirectory(gz) +install(DIRECTORY ignition DESTINATION ${IGN_INCLUDE_INSTALL_DIR_FULL}) diff --git a/eigen3/include/gz/math/eigen3/Conversions.hh b/eigen3/include/gz/math/eigen3/Conversions.hh index dc7334f68..bd3bbdc4e 100644 --- a/eigen3/include/gz/math/eigen3/Conversions.hh +++ b/eigen3/include/gz/math/eigen3/Conversions.hh @@ -15,16 +15,16 @@ * */ -#ifndef IGNITION_MATH_EIGEN3_CONVERSIONS_HH_ -#define IGNITION_MATH_EIGEN3_CONVERSIONS_HH_ +#ifndef GZ_MATH_EIGEN3_CONVERSIONS_HH_ +#define GZ_MATH_EIGEN3_CONVERSIONS_HH_ #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include namespace ignition { @@ -32,28 +32,28 @@ namespace ignition { 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) @@ -67,9 +67,9 @@ namespace ignition return matrix; } - /// \brief Convert from ignition::math::Matrix6d to + /// \brief Convert from gz::math::Matrix6d to /// Eigen::Matrix. - /// \param[in] _m ignition::math::Matrix6d to convert. + /// \param[in] _m gz::math::Matrix6d to convert. /// \return The equivalent Eigen::Matrix. /// \tparam Precision Precision such as int, double or float. template @@ -88,10 +88,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(); @@ -102,10 +102,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()); @@ -114,12 +114,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]; @@ -127,25 +127,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) @@ -158,9 +158,9 @@ namespace ignition } /// \brief Convert Eigen::Matrix to - /// ignition::math::Matrix6d. + /// gz::math::Matrix6d. /// \param[in] _m Eigen::Matrix to convert. - /// \return The equivalent ignition::math::Matrix6d. + /// \return The equivalent gz::math::Matrix6d. /// \tparam Precision Precision such as int, double or float. template inline @@ -178,12 +178,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(); @@ -192,12 +192,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 25f740bd8..15f10624a 100644 --- a/eigen3/include/gz/math/eigen3/Util.hh +++ b/eigen3/include/gz/math/eigen3/Util.hh @@ -15,21 +15,21 @@ * */ -#ifndef IGNITION_MATH_EIGEN3_UTIL_HH_ -#define IGNITION_MATH_EIGEN3_UTIL_HH_ +#ifndef GZ_MATH_EIGEN3_UTIL_HH_ +#define GZ_MATH_EIGEN3_UTIL_HH_ #include #include #include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include namespace ignition { @@ -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 new file mode 100644 index 000000000..20dafc6ec --- /dev/null +++ b/eigen3/include/ignition/math/eigen3.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/eigen3/include/ignition/math/eigen3/Conversions.hh b/eigen3/include/ignition/math/eigen3/Conversions.hh new file mode 100644 index 000000000..bab4a3f07 --- /dev/null +++ b/eigen3/include/ignition/math/eigen3/Conversions.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/eigen3/include/ignition/math/eigen3/Util.hh b/eigen3/include/ignition/math/eigen3/Util.hh new file mode 100644 index 000000000..962463fa3 --- /dev/null +++ b/eigen3/include/ignition/math/eigen3/Util.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/eigen3/src/Conversions_TEST.cc b/eigen3/src/Conversions_TEST.cc index 628311407..391f4f52f 100644 --- a/eigen3/src/Conversions_TEST.cc +++ b/eigen3/src/Conversions_TEST.cc @@ -18,29 +18,29 @@ #include -#include +#include ///////////////////////////////////////////////// /// Check Vector3 conversions 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, ConvertMatrix6) { { - ignition::math::Matrix6d iMat, iMat2; - auto eMat = ignition::math::eigen3::convert(iMat); + gz::math::Matrix6d iMat, iMat2; + auto eMat = gz::math::eigen3::convert(iMat); for (std::size_t i = 0; i < 6; ++i) { for (std::size_t j = 0; j < 6; ++j) @@ -158,20 +158,20 @@ TEST(EigenConversions, ConvertMatrix6) EXPECT_DOUBLE_EQ(0.0, eMat(i, j)); } } - iMat2 = ignition::math::eigen3::convert(eMat); + iMat2 = gz::math::eigen3::convert(eMat); EXPECT_EQ(iMat, iMat2); } { - ignition::math::Matrix6d iMat( + gz::math::Matrix6d iMat( 0.0, 1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0, 11.0, 12.0, 13.0, 14.0, 15.0, 16.0, 17.0, 18.0, 19.0, 20.0, 21.0, 22.0, 23.0, 24.0, 25.0, 26.0, 27.0, 28.0, 29.0, 30.0, 31.0, 32.0, 33.0, 34.0, 35.0); - ignition::math::Matrix6d iMat2; - auto eMat = ignition::math::eigen3::convert(iMat); + gz::math::Matrix6d iMat2; + auto eMat = gz::math::eigen3::convert(iMat); for (std::size_t i = 0; i < 6; ++i) { for (std::size_t j = 0; j < 6; ++j) @@ -179,7 +179,7 @@ TEST(EigenConversions, ConvertMatrix6) EXPECT_DOUBLE_EQ(iMat(i, j), eMat(i, j)); } } - iMat2 = ignition::math::eigen3::convert(eMat); + iMat2 = gz::math::eigen3::convert(eMat); EXPECT_EQ(iMat, iMat2); } } @@ -189,8 +189,8 @@ TEST(EigenConversions, ConvertMatrix6) 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]); @@ -200,14 +200,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]); @@ -217,7 +217,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 1e5220462..a4281ecc3 100644 --- a/eigen3/src/Util_TEST.cc +++ b/eigen3/src/Util_TEST.cc @@ -17,9 +17,9 @@ #include -#include +#include -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// /// \brief Test the oriented box converted from a set of vertices diff --git a/examples/additively_separable_scalar_field3_example.cc b/examples/additively_separable_scalar_field3_example.cc index c46ffd5ee..20670c59a 100644 --- a/examples/additively_separable_scalar_field3_example.cc +++ b/examples/additively_separable_scalar_field3_example.cc @@ -16,21 +16,21 @@ */ //! [complete] #include -#include -#include +#include +#include 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 eb2ea916c..e0390e529 100644 --- a/examples/angle_example.cc +++ b/examples/angle_example.cc @@ -16,20 +16,20 @@ */ //! [complete] #include -#include +#include 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/color_example.cc b/examples/color_example.cc index 4d7325a9e..8d0419234 100644 --- a/examples/color_example.cc +++ b/examples/color_example.cc @@ -16,31 +16,31 @@ */ //! [complete] #include -#include +#include 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 6f2bcdf8e..7b0a2be06 100644 --- a/examples/diff_drive_odometry.cc +++ b/examples/diff_drive_odometry.cc @@ -18,15 +18,15 @@ #include #include -#include -#include -#include +#include +#include +#include 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 313bd6272..1b0bf03fc 100644 --- a/examples/gauss_markov_process_example.cc +++ b/examples/gauss_markov_process_example.cc @@ -16,7 +16,7 @@ */ //! [complete] #include -#include +#include // You can plot the data generated by this program by following these // steps. @@ -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/graph_example.cc b/examples/graph_example.cc index a30788d48..6552ecc0c 100644 --- a/examples/graph_example.cc +++ b/examples/graph_example.cc @@ -16,13 +16,13 @@ */ #include -#include +#include 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/interval_example.cc b/examples/interval_example.cc index 68623ca72..18f95fb47 100644 --- a/examples/interval_example.cc +++ b/examples/interval_example.cc @@ -16,27 +16,27 @@ */ //! [complete] #include -#include +#include 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 6f02d2091..868d9f938 100644 --- a/examples/kmeans.cc +++ b/examples/kmeans.cc @@ -18,37 +18,37 @@ #include #include -#include +#include 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/piecewise_scalar_field3_example.cc b/examples/piecewise_scalar_field3_example.cc index d584ff09c..47bfdf92b 100644 --- a/examples/piecewise_scalar_field3_example.cc +++ b/examples/piecewise_scalar_field3_example.cc @@ -17,38 +17,38 @@ //! [complete] #include -#include -#include -#include +#include +#include +#include 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 f268dbdec..6862b5876 100644 --- a/examples/polynomial3_example.cc +++ b/examples/polynomial3_example.cc @@ -16,22 +16,22 @@ */ //! [complete] #include -#include -#include +#include +#include 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/quaternion_from_euler.cc b/examples/quaternion_from_euler.cc index 0f3fb16c8..b1353c0b5 100644 --- a/examples/quaternion_from_euler.cc +++ b/examples/quaternion_from_euler.cc @@ -17,8 +17,8 @@ #include #include -#include -#include +#include +#include // Copied from urdfdom static inline double strToDouble(const char *in) @@ -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 0fe1d0566..858b32be8 100644 --- a/examples/quaternion_to_euler.cc +++ b/examples/quaternion_to_euler.cc @@ -17,9 +17,9 @@ #include #include -#include -#include -#include +#include +#include +#include // Copied from urdfdom static inline double strToDouble(const char *in) @@ -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 227e4399a..08dbd9c11 100644 --- a/examples/rand_example.cc +++ b/examples/rand_example.cc @@ -16,7 +16,7 @@ */ //! [complete] #include -#include +#include // You can plot the data generated by this program by following these // steps. @@ -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 1cb647c01..97af405c7 100644 --- a/examples/region3_example.cc +++ b/examples/region3_example.cc @@ -16,33 +16,33 @@ */ //! [complete] #include -#include -#include +#include +#include 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/triangle_example.cc b/examples/triangle_example.cc index a2adeaf99..a6d849e97 100644 --- a/examples/triangle_example.cc +++ b/examples/triangle_example.cc @@ -16,7 +16,7 @@ */ #include -#include +#include int main(int argc, char **argv) { @@ -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" diff --git a/examples/vector2_example.cc b/examples/vector2_example.cc index e558a2327..6c63a81d7 100644 --- a/examples/vector2_example.cc +++ b/examples/vector2_example.cc @@ -16,7 +16,7 @@ */ //! [complete] #include -#include +#include int main(int argc, char **argv) { @@ -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 diff --git a/include/CMakeLists.txt b/include/CMakeLists.txt index 25ec89762..4b2bdd7bb 100644 --- a/include/CMakeLists.txt +++ b/include/CMakeLists.txt @@ -1 +1,2 @@ -add_subdirectory(ignition) +add_subdirectory(gz) +install(DIRECTORY ignition DESTINATION ${IGN_INCLUDE_INSTALL_DIR_FULL}) diff --git a/include/gz/CMakeLists.txt b/include/gz/CMakeLists.txt new file mode 100644 index 000000000..2767b4e7a --- /dev/null +++ b/include/gz/CMakeLists.txt @@ -0,0 +1 @@ +add_subdirectory(math) diff --git a/include/gz/math/AdditivelySeparableScalarField3.hh b/include/gz/math/AdditivelySeparableScalarField3.hh index e05128a35..446294482 100644 --- a/include/gz/math/AdditivelySeparableScalarField3.hh +++ b/include/gz/math/AdditivelySeparableScalarField3.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_SEPARABLE_SCALAR_FIELD3_HH_ -#define IGNITION_MATH_SEPARABLE_SCALAR_FIELD3_HH_ +#ifndef GZ_MATH_SEPARABLE_SCALAR_FIELD3_HH_ +#define GZ_MATH_SEPARABLE_SCALAR_FIELD3_HH_ #include #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -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 126fdbe5b..562b3c05e 100644 --- a/include/gz/math/Angle.hh +++ b/include/gz/math/Angle.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_ANGLE_HH_ -#define IGNITION_MATH_ANGLE_HH_ +#ifndef GZ_MATH_ANGLE_HH_ +#define GZ_MATH_ANGLE_HH_ #include -#include -#include +#include +#include /// \def IGN_RTOD(d) /// \brief Macro that converts radians to degrees @@ -234,7 +234,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; @@ -245,7 +245,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 6e50cac89..8393d6ba1 100644 --- a/include/gz/math/AxisAlignedBox.hh +++ b/include/gz/math/AxisAlignedBox.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_AXISALIGNEDBOX_HH_ -#define IGNITION_MATH_AXISALIGNEDBOX_HH_ +#ifndef GZ_MATH_AXISALIGNEDBOX_HH_ +#define GZ_MATH_AXISALIGNEDBOX_HH_ #include #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include namespace ignition { @@ -147,7 +147,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; @@ -277,14 +277,14 @@ namespace ignition /// \brief Get the material associated with this box. /// \return The material assigned to this box. /// \deprecated Unimplemented - public: const ignition::math::Material IGN_DEPRECATED(6.0) + public: const gz::math::Material IGN_DEPRECATED(6.0) &Material() const; /// \brief Set the material associated with this box. /// \param[in] _mat The material assigned to this box /// \deprecated Unimplemented public: void IGN_DEPRECATED(6.0) SetMaterial( - const ignition::math::Material &_mat); + const gz::math::Material &_mat); /// \brief Get the mass matrix for this box. This function /// is only meaningful if the box's size and material diff --git a/include/gz/math/Box.hh b/include/gz/math/Box.hh index 09a55ec59..70ba4aee7 100644 --- a/include/gz/math/Box.hh +++ b/include/gz/math/Box.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_BOX_HH_ -#define IGNITION_MATH_BOX_HH_ +#ifndef GZ_MATH_BOX_HH_ +#define GZ_MATH_BOX_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include "ignition/math/detail/WellOrderedVector.hh" +#include "gz/math/detail/WellOrderedVector.hh" #include @@ -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 Destructor. public: virtual ~Box() = default; @@ -127,11 +127,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. @@ -204,7 +204,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 @@ -221,5 +221,5 @@ namespace ignition } } } -#include "ignition/math/detail/Box.hh" +#include "gz/math/detail/Box.hh" #endif diff --git a/include/gz/math/Capsule.hh b/include/gz/math/Capsule.hh index cbf4ae198..1af18d89e 100644 --- a/include/gz/math/Capsule.hh +++ b/include/gz/math/Capsule.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_CAPSULE_HH_ -#define IGNITION_MATH_CAPSULE_HH_ +#ifndef GZ_MATH_CAPSULE_HH_ +#define GZ_MATH_CAPSULE_HH_ #include -#include "ignition/math/MassMatrix3.hh" -#include "ignition/math/Material.hh" +#include "gz/math/MassMatrix3.hh" +#include "gz/math/Material.hh" namespace ignition { @@ -146,6 +146,6 @@ namespace ignition } } } -#include "ignition/math/detail/Capsule.hh" +#include "gz/math/detail/Capsule.hh" #endif diff --git a/include/gz/math/Color.hh b/include/gz/math/Color.hh index fd6592941..9735edc3a 100644 --- a/include/gz/math/Color.hh +++ b/include/gz/math/Color.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_COLOR_HH_ -#define IGNITION_MATH_COLOR_HH_ +#ifndef GZ_MATH_COLOR_HH_ +#define GZ_MATH_COLOR_HH_ #include #include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/math/Cylinder.hh b/include/gz/math/Cylinder.hh index 161e5a48e..9ebfc5d15 100644 --- a/include/gz/math/Cylinder.hh +++ b/include/gz/math/Cylinder.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_CYLINDER_HH_ -#define IGNITION_MATH_CYLINDER_HH_ +#ifndef GZ_MATH_CYLINDER_HH_ +#define GZ_MATH_CYLINDER_HH_ -#include "ignition/math/MassMatrix3.hh" -#include "ignition/math/Material.hh" -#include "ignition/math/Quaternion.hh" +#include "gz/math/MassMatrix3.hh" +#include "gz/math/Material.hh" +#include "gz/math/Quaternion.hh" namespace ignition { @@ -178,6 +178,6 @@ namespace ignition } } } -#include "ignition/math/detail/Cylinder.hh" +#include "gz/math/detail/Cylinder.hh" #endif diff --git a/include/gz/math/DiffDriveOdometry.hh b/include/gz/math/DiffDriveOdometry.hh index 93d272155..2891d4c78 100644 --- a/include/gz/math/DiffDriveOdometry.hh +++ b/include/gz/math/DiffDriveOdometry.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_DIFFDRIVEODOMETRY_HH_ -#define IGNITION_MATH_DIFFDRIVEODOMETRY_HH_ +#ifndef GZ_MATH_DIFFDRIVEODOMETRY_HH_ +#define GZ_MATH_DIFFDRIVEODOMETRY_HH_ #include #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -64,7 +64,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()); /// diff --git a/include/gz/math/Ellipsoid.hh b/include/gz/math/Ellipsoid.hh index 4d67fa9ba..cf11a86ca 100644 --- a/include/gz/math/Ellipsoid.hh +++ b/include/gz/math/Ellipsoid.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_ELLIPSOID_HH_ -#define IGNITION_MATH_ELLIPSOID_HH_ +#ifndef GZ_MATH_ELLIPSOID_HH_ +#define GZ_MATH_ELLIPSOID_HH_ #include -#include "ignition/math/MassMatrix3.hh" -#include "ignition/math/Material.hh" +#include "gz/math/MassMatrix3.hh" +#include "gz/math/Material.hh" namespace ignition { @@ -129,6 +129,6 @@ namespace ignition } } } -#include "ignition/math/detail/Ellipsoid.hh" +#include "gz/math/detail/Ellipsoid.hh" #endif diff --git a/include/gz/math/Filter.hh b/include/gz/math/Filter.hh index f88d3c8d9..8bca55dc0 100644 --- a/include/gz/math/Filter.hh +++ b/include/gz/math/Filter.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_FILTER_HH_ -#define IGNITION_MATH_FILTER_HH_ +#ifndef GZ_MATH_FILTER_HH_ +#define GZ_MATH_FILTER_HH_ -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/math/Frustum.hh b/include/gz/math/Frustum.hh index d297490cd..c42fae6f4 100644 --- a/include/gz/math/Frustum.hh +++ b/include/gz/math/Frustum.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_FRUSTUM_HH_ -#define IGNITION_MATH_FRUSTUM_HH_ - -#include -#include -#include -#include -#include +#ifndef GZ_MATH_FRUSTUM_HH_ +#define GZ_MATH_FRUSTUM_HH_ + +#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/math/GaussMarkovProcess.hh b/include/gz/math/GaussMarkovProcess.hh index 02ebb1a4f..eef0de7ff 100644 --- a/include/gz/math/GaussMarkovProcess.hh +++ b/include/gz/math/GaussMarkovProcess.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_GAUSSMARKOVPROCESS_HH_ -#define IGNITION_MATH_GAUSSMARKOVPROCESS_HH_ +#ifndef GZ_MATH_GAUSSMARKOVPROCESS_HH_ +#define GZ_MATH_GAUSSMARKOVPROCESS_HH_ #include #include -#include -#include +#include +#include namespace ignition { diff --git a/include/gz/math/Helpers.hh b/include/gz/math/Helpers.hh index 5d69b209d..202221978 100644 --- a/include/gz/math/Helpers.hh +++ b/include/gz/math/Helpers.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_FUNCTIONS_HH_ -#define IGNITION_MATH_FUNCTIONS_HH_ +#ifndef GZ_MATH_FUNCTIONS_HH_ +#define GZ_MATH_FUNCTIONS_HH_ #include #include @@ -31,8 +31,8 @@ #include #include -#include -#include "ignition/math/Export.hh" +#include +#include "gz/math/Export.hh" /// \brief The default tolerance value used by MassMatrix3::IsValid(), /// MassMatrix3::IsPositive(), and MassMatrix3::ValidMoments() @@ -41,137 +41,137 @@ constexpr T IGN_MASSMATRIX3_DEFAULT_TOLERANCE = T(10); /// \brief Double maximum value. This value will be similar to 1.79769e+308 /// \deprecated Use static const value instead. -#define IGN_DBL_MAX ignition::math::DPRCT_MAX_D +#define IGN_DBL_MAX gz::math::DPRCT_MAX_D /// \brief Double min value. This value will be similar to 2.22507e-308 /// \deprecated Use static const value instead. -#define IGN_DBL_MIN ignition::math::DPRCT_MIN_D +#define IGN_DBL_MIN gz::math::DPRCT_MIN_D /// \brief Double low value, equivalent to -IGN_DBL_MAX /// \deprecated Use static const value instead. -#define IGN_DBL_LOW ignition::math::DPRCT_LOW_D +#define IGN_DBL_LOW gz::math::DPRCT_LOW_D /// \brief Double positive infinite value /// \deprecated Use static const value instead. -#define IGN_DBL_INF ignition::math::DPRCT_INF_D +#define IGN_DBL_INF gz::math::DPRCT_INF_D /// \brief Float maximum value. This value will be similar to 3.40282e+38 /// \deprecated Use static const value instead. -#define IGN_FLT_MAX ignition::math::DPRCT_MAX_F +#define IGN_FLT_MAX gz::math::DPRCT_MAX_F /// \brief Float minimum value. This value will be similar to 1.17549e-38 /// \deprecated Use static const value instead. -#define IGN_FLT_MIN ignition::math::DPRCT_MIN_F +#define IGN_FLT_MIN gz::math::DPRCT_MIN_F /// \brief Float lowest value, equivalent to -IGN_FLT_MAX /// \deprecated Use static const value instead. -#define IGN_FLT_LOW ignition::math::DPRCT_LOW_F +#define IGN_FLT_LOW gz::math::DPRCT_LOW_F /// \brief Float positive infinite value /// \deprecated Use static const value instead. -#define IGN_FLT_INF ignition::math::DPRCT_INF_F +#define IGN_FLT_INF gz::math::DPRCT_INF_F /// \brief 16bit unsigned integer maximum value /// \deprecated Use static const value instead. -#define IGN_UINT16_MAX ignition::math::DPRCT_MAX_UI16 +#define IGN_UINT16_MAX gz::math::DPRCT_MAX_UI16 /// \brief 16bit unsigned integer minimum value /// \deprecated Use static const value instead. -#define IGN_UINT16_MIN ignition::math::DPRCT_MIN_UI16 +#define IGN_UINT16_MIN gz::math::DPRCT_MIN_UI16 /// \brief 16bit unsigned integer lowest value. This is equivalent to /// IGN_UINT16_MIN, and is defined here for completeness. /// \deprecated Use static const value instead. -#define IGN_UINT16_LOW ignition::math::DPRCT_LOW_UI16 +#define IGN_UINT16_LOW gz::math::DPRCT_LOW_UI16 /// \brief 16-bit unsigned integer positive infinite value /// \deprecated Use static const value instead. -#define IGN_UINT16_INF ignition::math::DPRCT_INF_UI16 +#define IGN_UINT16_INF gz::math::DPRCT_INF_UI16 /// \brief 16bit integer maximum value /// \deprecated Use static const value instead. -#define IGN_INT16_MAX ignition::math::DPRCT_MAX_I16 +#define IGN_INT16_MAX gz::math::DPRCT_MAX_I16 /// \brief 16bit integer minimum value /// \deprecated Use static const value instead. -#define IGN_INT16_MIN ignition::math::DPRCT_MIN_I16 +#define IGN_INT16_MIN gz::math::DPRCT_MIN_I16 /// \brief 16bit integer lowest value. This is equivalent to IGN_INT16_MIN, /// and is defined here for completeness. /// \deprecated Use static const value instead. -#define IGN_INT16_LOW ignition::math::DPRCT_LOW_I16 +#define IGN_INT16_LOW gz::math::DPRCT_LOW_I16 /// \brief 16-bit integer positive infinite value /// \deprecated Use static const value instead. -#define IGN_INT16_INF ignition::math::DPRCT_INF_I16 +#define IGN_INT16_INF gz::math::DPRCT_INF_I16 /// \brief 32bit unsigned integer maximum value /// \deprecated Use static const value instead. -#define IGN_UINT32_MAX ignition::math::DPRCT_MAX_UI32 +#define IGN_UINT32_MAX gz::math::DPRCT_MAX_UI32 /// \brief 32bit unsigned integer minimum value /// \deprecated Use static const value instead. -#define IGN_UINT32_MIN ignition::math::DPRCT_MIN_UI32 +#define IGN_UINT32_MIN gz::math::DPRCT_MIN_UI32 /// \brief 32bit unsigned integer lowest value. This is equivalent to /// IGN_UINT32_MIN, and is defined here for completeness. /// \deprecated Use static const value instead. -#define IGN_UINT32_LOW ignition::math::DPRCT_LOW_UI32 +#define IGN_UINT32_LOW gz::math::DPRCT_LOW_UI32 /// \brief 32-bit unsigned integer positive infinite value /// \deprecated Use static const value instead. -#define IGN_UINT32_INF ignition::math::DPRCT_INF_UI32 +#define IGN_UINT32_INF gz::math::DPRCT_INF_UI32 /// \brief 32bit integer maximum value /// \deprecated Use static const value instead. -#define IGN_INT32_MAX ignition::math::DPRCT_MAX_I32 +#define IGN_INT32_MAX gz::math::DPRCT_MAX_I32 /// \brief 32bit integer minimum value /// \deprecated Use static const value instead. -#define IGN_INT32_MIN ignition::math::DPRCT_MIN_I32 +#define IGN_INT32_MIN gz::math::DPRCT_MIN_I32 /// \brief 32bit integer minimum value. This is equivalent to IGN_INT32_MIN, /// and is defined here for completeness. /// \deprecated Use static const value instead. -#define IGN_INT32_LOW ignition::math::DPRCT_LOW_I32 +#define IGN_INT32_LOW gz::math::DPRCT_LOW_I32 /// \brief 32-bit integer positive infinite value /// \deprecated Use static const value instead. -#define IGN_INT32_INF ignition::math::DPRCT_INF_I32 +#define IGN_INT32_INF gz::math::DPRCT_INF_I32 /// \brief 64bit unsigned integer maximum value /// \deprecated Use static const value instead. -#define IGN_UINT64_MAX ignition::math::DPRCT_MAX_UI64 +#define IGN_UINT64_MAX gz::math::DPRCT_MAX_UI64 /// \brief 64bit unsigned integer minimum value /// \deprecated Use static const value instead. -#define IGN_UINT64_MIN ignition::math::DPRCT_MIN_UI64 +#define IGN_UINT64_MIN gz::math::DPRCT_MIN_UI64 /// \brief 64bit unsigned integer lowest value. This is equivalent to /// IGN_UINT64_MIN, and is defined here for completeness. /// \deprecated Use static const value instead. -#define IGN_UINT64_LOW ignition::math::DPRCT_LOW_UI64 +#define IGN_UINT64_LOW gz::math::DPRCT_LOW_UI64 /// \brief 64-bit unsigned integer positive infinite value /// \deprecated Use static const value instead. -#define IGN_UINT64_INF ignition::math::DPRCT_INF_UI64 +#define IGN_UINT64_INF gz::math::DPRCT_INF_UI64 /// \brief 64bit integer maximum value /// \deprecated Use static const value instead. -#define IGN_INT64_MAX ignition::math::DPRCT_MAX_I64 +#define IGN_INT64_MAX gz::math::DPRCT_MAX_I64 /// \brief 64bit integer minimum value /// \deprecated Use static const value instead. -#define IGN_INT64_MIN ignition::math::DPRCT_MIN_I64 +#define IGN_INT64_MIN gz::math::DPRCT_MIN_I64 /// \brief 64bit integer lowest value. This is equivalent to IGN_INT64_MIN, /// and is defined here for completeness. /// \deprecated Use static const value instead. -#define IGN_INT64_LOW ignition::math::DPRCT_LOW_I64 +#define IGN_INT64_LOW gz::math::DPRCT_LOW_I64 /// \brief 64-bit integer positive infinite value /// \deprecated Use static const value instead. -#define IGN_INT64_INF ignition::math::DPRCT_INF_I64 +#define IGN_INT64_INF gz::math::DPRCT_INF_I64 /// \brief Define IGN_PI, IGN_PI_2, and IGN_PI_4. /// This was put here for Windows support. diff --git a/include/gz/math/Inertial.hh b/include/gz/math/Inertial.hh index 91f486262..8a172af00 100644 --- a/include/gz/math/Inertial.hh +++ b/include/gz/math/Inertial.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_INERTIAL_HH_ -#define IGNITION_MATH_INERTIAL_HH_ +#ifndef GZ_MATH_INERTIAL_HH_ +#define GZ_MATH_INERTIAL_HH_ -#include -#include "ignition/math/MassMatrix3.hh" -#include "ignition/math/Pose3.hh" +#include +#include "gz/math/MassMatrix3.hh" +#include "gz/math/Pose3.hh" namespace ignition { diff --git a/include/gz/math/Interval.hh b/include/gz/math/Interval.hh index 115db95dc..523a63b66 100644 --- a/include/gz/math/Interval.hh +++ b/include/gz/math/Interval.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_INTERVAL_HH_ -#define IGNITION_MATH_INTERVAL_HH_ +#ifndef GZ_MATH_INTERVAL_HH_ +#define GZ_MATH_INTERVAL_HH_ #include #include @@ -23,7 +23,7 @@ #include #include -#include +#include namespace ignition { @@ -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 43d4231d4..cd6e714ce 100644 --- a/include/gz/math/Kmeans.hh +++ b/include/gz/math/Kmeans.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_KMEANS_HH_ -#define IGNITION_MATH_KMEANS_HH_ +#ifndef GZ_MATH_KMEANS_HH_ +#define GZ_MATH_KMEANS_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/math/Line2.hh b/include/gz/math/Line2.hh index 0b669f868..3c40b0848 100644 --- a/include/gz/math/Line2.hh +++ b/include/gz/math/Line2.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_LINE2_HH_ -#define IGNITION_MATH_LINE2_HH_ +#ifndef GZ_MATH_LINE2_HH_ +#define GZ_MATH_LINE2_HH_ #include -#include -#include +#include +#include namespace ignition { diff --git a/include/gz/math/Line3.hh b/include/gz/math/Line3.hh index e927817b8..eeac8f15c 100644 --- a/include/gz/math/Line3.hh +++ b/include/gz/math/Line3.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_LINE3_HH_ -#define IGNITION_MATH_LINE3_HH_ +#ifndef GZ_MATH_LINE3_HH_ +#define GZ_MATH_LINE3_HH_ #include -#include -#include +#include +#include namespace ignition { diff --git a/include/gz/math/MassMatrix3.hh b/include/gz/math/MassMatrix3.hh index 4767ffab6..e4fba8631 100644 --- a/include/gz/math/MassMatrix3.hh +++ b/include/gz/math/MassMatrix3.hh @@ -14,21 +14,21 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_MASSMATRIX3_HH_ -#define IGNITION_MATH_MASSMATRIX3_HH_ +#ifndef GZ_MATH_MASSMATRIX3_HH_ +#define GZ_MATH_MASSMATRIX3_HH_ #include #include #include #include -#include -#include "ignition/math/Helpers.hh" -#include "ignition/math/Material.hh" -#include "ignition/math/Quaternion.hh" -#include "ignition/math/Vector2.hh" -#include "ignition/math/Vector3.hh" -#include "ignition/math/Matrix3.hh" +#include +#include "gz/math/Helpers.hh" +#include "gz/math/Material.hh" +#include "gz/math/Quaternion.hh" +#include "gz/math/Vector2.hh" +#include "gz/math/Vector3.hh" +#include "gz/math/Matrix3.hh" namespace ignition { diff --git a/include/gz/math/Material.hh b/include/gz/math/Material.hh index 89bde08ea..add7fe13f 100644 --- a/include/gz/math/Material.hh +++ b/include/gz/math/Material.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_MATERIAL_HH_ -#define IGNITION_MATH_MATERIAL_HH_ +#ifndef GZ_MATH_MATERIAL_HH_ +#define GZ_MATH_MATERIAL_HH_ #include #include #include -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/math/MaterialType.hh b/include/gz/math/MaterialType.hh index eae22f3a4..046cc23d3 100644 --- a/include/gz/math/MaterialType.hh +++ b/include/gz/math/MaterialType.hh @@ -14,11 +14,11 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_MATERIALTYPES_HH_ -#define IGNITION_MATH_MATERIALTYPES_HH_ +#ifndef GZ_MATH_MATERIALTYPES_HH_ +#define GZ_MATH_MATERIALTYPES_HH_ -#include -#include +#include +#include namespace ignition { diff --git a/include/gz/math/Matrix3.hh b/include/gz/math/Matrix3.hh index f101bb6ef..ac64513fe 100644 --- a/include/gz/math/Matrix3.hh +++ b/include/gz/math/Matrix3.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_MATRIX3_HH_ -#define IGNITION_MATH_MATRIX3_HH_ +#ifndef GZ_MATH_MATRIX3_HH_ +#define GZ_MATH_MATRIX3_HH_ #include #include #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -490,7 +490,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) { _out << precision(_m(0, 0), 6) << " " << precision(_m(0, 1), 6) << " " @@ -510,7 +510,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 b7b0044c2..624f4e799 100644 --- a/include/gz/math/Matrix4.hh +++ b/include/gz/math/Matrix4.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_MATRIX4_HH_ -#define IGNITION_MATH_MATRIX4_HH_ +#ifndef GZ_MATH_MATRIX4_HH_ +#define GZ_MATH_MATRIX4_HH_ #include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { @@ -804,7 +804,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) { _out << precision(_m(0, 0), 6) << " " << precision(_m(0, 1), 6) << " " @@ -831,7 +831,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/Matrix6.hh b/include/gz/math/Matrix6.hh index c8dd33135..3a793648c 100644 --- a/include/gz/math/Matrix6.hh +++ b/include/gz/math/Matrix6.hh @@ -18,9 +18,9 @@ #define GZ_MATH_MATRIX6_HH_ #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -507,7 +507,7 @@ namespace ignition /// \param _m Matrix to output /// \return the stream public: friend std::ostream &operator<<( - std::ostream &_out, const ignition::math::Matrix6 &_m) + std::ostream &_out, const gz::math::Matrix6 &_m) { for (auto i : {0, 1, 2, 3, 4, 5}) { @@ -528,7 +528,7 @@ namespace ignition /// \param[out] _m Matrix6 to read values into /// \return the stream public: friend std::istream &operator>>( - std::istream &_in, ignition::math::Matrix6 &_m) + std::istream &_in, gz::math::Matrix6 &_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 67bb20c94..a0d6be5f3 100644 --- a/include/gz/math/MovingWindowFilter.hh +++ b/include/gz/math/MovingWindowFilter.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_MOVINGWINDOWFILTER_HH_ -#define IGNITION_MATH_MOVINGWINDOWFILTER_HH_ +#ifndef GZ_MATH_MOVINGWINDOWFILTER_HH_ +#define GZ_MATH_MOVINGWINDOWFILTER_HH_ #include #include -#include "ignition/math/Export.hh" +#include "gz/math/Export.hh" namespace ignition { diff --git a/include/gz/math/OrientedBox.hh b/include/gz/math/OrientedBox.hh index 64d48b578..b81cb682a 100644 --- a/include/gz/math/OrientedBox.hh +++ b/include/gz/math/OrientedBox.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_ORIENTEDBOX_HH_ -#define IGNITION_MATH_ORIENTEDBOX_HH_ +#ifndef GZ_MATH_ORIENTEDBOX_HH_ +#define GZ_MATH_ORIENTEDBOX_HH_ #include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include namespace ignition { @@ -201,14 +201,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; } @@ -274,7 +274,7 @@ namespace ignition private: Pose3 pose; /// \brief The box's material. - private: ignition::math::Material material; + private: gz::math::Material material; }; typedef OrientedBox OrientedBoxi; diff --git a/include/gz/math/PID.hh b/include/gz/math/PID.hh index 3291b3c5b..bf40356c8 100644 --- a/include/gz/math/PID.hh +++ b/include/gz/math/PID.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_PID_HH_ -#define IGNITION_MATH_PID_HH_ +#ifndef GZ_MATH_PID_HH_ +#define GZ_MATH_PID_HH_ #include -#include -#include +#include +#include namespace ignition { diff --git a/include/gz/math/PiecewiseScalarField3.hh b/include/gz/math/PiecewiseScalarField3.hh index ce938d1bf..fefce8e51 100644 --- a/include/gz/math/PiecewiseScalarField3.hh +++ b/include/gz/math/PiecewiseScalarField3.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_PIECEWISE_SCALAR_FIELD3_HH_ -#define IGNITION_MATH_PIECEWISE_SCALAR_FIELD3_HH_ +#ifndef GZ_MATH_PIECEWISE_SCALAR_FIELD3_HH_ +#define GZ_MATH_PIECEWISE_SCALAR_FIELD3_HH_ #include #include @@ -23,9 +23,9 @@ #include #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -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 4994f8128..07dfbe66d 100644 --- a/include/gz/math/Plane.hh +++ b/include/gz/math/Plane.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_PLANE_HH_ -#define IGNITION_MATH_PLANE_HH_ - -#include -#include -#include -#include -#include -#include +#ifndef GZ_MATH_PLANE_HH_ +#define GZ_MATH_PLANE_HH_ + +#include +#include +#include +#include +#include +#include #include namespace ignition diff --git a/include/gz/math/Polynomial3.hh b/include/gz/math/Polynomial3.hh index 4112d8f80..53148a387 100644 --- a/include/gz/math/Polynomial3.hh +++ b/include/gz/math/Polynomial3.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_POLYNOMIAL3_HH_ -#define IGNITION_MATH_POLYNOMIAL3_HH_ +#ifndef GZ_MATH_POLYNOMIAL3_HH_ +#define GZ_MATH_POLYNOMIAL3_HH_ #include #include @@ -23,9 +23,9 @@ #include #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -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 28c86ae30..aabf9ec43 100644 --- a/include/gz/math/Pose3.hh +++ b/include/gz/math/Pose3.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_POSE_HH_ -#define IGNITION_MATH_POSE_HH_ +#ifndef GZ_MATH_POSE_HH_ +#define GZ_MATH_POSE_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { @@ -461,7 +461,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; @@ -472,7 +472,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 d8196a087..b55f14f1c 100644 --- a/include/gz/math/Quaternion.hh +++ b/include/gz/math/Quaternion.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_QUATERNION_HH_ -#define IGNITION_MATH_QUATERNION_HH_ +#ifndef GZ_MATH_QUATERNION_HH_ +#define GZ_MATH_QUATERNION_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { @@ -1050,7 +1050,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 << precision(v.X(), 6) << " " << precision(v.Y(), 6) << " " @@ -1063,7 +1063,7 @@ namespace ignition /// \param[in] _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; diff --git a/include/gz/math/Rand.hh b/include/gz/math/Rand.hh index c1f9a1340..a911f2be3 100644 --- a/include/gz/math/Rand.hh +++ b/include/gz/math/Rand.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_RAND_HH_ -#define IGNITION_MATH_RAND_HH_ +#ifndef GZ_MATH_RAND_HH_ +#define GZ_MATH_RAND_HH_ #include #include #include -#include -#include +#include +#include namespace ignition { diff --git a/include/gz/math/Region3.hh b/include/gz/math/Region3.hh index 339a9d91b..70e2e43f9 100644 --- a/include/gz/math/Region3.hh +++ b/include/gz/math/Region3.hh @@ -14,17 +14,17 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_REGION3_HH_ -#define IGNITION_MATH_REGION3_HH_ +#ifndef GZ_MATH_REGION3_HH_ +#define GZ_MATH_REGION3_HH_ #include #include #include #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -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 ff49dbdec..f56f07524 100644 --- a/include/gz/math/RollingMean.hh +++ b/include/gz/math/RollingMean.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_ROLLINGMEAN_HH_ -#define IGNITION_MATH_ROLLINGMEAN_HH_ +#ifndef GZ_MATH_ROLLINGMEAN_HH_ +#define GZ_MATH_ROLLINGMEAN_HH_ #include -#include -#include +#include +#include namespace ignition { diff --git a/include/gz/math/RotationSpline.hh b/include/gz/math/RotationSpline.hh index 4c4c6b8d9..c89609510 100644 --- a/include/gz/math/RotationSpline.hh +++ b/include/gz/math/RotationSpline.hh @@ -14,11 +14,11 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_ROTATIONSPLINE_HH_ -#define IGNITION_MATH_ROTATIONSPLINE_HH_ +#ifndef GZ_MATH_ROTATIONSPLINE_HH_ +#define GZ_MATH_ROTATIONSPLINE_HH_ -#include -#include +#include +#include namespace ignition { diff --git a/include/gz/math/SemanticVersion.hh b/include/gz/math/SemanticVersion.hh index d3420e5a3..136ce853b 100644 --- a/include/gz/math/SemanticVersion.hh +++ b/include/gz/math/SemanticVersion.hh @@ -15,13 +15,13 @@ * */ -#ifndef IGNITION_MATH_SEMANTICVERSION_HH_ -#define IGNITION_MATH_SEMANTICVERSION_HH_ +#ifndef GZ_MATH_SEMANTICVERSION_HH_ +#define GZ_MATH_SEMANTICVERSION_HH_ #include #include -#include -#include +#include +#include namespace ignition { diff --git a/include/gz/math/SignalStats.hh b/include/gz/math/SignalStats.hh index 2e1924ebe..360800bec 100644 --- a/include/gz/math/SignalStats.hh +++ b/include/gz/math/SignalStats.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_SIGNALSTATS_HH_ -#define IGNITION_MATH_SIGNALSTATS_HH_ +#ifndef GZ_MATH_SIGNALSTATS_HH_ +#define GZ_MATH_SIGNALSTATS_HH_ #include #include #include -#include -#include +#include +#include namespace ignition { diff --git a/include/gz/math/SpeedLimiter.hh b/include/gz/math/SpeedLimiter.hh index 0376ff7b4..e90ce8f20 100644 --- a/include/gz/math/SpeedLimiter.hh +++ b/include/gz/math/SpeedLimiter.hh @@ -15,13 +15,13 @@ * */ -#ifndef IGNITION_MATH_SYSTEMS_SPEEDLIMITER_HH_ -#define IGNITION_MATH_SYSTEMS_SPEEDLIMITER_HH_ +#ifndef GZ_MATH_SYSTEMS_SPEEDLIMITER_HH_ +#define GZ_MATH_SYSTEMS_SPEEDLIMITER_HH_ #include #include -#include -#include "ignition/math/Helpers.hh" +#include +#include "gz/math/Helpers.hh" namespace ignition { diff --git a/include/gz/math/Sphere.hh b/include/gz/math/Sphere.hh index 537bd109f..8da5a82d1 100644 --- a/include/gz/math/Sphere.hh +++ b/include/gz/math/Sphere.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_SPHERE_HH_ -#define IGNITION_MATH_SPHERE_HH_ +#ifndef GZ_MATH_SPHERE_HH_ +#define GZ_MATH_SPHERE_HH_ -#include "ignition/math/MassMatrix3.hh" -#include "ignition/math/Material.hh" -#include "ignition/math/Quaternion.hh" -#include "ignition/math/Plane.hh" +#include "gz/math/MassMatrix3.hh" +#include "gz/math/Material.hh" +#include "gz/math/Quaternion.hh" +#include "gz/math/Plane.hh" namespace ignition { @@ -66,11 +66,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. @@ -137,7 +137,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 @@ -154,6 +154,6 @@ namespace ignition } } } -#include "ignition/math/detail/Sphere.hh" +#include "gz/math/detail/Sphere.hh" #endif diff --git a/include/gz/math/SphericalCoordinates.hh b/include/gz/math/SphericalCoordinates.hh index 120407ab6..ecdbf4602 100644 --- a/include/gz/math/SphericalCoordinates.hh +++ b/include/gz/math/SphericalCoordinates.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_SPHERICALCOORDINATES_HH_ -#define IGNITION_MATH_SPHERICALCOORDINATES_HH_ +#ifndef GZ_MATH_SPHERICALCOORDINATES_HH_ +#define GZ_MATH_SPHERICALCOORDINATES_HH_ #include #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { @@ -82,10 +82,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 Copy constructor. /// \param[in] _sc Spherical coordinates to copy. @@ -107,8 +107,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. @@ -121,8 +121,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"]. @@ -144,10 +144,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. @@ -155,11 +155,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. @@ -169,7 +169,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. @@ -177,11 +177,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. @@ -189,23 +189,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(); @@ -216,8 +216,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 @@ -226,8 +226,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 ee2658223..353aba3fe 100644 --- a/include/gz/math/Spline.hh +++ b/include/gz/math/Spline.hh @@ -16,12 +16,12 @@ */ // Note: Originally cribbed from Ogre3d. Modified to implement Cardinal // spline and catmull-rom spline -#ifndef IGNITION_MATH_SPLINE_HH_ -#define IGNITION_MATH_SPLINE_HH_ +#ifndef GZ_MATH_SPLINE_HH_ +#define GZ_MATH_SPLINE_HH_ -#include -#include -#include +#include +#include +#include namespace ignition { diff --git a/include/gz/math/Stopwatch.hh b/include/gz/math/Stopwatch.hh index f469672f5..e1eca283c 100644 --- a/include/gz/math/Stopwatch.hh +++ b/include/gz/math/Stopwatch.hh @@ -15,13 +15,13 @@ * */ -#ifndef IGNITION_MATH_STOPWATCH_HH_ -#define IGNITION_MATH_STOPWATCH_HH_ +#ifndef GZ_MATH_STOPWATCH_HH_ +#define GZ_MATH_STOPWATCH_HH_ #include #include -#include -#include +#include +#include namespace ignition { @@ -48,7 +48,7 @@ namespace ignition /// # Example usage /// /// ```{.cpp} - /// ignition::math::Stopwatch watch; + /// gz::math::Stopwatch watch; /// watch.Start(); /// /// // do something... diff --git a/include/gz/math/Temperature.hh b/include/gz/math/Temperature.hh index 067137ec8..e08c63321 100644 --- a/include/gz/math/Temperature.hh +++ b/include/gz/math/Temperature.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_TEMPERATURE_HH_ -#define IGNITION_MATH_TEMPERATURE_HH_ +#ifndef GZ_MATH_TEMPERATURE_HH_ +#define GZ_MATH_TEMPERATURE_HH_ #include #include -#include -#include "ignition/math/Helpers.hh" +#include +#include "gz/math/Helpers.hh" namespace ignition { @@ -48,11 +48,11 @@ namespace ignition /// /// ### Convert from Kelvin to Celsius ### /// - /// double celsius = ignition::math::Temperature::KelvinToCelsius(2.5); + /// double celsius = gz::math::Temperature::KelvinToCelsius(2.5); /// /// ### Create and use a Temperature object ### /// - /// ignition::math::Temperature temp(123.5); + /// gz::math::Temperature temp(123.5); /// std::cout << "Temperature in Kelvin = " << temp << std::endl; /// std::cout << "Temperature in Celsius = " /// << temp.Celsius() << std::endl; @@ -60,7 +60,7 @@ namespace ignition /// temp += 100.0; /// std::cout << "Temperature + 100.0 = " << temp << "K" << std::endl; /// - /// ignition::math::Temperature newTemp(temp); + /// gz::math::Temperature newTemp(temp); /// newTemp += temp + 23.5; /// std::cout << "Copied the temp object and added 23.5K. newTemp = " /// << newTemp.Fahrenheit() << "F" << std::endl; @@ -378,7 +378,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; @@ -390,7 +390,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 6ad394ae0..44f68d241 100644 --- a/include/gz/math/Triangle.hh +++ b/include/gz/math/Triangle.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_TRIANGLE_HH_ -#define IGNITION_MATH_TRIANGLE_HH_ +#ifndef GZ_MATH_TRIANGLE_HH_ +#define GZ_MATH_TRIANGLE_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/math/Triangle3.hh b/include/gz/math/Triangle3.hh index f68d5c187..215118dfb 100644 --- a/include/gz/math/Triangle3.hh +++ b/include/gz/math/Triangle3.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_TRIANGLE3_HH_ -#define IGNITION_MATH_TRIANGLE3_HH_ +#ifndef GZ_MATH_TRIANGLE3_HH_ +#define GZ_MATH_TRIANGLE3_HH_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/math/Vector2.hh b/include/gz/math/Vector2.hh index 6bf68b1d0..a30780244 100644 --- a/include/gz/math/Vector2.hh +++ b/include/gz/math/Vector2.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_VECTOR2_HH_ -#define IGNITION_MATH_VECTOR2_HH_ +#ifndef GZ_MATH_VECTOR2_HH_ +#define GZ_MATH_VECTOR2_HH_ #include #include #include -#include -#include +#include +#include namespace ignition { diff --git a/include/gz/math/Vector3.hh b/include/gz/math/Vector3.hh index 85952e13a..3c286c295 100644 --- a/include/gz/math/Vector3.hh +++ b/include/gz/math/Vector3.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_VECTOR3_HH_ -#define IGNITION_MATH_VECTOR3_HH_ +#ifndef GZ_MATH_VECTOR3_HH_ +#define GZ_MATH_VECTOR3_HH_ #include #include @@ -23,8 +23,8 @@ #include #include -#include -#include +#include +#include namespace ignition { @@ -727,7 +727,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) { _out << precision(_pt[0], 6) << " " << precision(_pt[1], 6) << " " << precision(_pt[2], 6); @@ -739,7 +739,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 65d45ba45..d34f55f1e 100644 --- a/include/gz/math/Vector3Stats.hh +++ b/include/gz/math/Vector3Stats.hh @@ -14,14 +14,14 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_VECTOR3STATS_HH_ -#define IGNITION_MATH_VECTOR3STATS_HH_ +#ifndef GZ_MATH_VECTOR3STATS_HH_ +#define GZ_MATH_VECTOR3STATS_HH_ #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { diff --git a/include/gz/math/Vector4.hh b/include/gz/math/Vector4.hh index 9d81d1d85..091b9b1c7 100644 --- a/include/gz/math/Vector4.hh +++ b/include/gz/math/Vector4.hh @@ -14,16 +14,16 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_VECTOR4_HH_ -#define IGNITION_MATH_VECTOR4_HH_ +#ifndef GZ_MATH_VECTOR4_HH_ +#define GZ_MATH_VECTOR4_HH_ #include #include #include -#include -#include -#include +#include +#include +#include namespace ignition { @@ -705,7 +705,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) { _out << _pt[0] << " " << _pt[1] << " " << _pt[2] << " " << _pt[3]; return _out; @@ -716,7 +716,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/config.hh.in b/include/gz/math/config.hh.in index 84c001136..f395bdce7 100644 --- a/include/gz/math/config.hh.in +++ b/include/gz/math/config.hh.in @@ -15,3 +15,12 @@ #cmakedefine IGNITION_MATH_BUILD_TYPE_PROFILE 1 #cmakedefine IGNITION_MATH_BUILD_TYPE_DEBUG 1 #cmakedefine IGNITION_MATH_BUILD_TYPE_RELEASE 1 + +namespace ignition +{ +} + +namespace gz +{ + using namespace ignition; +} diff --git a/include/gz/math/detail/Box.hh b/include/gz/math/detail/Box.hh index 2ce5f0f9b..229d1d6ee 100644 --- a/include/gz/math/detail/Box.hh +++ b/include/gz/math/detail/Box.hh @@ -14,10 +14,10 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_DETAIL_BOX_HH_ -#define IGNITION_MATH_DETAIL_BOX_HH_ +#ifndef GZ_MATH_DETAIL_BOX_HH_ +#define GZ_MATH_DETAIL_BOX_HH_ -#include "ignition/math/Triangle3.hh" +#include "gz/math/Triangle3.hh" #include #include @@ -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 ebf52b616..b3cd6d745 100644 --- a/include/gz/math/detail/Capsule.hh +++ b/include/gz/math/detail/Capsule.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_DETAIL_CAPSULE_HH_ -#define IGNITION_MATH_DETAIL_CAPSULE_HH_ +#ifndef GZ_MATH_DETAIL_CAPSULE_HH_ +#define GZ_MATH_DETAIL_CAPSULE_HH_ #include #include -#include -#include +#include +#include namespace ignition { diff --git a/include/gz/math/detail/Cylinder.hh b/include/gz/math/detail/Cylinder.hh index ac4a96722..afb141aa5 100644 --- a/include/gz/math/detail/Cylinder.hh +++ b/include/gz/math/detail/Cylinder.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_DETAIL_CYLINDER_HH_ -#define IGNITION_MATH_DETAIL_CYLINDER_HH_ +#ifndef GZ_MATH_DETAIL_CYLINDER_HH_ +#define GZ_MATH_DETAIL_CYLINDER_HH_ namespace ignition { namespace math diff --git a/include/gz/math/detail/Ellipsoid.hh b/include/gz/math/detail/Ellipsoid.hh index bc1c16f84..b84522010 100644 --- a/include/gz/math/detail/Ellipsoid.hh +++ b/include/gz/math/detail/Ellipsoid.hh @@ -14,13 +14,13 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_DETAIL_ELLIPSOID_HH_ -#define IGNITION_MATH_DETAIL_ELLIPSOID_HH_ +#ifndef GZ_MATH_DETAIL_ELLIPSOID_HH_ +#define GZ_MATH_DETAIL_ELLIPSOID_HH_ #include #include -#include -#include +#include +#include namespace ignition { diff --git a/include/gz/math/detail/Sphere.hh b/include/gz/math/detail/Sphere.hh index 740ee6741..84f6293ec 100644 --- a/include/gz/math/detail/Sphere.hh +++ b/include/gz/math/detail/Sphere.hh @@ -14,10 +14,10 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_DETAIL_SPHERE_HH_ -#define IGNITION_MATH_DETAIL_SPHERE_HH_ +#ifndef GZ_MATH_DETAIL_SPHERE_HH_ +#define GZ_MATH_DETAIL_SPHERE_HH_ -#include "ignition/math/Sphere.hh" +#include "gz/math/Sphere.hh" namespace ignition { @@ -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 1040a9bf5..98aebfa7c 100644 --- a/include/gz/math/detail/WellOrderedVector.hh +++ b/include/gz/math/detail/WellOrderedVector.hh @@ -14,9 +14,9 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_DETAIL_WELLORDERED_VECTOR_HH_ -#define IGNITION_MATH_DETAIL_WELLORDERED_VECTOR_HH_ -#include +#ifndef GZ_MATH_DETAIL_WELLORDERED_VECTOR_HH_ +#define GZ_MATH_DETAIL_WELLORDERED_VECTOR_HH_ +#include namespace ignition { diff --git a/include/gz/math/graph/Edge.hh b/include/gz/math/graph/Edge.hh index db68db461..f0f777e77 100644 --- a/include/gz/math/graph/Edge.hh +++ b/include/gz/math/graph/Edge.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_GRAPH_EDGE_HH_ -#define IGNITION_MATH_GRAPH_EDGE_HH_ +#ifndef GZ_MATH_GRAPH_EDGE_HH_ +#define GZ_MATH_GRAPH_EDGE_HH_ // uint64_t #include @@ -24,8 +24,8 @@ #include #include -#include -#include "ignition/math/graph/Vertex.hh" +#include +#include "gz/math/graph/Vertex.hh" namespace ignition { diff --git a/include/gz/math/graph/Graph.hh b/include/gz/math/graph/Graph.hh index 02e402371..05b5c9414 100644 --- a/include/gz/math/graph/Graph.hh +++ b/include/gz/math/graph/Graph.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_GRAPH_GRAPH_HH_ -#define IGNITION_MATH_GRAPH_GRAPH_HH_ +#ifndef GZ_MATH_GRAPH_GRAPH_HH_ +#define GZ_MATH_GRAPH_GRAPH_HH_ #include #include @@ -25,9 +25,9 @@ #include #include -#include -#include "ignition/math/graph/Edge.hh" -#include "ignition/math/graph/Vertex.hh" +#include +#include "gz/math/graph/Edge.hh" +#include "gz/math/graph/Vertex.hh" namespace ignition { @@ -50,7 +50,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"} @@ -63,7 +63,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} @@ -77,7 +77,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} @@ -88,7 +88,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 0d3677384..2d6e55703 100644 --- a/include/gz/math/graph/GraphAlgorithms.hh +++ b/include/gz/math/graph/GraphAlgorithms.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_GRAPH_GRAPHALGORITHMS_HH_ -#define IGNITION_MATH_GRAPH_GRAPHALGORITHMS_HH_ +#ifndef GZ_MATH_GRAPH_GRAPHALGORITHMS_HH_ +#define GZ_MATH_GRAPH_GRAPHALGORITHMS_HH_ #include #include @@ -25,9 +25,9 @@ #include #include -#include -#include "ignition/math/graph/Graph.hh" -#include "ignition/math/Helpers.hh" +#include +#include "gz/math/graph/Graph.hh" +#include "gz/math/Helpers.hh" namespace ignition { diff --git a/include/gz/math/graph/Vertex.hh b/include/gz/math/graph/Vertex.hh index b65b73b6d..46c8f007b 100644 --- a/include/gz/math/graph/Vertex.hh +++ b/include/gz/math/graph/Vertex.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_GRAPH_VERTEX_HH_ -#define IGNITION_MATH_GRAPH_VERTEX_HH_ +#ifndef GZ_MATH_GRAPH_VERTEX_HH_ +#define GZ_MATH_GRAPH_VERTEX_HH_ // uint64_t #include @@ -25,8 +25,8 @@ #include #include -#include -#include +#include +#include namespace ignition { diff --git a/include/gz/math/math.hh.in b/include/gz/math/math.hh.in index 4b76db86d..32d48f66a 100644 --- a/include/gz/math/math.hh.in +++ b/include/gz/math/math.hh.in @@ -1,3 +1,3 @@ // Automatically generated -#include +#include ${ign_headers} diff --git a/include/ignition/math.hh b/include/ignition/math.hh new file mode 100644 index 000000000..cad1e2c96 --- /dev/null +++ b/include/ignition/math.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/AdditivelySeparableScalarField3.hh b/include/ignition/math/AdditivelySeparableScalarField3.hh new file mode 100644 index 000000000..62620a374 --- /dev/null +++ b/include/ignition/math/AdditivelySeparableScalarField3.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Angle.hh b/include/ignition/math/Angle.hh new file mode 100644 index 000000000..29188f1ec --- /dev/null +++ b/include/ignition/math/Angle.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/AxisAlignedBox.hh b/include/ignition/math/AxisAlignedBox.hh new file mode 100644 index 000000000..4229cbd72 --- /dev/null +++ b/include/ignition/math/AxisAlignedBox.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Box.hh b/include/ignition/math/Box.hh new file mode 100644 index 000000000..f517d2dea --- /dev/null +++ b/include/ignition/math/Box.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Capsule.hh b/include/ignition/math/Capsule.hh new file mode 100644 index 000000000..cd30f01c4 --- /dev/null +++ b/include/ignition/math/Capsule.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Color.hh b/include/ignition/math/Color.hh new file mode 100644 index 000000000..4d25c3c78 --- /dev/null +++ b/include/ignition/math/Color.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Cylinder.hh b/include/ignition/math/Cylinder.hh new file mode 100644 index 000000000..9742d05ad --- /dev/null +++ b/include/ignition/math/Cylinder.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/DiffDriveOdometry.hh b/include/ignition/math/DiffDriveOdometry.hh new file mode 100644 index 000000000..360400b56 --- /dev/null +++ b/include/ignition/math/DiffDriveOdometry.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Ellipsoid.hh b/include/ignition/math/Ellipsoid.hh new file mode 100644 index 000000000..f836ca057 --- /dev/null +++ b/include/ignition/math/Ellipsoid.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Export.hh b/include/ignition/math/Export.hh new file mode 100644 index 000000000..04084226f --- /dev/null +++ b/include/ignition/math/Export.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Filter.hh b/include/ignition/math/Filter.hh new file mode 100644 index 000000000..636aa4caf --- /dev/null +++ b/include/ignition/math/Filter.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Frustum.hh b/include/ignition/math/Frustum.hh new file mode 100644 index 000000000..3b089d8ee --- /dev/null +++ b/include/ignition/math/Frustum.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/GaussMarkovProcess.hh b/include/ignition/math/GaussMarkovProcess.hh new file mode 100644 index 000000000..7c9802c45 --- /dev/null +++ b/include/ignition/math/GaussMarkovProcess.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Helpers.hh b/include/ignition/math/Helpers.hh new file mode 100644 index 000000000..e140adc89 --- /dev/null +++ b/include/ignition/math/Helpers.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Inertial.hh b/include/ignition/math/Inertial.hh new file mode 100644 index 000000000..2f2b93e75 --- /dev/null +++ b/include/ignition/math/Inertial.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Interval.hh b/include/ignition/math/Interval.hh new file mode 100644 index 000000000..ce17d0916 --- /dev/null +++ b/include/ignition/math/Interval.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Kmeans.hh b/include/ignition/math/Kmeans.hh new file mode 100644 index 000000000..7067b32e3 --- /dev/null +++ b/include/ignition/math/Kmeans.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Line2.hh b/include/ignition/math/Line2.hh new file mode 100644 index 000000000..bbdefa9ea --- /dev/null +++ b/include/ignition/math/Line2.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Line3.hh b/include/ignition/math/Line3.hh new file mode 100644 index 000000000..23795634a --- /dev/null +++ b/include/ignition/math/Line3.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/MassMatrix3.hh b/include/ignition/math/MassMatrix3.hh new file mode 100644 index 000000000..b79e8c16c --- /dev/null +++ b/include/ignition/math/MassMatrix3.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Material.hh b/include/ignition/math/Material.hh new file mode 100644 index 000000000..1e57794db --- /dev/null +++ b/include/ignition/math/Material.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/MaterialType.hh b/include/ignition/math/MaterialType.hh new file mode 100644 index 000000000..a5cdb889f --- /dev/null +++ b/include/ignition/math/MaterialType.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Matrix3.hh b/include/ignition/math/Matrix3.hh new file mode 100644 index 000000000..3deada8ff --- /dev/null +++ b/include/ignition/math/Matrix3.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Matrix4.hh b/include/ignition/math/Matrix4.hh new file mode 100644 index 000000000..4f5359cc0 --- /dev/null +++ b/include/ignition/math/Matrix4.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Matrix6.hh b/include/ignition/math/Matrix6.hh new file mode 100644 index 000000000..319f5c7e8 --- /dev/null +++ b/include/ignition/math/Matrix6.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/MovingWindowFilter.hh b/include/ignition/math/MovingWindowFilter.hh new file mode 100644 index 000000000..42550b5a2 --- /dev/null +++ b/include/ignition/math/MovingWindowFilter.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/OrientedBox.hh b/include/ignition/math/OrientedBox.hh new file mode 100644 index 000000000..5642ecb0e --- /dev/null +++ b/include/ignition/math/OrientedBox.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/PID.hh b/include/ignition/math/PID.hh new file mode 100644 index 000000000..dba527832 --- /dev/null +++ b/include/ignition/math/PID.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/PiecewiseScalarField3.hh b/include/ignition/math/PiecewiseScalarField3.hh new file mode 100644 index 000000000..c52dd227b --- /dev/null +++ b/include/ignition/math/PiecewiseScalarField3.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Plane.hh b/include/ignition/math/Plane.hh new file mode 100644 index 000000000..bf1fcf1a5 --- /dev/null +++ b/include/ignition/math/Plane.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Polynomial3.hh b/include/ignition/math/Polynomial3.hh new file mode 100644 index 000000000..9f1238926 --- /dev/null +++ b/include/ignition/math/Polynomial3.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Pose3.hh b/include/ignition/math/Pose3.hh new file mode 100644 index 000000000..5981cc5f8 --- /dev/null +++ b/include/ignition/math/Pose3.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Quaternion.hh b/include/ignition/math/Quaternion.hh new file mode 100644 index 000000000..dc9900eec --- /dev/null +++ b/include/ignition/math/Quaternion.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Rand.hh b/include/ignition/math/Rand.hh new file mode 100644 index 000000000..9bbd2e77f --- /dev/null +++ b/include/ignition/math/Rand.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Region3.hh b/include/ignition/math/Region3.hh new file mode 100644 index 000000000..4b7564ef1 --- /dev/null +++ b/include/ignition/math/Region3.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/RollingMean.hh b/include/ignition/math/RollingMean.hh new file mode 100644 index 000000000..ce8f54411 --- /dev/null +++ b/include/ignition/math/RollingMean.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/RotationSpline.hh b/include/ignition/math/RotationSpline.hh new file mode 100644 index 000000000..c403c7266 --- /dev/null +++ b/include/ignition/math/RotationSpline.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/SemanticVersion.hh b/include/ignition/math/SemanticVersion.hh new file mode 100644 index 000000000..903aa1f30 --- /dev/null +++ b/include/ignition/math/SemanticVersion.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/SignalStats.hh b/include/ignition/math/SignalStats.hh new file mode 100644 index 000000000..0682f8d5e --- /dev/null +++ b/include/ignition/math/SignalStats.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/SpeedLimiter.hh b/include/ignition/math/SpeedLimiter.hh new file mode 100644 index 000000000..76ff2c8d2 --- /dev/null +++ b/include/ignition/math/SpeedLimiter.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Sphere.hh b/include/ignition/math/Sphere.hh new file mode 100644 index 000000000..6f398538f --- /dev/null +++ b/include/ignition/math/Sphere.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/SphericalCoordinates.hh b/include/ignition/math/SphericalCoordinates.hh new file mode 100644 index 000000000..c4109bce2 --- /dev/null +++ b/include/ignition/math/SphericalCoordinates.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Spline.hh b/include/ignition/math/Spline.hh new file mode 100644 index 000000000..47688d66e --- /dev/null +++ b/include/ignition/math/Spline.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Stopwatch.hh b/include/ignition/math/Stopwatch.hh new file mode 100644 index 000000000..4354dda68 --- /dev/null +++ b/include/ignition/math/Stopwatch.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Temperature.hh b/include/ignition/math/Temperature.hh new file mode 100644 index 000000000..6fc6ea4a4 --- /dev/null +++ b/include/ignition/math/Temperature.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Triangle.hh b/include/ignition/math/Triangle.hh new file mode 100644 index 000000000..9fd46e9cc --- /dev/null +++ b/include/ignition/math/Triangle.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Triangle3.hh b/include/ignition/math/Triangle3.hh new file mode 100644 index 000000000..423c1c04c --- /dev/null +++ b/include/ignition/math/Triangle3.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Vector2.hh b/include/ignition/math/Vector2.hh new file mode 100644 index 000000000..71f4d6861 --- /dev/null +++ b/include/ignition/math/Vector2.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Vector3.hh b/include/ignition/math/Vector3.hh new file mode 100644 index 000000000..b8bbc8965 --- /dev/null +++ b/include/ignition/math/Vector3.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Vector3Stats.hh b/include/ignition/math/Vector3Stats.hh new file mode 100644 index 000000000..af30f152d --- /dev/null +++ b/include/ignition/math/Vector3Stats.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/Vector4.hh b/include/ignition/math/Vector4.hh new file mode 100644 index 000000000..a41a0d2d4 --- /dev/null +++ b/include/ignition/math/Vector4.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/config.hh b/include/ignition/math/config.hh new file mode 100644 index 000000000..a83a60c8b --- /dev/null +++ b/include/ignition/math/config.hh @@ -0,0 +1,48 @@ +/* + * 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. + * + */ + +#ifndef IGNITION_MATH__CONFIG_HH_ +#define IGNITION_MATH__CONFIG_HH_ + +#include + +/* Version number */ +// #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 + +/* #undef IGNITION_MATH_BUILD_TYPE_PROFILE */ +/* #undef IGNITION_MATH_BUILD_TYPE_DEBUG */ +/* #undef IGNITION_MATH_BUILD_TYPE_RELEASE */ + +namespace ignition +{ +} + +namespace gz +{ + using namespace ignition; +} + +#endif diff --git a/include/ignition/math/graph/Edge.hh b/include/ignition/math/graph/Edge.hh new file mode 100644 index 000000000..9a36fadd7 --- /dev/null +++ b/include/ignition/math/graph/Edge.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/graph/Graph.hh b/include/ignition/math/graph/Graph.hh new file mode 100644 index 000000000..cae7123d7 --- /dev/null +++ b/include/ignition/math/graph/Graph.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/graph/GraphAlgorithms.hh b/include/ignition/math/graph/GraphAlgorithms.hh new file mode 100644 index 000000000..beb36fea4 --- /dev/null +++ b/include/ignition/math/graph/GraphAlgorithms.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/include/ignition/math/graph/Vertex.hh b/include/ignition/math/graph/Vertex.hh new file mode 100644 index 000000000..f1e2f7d45 --- /dev/null +++ b/include/ignition/math/graph/Vertex.hh @@ -0,0 +1,19 @@ +/* + * 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 +#include diff --git a/src/AdditivelySeparableScalarField3_TEST.cc b/src/AdditivelySeparableScalarField3_TEST.cc index bbd52d323..78d4bd6ad 100644 --- a/src/AdditivelySeparableScalarField3_TEST.cc +++ b/src/AdditivelySeparableScalarField3_TEST.cc @@ -18,10 +18,10 @@ #include #include -#include "ignition/math/AdditivelySeparableScalarField3.hh" -#include "ignition/math/Polynomial3.hh" +#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 296729a1c..632dee6c3 100644 --- a/src/Angle.cc +++ b/src/Angle.cc @@ -14,10 +14,10 @@ * limitations under the License. * */ -#include "ignition/math/Helpers.hh" -#include "ignition/math/Angle.hh" +#include "gz/math/Helpers.hh" +#include "gz/math/Angle.hh" -using namespace ignition::math; +using namespace gz::math; const Angle Angle::Zero = Angle(0); const Angle Angle::Pi = Angle(IGN_PI); diff --git a/src/Angle_TEST.cc b/src/Angle_TEST.cc index d99d7c7d0..8d4fe5f8f 100644 --- a/src/Angle_TEST.cc +++ b/src/Angle_TEST.cc @@ -19,10 +19,10 @@ #include -#include "ignition/math/Helpers.hh" -#include "ignition/math/Angle.hh" +#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 af6f15a6d..2d308e825 100644 --- a/src/AxisAlignedBox.cc +++ b/src/AxisAlignedBox.cc @@ -15,13 +15,13 @@ * */ #include -#include +#include -using namespace ignition; +using namespace gz; using namespace math; // Private data for AxisAlignedBox class -class ignition::math::AxisAlignedBoxPrivate +class gz::math::AxisAlignedBoxPrivate { /// \brief Minimum corner of the box public: Vector3d min = Vector3d(MAX_D, MAX_D, MAX_D); diff --git a/src/AxisAlignedBox_TEST.cc b/src/AxisAlignedBox_TEST.cc index dadbf0388..79116cc94 100644 --- a/src/AxisAlignedBox_TEST.cc +++ b/src/AxisAlignedBox_TEST.cc @@ -17,9 +17,9 @@ #include #include -#include "ignition/math/AxisAlignedBox.hh" +#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 454abf4cb..8be010c6e 100644 --- a/src/Box_TEST.cc +++ b/src/Box_TEST.cc @@ -17,9 +17,9 @@ #include #include -#include "ignition/math/Box.hh" +#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 bb09828d9..e2fdd0e8c 100644 --- a/src/Capsule_TEST.cc +++ b/src/Capsule_TEST.cc @@ -18,10 +18,10 @@ #include #include -#include "ignition/math/Capsule.hh" -#include "ignition/math/Helpers.hh" +#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 41dcd40a1..3fcbc24b9 100644 --- a/src/Color.cc +++ b/src/Color.cc @@ -17,9 +17,9 @@ #include #include -#include "ignition/math/Color.hh" +#include "gz/math/Color.hh" -using namespace ignition; +using namespace gz; using namespace math; const Color Color::White = Color(1, 1, 1, 1); diff --git a/src/Color_TEST.cc b/src/Color_TEST.cc index 382d38673..b91ba1cb4 100644 --- a/src/Color_TEST.cc +++ b/src/Color_TEST.cc @@ -17,9 +17,9 @@ #include #include -#include +#include -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(Color, ConstColors) diff --git a/src/Cylinder_TEST.cc b/src/Cylinder_TEST.cc index c0ad31de2..c9e5df94e 100644 --- a/src/Cylinder_TEST.cc +++ b/src/Cylinder_TEST.cc @@ -18,9 +18,9 @@ #include #include -#include "ignition/math/Cylinder.hh" +#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 d184b8e02..f86905b57 100644 --- a/src/DiffDriveOdometry.cc +++ b/src/DiffDriveOdometry.cc @@ -15,15 +15,15 @@ * */ #include -#include "ignition/math/DiffDriveOdometry.hh" -#include "ignition/math/RollingMean.hh" +#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::DiffDriveOdometryPrivate +class gz::math::DiffDriveOdometryPrivate { /// \brief Integrates the velocities (linear and angular) using 2nd order /// Runge-Kutta. diff --git a/src/DiffDriveOdometry_TEST.cc b/src/DiffDriveOdometry_TEST.cc index 6bc531f11..68fd06c56 100644 --- a/src/DiffDriveOdometry_TEST.cc +++ b/src/DiffDriveOdometry_TEST.cc @@ -18,11 +18,11 @@ #include #include -#include "ignition/math/Angle.hh" -#include "ignition/math/Helpers.hh" -#include "ignition/math/DiffDriveOdometry.hh" +#include "gz/math/Angle.hh" +#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 3d89f15df..951401bba 100644 --- a/src/Ellipsoid_TEST.cc +++ b/src/Ellipsoid_TEST.cc @@ -18,11 +18,11 @@ #include #include -#include "ignition/math/Ellipsoid.hh" -#include "ignition/math/Helpers.hh" -#include "ignition/math/Vector3.hh" +#include "gz/math/Ellipsoid.hh" +#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 84510665b..aa9e9264f 100644 --- a/src/Filter_TEST.cc +++ b/src/Filter_TEST.cc @@ -17,9 +17,9 @@ #include -#include "ignition/math/Filter.hh" +#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 22fa0ca6a..c835a3960 100644 --- a/src/Frustum.cc +++ b/src/Frustum.cc @@ -16,12 +16,12 @@ */ #include -#include "ignition/math/AxisAlignedBox.hh" -#include "ignition/math/Frustum.hh" -#include "ignition/math/Matrix4.hh" +#include "gz/math/AxisAlignedBox.hh" +#include "gz/math/Frustum.hh" +#include "gz/math/Matrix4.hh" #include "FrustumPrivate.hh" -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// diff --git a/src/FrustumPrivate.hh b/src/FrustumPrivate.hh index 3077655e5..dae03a740 100644 --- a/src/FrustumPrivate.hh +++ b/src/FrustumPrivate.hh @@ -14,15 +14,15 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_FRUSTUMPRIVATE_HH_ -#define IGNITION_MATH_FRUSTUMPRIVATE_HH_ +#ifndef GZ_MATH_FRUSTUMPRIVATE_HH_ +#define GZ_MATH_FRUSTUMPRIVATE_HH_ #include #include -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { diff --git a/src/Frustum_TEST.cc b/src/Frustum_TEST.cc index 492af9f32..0417eaa2a 100644 --- a/src/Frustum_TEST.cc +++ b/src/Frustum_TEST.cc @@ -17,10 +17,10 @@ #include -#include "ignition/math/Helpers.hh" -#include "ignition/math/Frustum.hh" +#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 311de7e54..118bbb3ed 100644 --- a/src/GaussMarkovProcess.cc +++ b/src/GaussMarkovProcess.cc @@ -15,13 +15,13 @@ * */ -#include -#include +#include +#include -using namespace ignition::math; +using namespace gz::math; ////////////////////////////////////////////////// -class ignition::math::GaussMarkovProcessPrivate +class gz::math::GaussMarkovProcessPrivate { /// \brief Current process value. public: double value{0}; diff --git a/src/GaussMarkovProcess_TEST.cc b/src/GaussMarkovProcess_TEST.cc index cc96cea56..cf239a083 100644 --- a/src/GaussMarkovProcess_TEST.cc +++ b/src/GaussMarkovProcess_TEST.cc @@ -17,11 +17,11 @@ #include -#include "ignition/math/GaussMarkovProcess.hh" -#include "ignition/math/Helpers.hh" -#include "ignition/math/Rand.hh" +#include "gz/math/GaussMarkovProcess.hh" +#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 85c17962f..d4622b367 100644 --- a/src/Helpers.cc +++ b/src/Helpers.cc @@ -14,7 +14,7 @@ * limitations under the License. * */ -#include "ignition/math/Helpers.hh" +#include "gz/math/Helpers.hh" namespace ignition { diff --git a/src/Helpers_TEST.cc b/src/Helpers_TEST.cc index a602f210d..7734d16ca 100644 --- a/src/Helpers_TEST.cc +++ b/src/Helpers_TEST.cc @@ -17,11 +17,11 @@ #include -#include "ignition/math/Rand.hh" -#include "ignition/math/Vector3.hh" -#include "ignition/math/Helpers.hh" +#include "gz/math/Rand.hh" +#include "gz/math/Vector3.hh" +#include "gz/math/Helpers.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// // Test a few function in Helpers diff --git a/src/Inertial_TEST.cc b/src/Inertial_TEST.cc index b5793cd4f..55d804c16 100644 --- a/src/Inertial_TEST.cc +++ b/src/Inertial_TEST.cc @@ -18,9 +18,9 @@ #include #include -#include "ignition/math/Inertial.hh" +#include "gz/math/Inertial.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// /// \brief Compare quaternions, but allow rotations of PI about any axis. diff --git a/src/Interval_TEST.cc b/src/Interval_TEST.cc index ecd0c8ee1..f03332ea3 100644 --- a/src/Interval_TEST.cc +++ b/src/Interval_TEST.cc @@ -17,9 +17,9 @@ #include #include -#include "ignition/math/Interval.hh" +#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 41dce68c1..f8e2af4e9 100644 --- a/src/Kmeans.cc +++ b/src/Kmeans.cc @@ -15,14 +15,14 @@ * */ -#include +#include #include -#include +#include #include "KmeansPrivate.hh" -using namespace ignition; +using namespace gz; using namespace math; ////////////////////////////////////////////////// diff --git a/src/KmeansPrivate.hh b/src/KmeansPrivate.hh index bcda8ef77..8c868dccf 100644 --- a/src/KmeansPrivate.hh +++ b/src/KmeansPrivate.hh @@ -14,13 +14,13 @@ * 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 +#include +#include +#include namespace ignition { diff --git a/src/Kmeans_TEST.cc b/src/Kmeans_TEST.cc index 4478f268a..66e5bc996 100644 --- a/src/Kmeans_TEST.cc +++ b/src/Kmeans_TEST.cc @@ -17,9 +17,9 @@ #include #include -#include "ignition/math/Kmeans.hh" +#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 6ac265446..d166d24c7 100644 --- a/src/Line2_TEST.cc +++ b/src/Line2_TEST.cc @@ -17,10 +17,10 @@ #include -#include "ignition/math/Line2.hh" -#include "ignition/math/Helpers.hh" +#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 db50be5b6..92c58a15f 100644 --- a/src/Line3_TEST.cc +++ b/src/Line3_TEST.cc @@ -17,10 +17,10 @@ #include -#include "ignition/math/Line3.hh" -#include "ignition/math/Helpers.hh" +#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 ec4a23d02..19cdff98f 100644 --- a/src/MassMatrix3_TEST.cc +++ b/src/MassMatrix3_TEST.cc @@ -18,11 +18,11 @@ #include #include -#include "ignition/math/Helpers.hh" -#include "ignition/math/MassMatrix3.hh" -#include "ignition/math/Material.hh" +#include "gz/math/Helpers.hh" +#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 37893a5c8..ec2cc59d7 100644 --- a/src/Material.cc +++ b/src/Material.cc @@ -15,13 +15,13 @@ * */ -#include "ignition/math/Material.hh" -#include "ignition/math/Helpers.hh" +#include "gz/math/Material.hh" +#include "gz/math/Helpers.hh" // Placing the kMaterialData in a separate file for conveniece and clarity. #include "MaterialType.hh" -using namespace ignition; +using namespace gz; using namespace math; // Initialize the static map of Material objects based on the kMaterialData. @@ -40,7 +40,7 @@ static const std::map kMaterials = []() }(); // Private data for the Material class -class ignition::math::MaterialPrivate +class gz::math::MaterialPrivate { /// \brief The material type. public: MaterialType type = MaterialType::UNKNOWN_MATERIAL; diff --git a/src/MaterialType.hh b/src/MaterialType.hh index cda91a23e..fc15e433a 100644 --- a/src/MaterialType.hh +++ b/src/MaterialType.hh @@ -14,8 +14,8 @@ * limitations under the License. * */ -#ifndef IGNITION_MATERIAL_HH_ -#define IGNITION_MATERIAL_HH_ +#ifndef GZ_MATERIAL_HH_ +#define GZ_MATERIAL_HH_ #include #include diff --git a/src/Material_TEST.cc b/src/Material_TEST.cc index 1d79fc820..6c7a93731 100644 --- a/src/Material_TEST.cc +++ b/src/Material_TEST.cc @@ -16,11 +16,11 @@ */ #include -#include "ignition/math/Material.hh" -#include "ignition/math/MaterialType.hh" -#include "ignition/math/Helpers.hh" +#include "gz/math/Material.hh" +#include "gz/math/MaterialType.hh" +#include "gz/math/Helpers.hh" -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// diff --git a/src/Matrix3_TEST.cc b/src/Matrix3_TEST.cc index 1cd0044cd..910bb6720 100644 --- a/src/Matrix3_TEST.cc +++ b/src/Matrix3_TEST.cc @@ -17,10 +17,10 @@ #include -#include "ignition/math/Helpers.hh" -#include "ignition/math/Matrix3.hh" +#include "gz/math/Helpers.hh" +#include "gz/math/Matrix3.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(Matrix3dTest, Matrix3d) diff --git a/src/Matrix4_TEST.cc b/src/Matrix4_TEST.cc index d1459f87a..dc5e7ff35 100644 --- a/src/Matrix4_TEST.cc +++ b/src/Matrix4_TEST.cc @@ -17,12 +17,12 @@ #include -#include "ignition/math/Pose3.hh" -#include "ignition/math/Quaternion.hh" -#include "ignition/math/Matrix4.hh" -#include "ignition/math/Vector3.hh" +#include "gz/math/Pose3.hh" +#include "gz/math/Quaternion.hh" +#include "gz/math/Matrix4.hh" +#include "gz/math/Vector3.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(Matrix4dTest, Construct) diff --git a/src/Matrix6_TEST.cc b/src/Matrix6_TEST.cc index 27c9a56ac..8ec94a281 100644 --- a/src/Matrix6_TEST.cc +++ b/src/Matrix6_TEST.cc @@ -17,9 +17,9 @@ #include -#include "ignition/math/Matrix6.hh" +#include "gz/math/Matrix6.hh" -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// diff --git a/src/MovingWindowFilter_TEST.cc b/src/MovingWindowFilter_TEST.cc index f6189b202..a09ba5469 100644 --- a/src/MovingWindowFilter_TEST.cc +++ b/src/MovingWindowFilter_TEST.cc @@ -16,10 +16,10 @@ */ #include -#include "ignition/math/Vector3.hh" -#include "ignition/math/MovingWindowFilter.hh" +#include "gz/math/Vector3.hh" +#include "gz/math/MovingWindowFilter.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(MovingWindowFilterTest, SetWindowSize) diff --git a/src/OrientedBox_TEST.cc b/src/OrientedBox_TEST.cc index 445d7c6b5..2265c3bf8 100644 --- a/src/OrientedBox_TEST.cc +++ b/src/OrientedBox_TEST.cc @@ -17,10 +17,10 @@ #include #include -#include "ignition/math/Angle.hh" -#include "ignition/math/OrientedBox.hh" +#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 1ec3bd29c..c80989121 100644 --- a/src/PID.cc +++ b/src/PID.cc @@ -17,10 +17,10 @@ #include #include -#include "ignition/math/Helpers.hh" -#include "ignition/math/PID.hh" +#include "gz/math/Helpers.hh" +#include "gz/math/PID.hh" -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// diff --git a/src/PID_TEST.cc b/src/PID_TEST.cc index 1a0158316..ff58a25bf 100644 --- a/src/PID_TEST.cc +++ b/src/PID_TEST.cc @@ -17,10 +17,10 @@ #include -#include "ignition/math/PID.hh" -#include "ignition/math/Helpers.hh" +#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 ac7c10c1f..40e63d769 100644 --- a/src/PiecewiseScalarField3_TEST.cc +++ b/src/PiecewiseScalarField3_TEST.cc @@ -19,12 +19,12 @@ #include #include -#include "ignition/math/AdditivelySeparableScalarField3.hh" -#include "ignition/math/PiecewiseScalarField3.hh" -#include "ignition/math/Polynomial3.hh" -#include "ignition/math/Vector3.hh" +#include "gz/math/AdditivelySeparableScalarField3.hh" +#include "gz/math/PiecewiseScalarField3.hh" +#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 e082d2c26..a7970616d 100644 --- a/src/Plane_TEST.cc +++ b/src/Plane_TEST.cc @@ -17,10 +17,10 @@ #include -#include "ignition/math/Helpers.hh" -#include "ignition/math/Plane.hh" +#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 dc5998cfa..e1b6f627d 100644 --- a/src/Polynomial3_TEST.cc +++ b/src/Polynomial3_TEST.cc @@ -17,9 +17,9 @@ #include #include -#include "ignition/math/Polynomial3.hh" +#include "gz/math/Polynomial3.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(Polynomial3Test, DefaultConstructor) diff --git a/src/Pose_TEST.cc b/src/Pose_TEST.cc index 3313ba186..dde17ce9c 100644 --- a/src/Pose_TEST.cc +++ b/src/Pose_TEST.cc @@ -17,10 +17,10 @@ #include -#include "ignition/math/Helpers.hh" -#include "ignition/math/Pose3.hh" +#include "gz/math/Helpers.hh" +#include "gz/math/Pose3.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(PoseTest, Construction) diff --git a/src/Quaternion_TEST.cc b/src/Quaternion_TEST.cc index 5e4f0deb8..f7167163b 100644 --- a/src/Quaternion_TEST.cc +++ b/src/Quaternion_TEST.cc @@ -19,12 +19,12 @@ #include -#include "ignition/math/Helpers.hh" -#include "ignition/math/Quaternion.hh" -#include "ignition/math/Matrix3.hh" -#include "ignition/math/Matrix4.hh" +#include "gz/math/Helpers.hh" +#include "gz/math/Quaternion.hh" +#include "gz/math/Matrix3.hh" +#include "gz/math/Matrix4.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(QuaternionTest, Construction) diff --git a/src/Rand.cc b/src/Rand.cc index 95fcae443..0cb9b7b9f 100644 --- a/src/Rand.cc +++ b/src/Rand.cc @@ -25,9 +25,9 @@ #include #endif -#include "ignition/math/Rand.hh" +#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 447d2c7c3..df31afbdc 100644 --- a/src/Rand_TEST.cc +++ b/src/Rand_TEST.cc @@ -17,10 +17,10 @@ #include -#include "ignition/math/Helpers.hh" -#include "ignition/math/Rand.hh" +#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 feb408919..2af3c1308 100644 --- a/src/Region3_TEST.cc +++ b/src/Region3_TEST.cc @@ -17,9 +17,9 @@ #include #include -#include "ignition/math/Region3.hh" +#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 3510d0619..7f7e21e74 100644 --- a/src/RollingMean.cc +++ b/src/RollingMean.cc @@ -18,12 +18,12 @@ #include #include #include -#include "ignition/math/RollingMean.hh" +#include "gz/math/RollingMean.hh" -using namespace ignition::math; +using namespace gz::math; /// \brief Private data -class ignition::math::RollingMeanPrivate +class gz::math::RollingMeanPrivate { /// \brief The window size public: size_t windowSize{10}; diff --git a/src/RollingMean_TEST.cc b/src/RollingMean_TEST.cc index 9ae85ffa4..4800003b8 100644 --- a/src/RollingMean_TEST.cc +++ b/src/RollingMean_TEST.cc @@ -17,10 +17,10 @@ #include -#include "ignition/math/Helpers.hh" -#include "ignition/math/RollingMean.hh" +#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 8fdc1fc0b..9f04abccf 100644 --- a/src/RotationSpline.cc +++ b/src/RotationSpline.cc @@ -14,11 +14,11 @@ * limitations under the License. * */ -#include "ignition/math/Quaternion.hh" -#include "ignition/math/RotationSpline.hh" +#include "gz/math/Quaternion.hh" +#include "gz/math/RotationSpline.hh" #include "RotationSplinePrivate.hh" -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// diff --git a/src/RotationSplinePrivate.cc b/src/RotationSplinePrivate.cc index 1396e829e..e993c6830 100644 --- a/src/RotationSplinePrivate.cc +++ b/src/RotationSplinePrivate.cc @@ -16,7 +16,7 @@ */ #include "RotationSplinePrivate.hh" -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// diff --git a/src/RotationSplinePrivate.hh b/src/RotationSplinePrivate.hh index 34af9b9f1..d980a6124 100644 --- a/src/RotationSplinePrivate.hh +++ b/src/RotationSplinePrivate.hh @@ -14,12 +14,12 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_ROTATIONSPLINEPRIVATE_HH_ -#define IGNITION_MATH_ROTATIONSPLINEPRIVATE_HH_ +#ifndef GZ_MATH_ROTATIONSPLINEPRIVATE_HH_ +#define GZ_MATH_ROTATIONSPLINEPRIVATE_HH_ #include -#include -#include "ignition/math/Quaternion.hh" +#include +#include "gz/math/Quaternion.hh" namespace ignition { diff --git a/src/RotationSpline_TEST.cc b/src/RotationSpline_TEST.cc index cf5b2816f..d01270b6c 100644 --- a/src/RotationSpline_TEST.cc +++ b/src/RotationSpline_TEST.cc @@ -17,12 +17,12 @@ #include -#include "ignition/math/Helpers.hh" -#include "ignition/math/Vector3.hh" -#include "ignition/math/Quaternion.hh" -#include "ignition/math/RotationSpline.hh" +#include "gz/math/Helpers.hh" +#include "gz/math/Vector3.hh" +#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 ca594d588..a9c8c2fcd 100644 --- a/src/SemanticVersion.cc +++ b/src/SemanticVersion.cc @@ -17,9 +17,9 @@ #include -#include "ignition/math/SemanticVersion.hh" +#include "gz/math/SemanticVersion.hh" -using namespace ignition; +using namespace gz; using namespace math; namespace ignition diff --git a/src/SemanticVersion_TEST.cc b/src/SemanticVersion_TEST.cc index 66f60d268..6e3637ec5 100644 --- a/src/SemanticVersion_TEST.cc +++ b/src/SemanticVersion_TEST.cc @@ -17,9 +17,9 @@ #include -#include "ignition/math/SemanticVersion.hh" +#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 4523bef3a..151c40d85 100644 --- a/src/SignalStats.cc +++ b/src/SignalStats.cc @@ -16,10 +16,10 @@ */ #include #include -#include +#include #include "SignalStatsPrivate.hh" -using namespace ignition; +using namespace gz; using namespace math; ////////////////////////////////////////////////// diff --git a/src/SignalStatsPrivate.hh b/src/SignalStatsPrivate.hh index e5e045e86..0d379cc16 100644 --- a/src/SignalStatsPrivate.hh +++ b/src/SignalStatsPrivate.hh @@ -14,12 +14,12 @@ * 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 +#include namespace ignition { diff --git a/src/SignalStats_TEST.cc b/src/SignalStats_TEST.cc index 8024fb93d..289deef78 100644 --- a/src/SignalStats_TEST.cc +++ b/src/SignalStats_TEST.cc @@ -17,10 +17,10 @@ #include -#include -#include +#include +#include -using namespace ignition; +using namespace gz; ////////////////////////////////////////////////// TEST(SignalStatsTest, SignalMaximumConstructor) diff --git a/src/SpeedLimiter.cc b/src/SpeedLimiter.cc index 02a0b8a99..fe2c1df6f 100644 --- a/src/SpeedLimiter.cc +++ b/src/SpeedLimiter.cc @@ -15,14 +15,14 @@ * */ -#include "ignition/math/Helpers.hh" -#include "ignition/math/SpeedLimiter.hh" +#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()}; diff --git a/src/SpeedLimiter_TEST.cc b/src/SpeedLimiter_TEST.cc index 7f4c46134..c6a2b6d44 100644 --- a/src/SpeedLimiter_TEST.cc +++ b/src/SpeedLimiter_TEST.cc @@ -17,10 +17,10 @@ #include -#include "ignition/math/Helpers.hh" -#include "ignition/math/SpeedLimiter.hh" +#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 cebc5b657..0f99d569d 100644 --- a/src/Sphere_TEST.cc +++ b/src/Sphere_TEST.cc @@ -18,9 +18,9 @@ #include #include -#include "ignition/math/Sphere.hh" +#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 abbb313b2..915446695 100644 --- a/src/SphericalCoordinates.cc +++ b/src/SphericalCoordinates.cc @@ -16,10 +16,10 @@ */ #include -#include "ignition/math/Matrix3.hh" -#include "ignition/math/SphericalCoordinates.hh" +#include "gz/math/Matrix3.hh" +#include "gz/math/SphericalCoordinates.hh" -using namespace ignition; +using namespace gz; using namespace math; // Parameters for EARTH_WGS84 model @@ -38,7 +38,7 @@ const double g_EarthWGS84Flattening = 1.0/298.257223563; const double g_EarthRadius = 6371000.0; // Private data for the SphericalCoordinates class. -class ignition::math::SphericalCoordinatesPrivate +class gz::math::SphericalCoordinatesPrivate { /// \brief Type of surface being used. public: SphericalCoordinates::SurfaceType surfaceType; diff --git a/src/SphericalCoordinates_TEST.cc b/src/SphericalCoordinates_TEST.cc index b3f67e198..a4042846b 100644 --- a/src/SphericalCoordinates_TEST.cc +++ b/src/SphericalCoordinates_TEST.cc @@ -16,9 +16,9 @@ */ #include -#include "ignition/math/SphericalCoordinates.hh" +#include "gz/math/SphericalCoordinates.hh" -using namespace ignition; +using namespace gz; ////////////////////////////////////////////////// // Test different constructors, default parameters diff --git a/src/Spline.cc b/src/Spline.cc index c54b3e39f..22e9e29a4 100644 --- a/src/Spline.cc +++ b/src/Spline.cc @@ -18,11 +18,11 @@ // spline and catmull-rom spline #include "SplinePrivate.hh" -#include "ignition/math/Helpers.hh" -#include "ignition/math/Vector4.hh" -#include "ignition/math/Spline.hh" +#include "gz/math/Helpers.hh" +#include "gz/math/Vector4.hh" +#include "gz/math/Spline.hh" -using namespace ignition; +using namespace gz; using namespace math; /////////////////////////////////////////////////////////// diff --git a/src/SplinePrivate.cc b/src/SplinePrivate.cc index 896b5af25..64a2b7c24 100644 --- a/src/SplinePrivate.cc +++ b/src/SplinePrivate.cc @@ -15,7 +15,7 @@ * */ -#include "ignition/math/Matrix4.hh" +#include "gz/math/Matrix4.hh" #include "SplinePrivate.hh" diff --git a/src/SplinePrivate.hh b/src/SplinePrivate.hh index ef82e2959..12a2b21ac 100644 --- a/src/SplinePrivate.hh +++ b/src/SplinePrivate.hh @@ -14,15 +14,15 @@ * 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 -#include -#include -#include -#include +#include +#include +#include +#include namespace ignition { diff --git a/src/Spline_TEST.cc b/src/Spline_TEST.cc index d1d013344..1cbd627f3 100644 --- a/src/Spline_TEST.cc +++ b/src/Spline_TEST.cc @@ -17,10 +17,10 @@ #include -#include "ignition/math/Vector3.hh" -#include "ignition/math/Spline.hh" +#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 d534125df..86701c059 100644 --- a/src/Stopwatch.cc +++ b/src/Stopwatch.cc @@ -15,12 +15,12 @@ * */ #include -#include "ignition/math/Stopwatch.hh" +#include "gz/math/Stopwatch.hh" -using namespace ignition::math; +using namespace gz::math; // Private data class -class ignition::math::StopwatchPrivate +class gz::math::StopwatchPrivate { /// \brief Default constructor. public: StopwatchPrivate() = default; diff --git a/src/Stopwatch_TEST.cc b/src/Stopwatch_TEST.cc index 0c5a69258..fc517e529 100644 --- a/src/Stopwatch_TEST.cc +++ b/src/Stopwatch_TEST.cc @@ -18,9 +18,9 @@ #include #include -#include "ignition/math/Stopwatch.hh" +#include "gz/math/Stopwatch.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// // Helper function that runs a few tests diff --git a/src/Temperature.cc b/src/Temperature.cc index 2fdf727a3..3a2e75f07 100644 --- a/src/Temperature.cc +++ b/src/Temperature.cc @@ -14,10 +14,10 @@ * limitations under the License. * */ -#include "ignition/math/Temperature.hh" +#include "gz/math/Temperature.hh" /// \brief Private data for the Temperature class. -class ignition::math::TemperaturePrivate +class gz::math::TemperaturePrivate { /// \brief Default constructor public: TemperaturePrivate() : kelvin(0.0) {} @@ -30,7 +30,7 @@ class ignition::math::TemperaturePrivate public: double kelvin; }; -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// diff --git a/src/Temperature_TEST.cc b/src/Temperature_TEST.cc index ae3765673..c015476b8 100644 --- a/src/Temperature_TEST.cc +++ b/src/Temperature_TEST.cc @@ -16,9 +16,9 @@ */ #include -#include "ignition/math/Temperature.hh" +#include "gz/math/Temperature.hh" -using namespace ignition; +using namespace gz; using namespace math; ///////////////////////////////////////////////// diff --git a/src/Triangle3_TEST.cc b/src/Triangle3_TEST.cc index bcc798ede..6748ab648 100644 --- a/src/Triangle3_TEST.cc +++ b/src/Triangle3_TEST.cc @@ -17,10 +17,10 @@ #include -#include "ignition/math/Triangle3.hh" -#include "ignition/math/Helpers.hh" +#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 0e2e3372c..7581c39ed 100644 --- a/src/Triangle_TEST.cc +++ b/src/Triangle_TEST.cc @@ -17,10 +17,10 @@ #include -#include "ignition/math/Triangle.hh" -#include "ignition/math/Helpers.hh" +#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 3e6e95f75..8ac6dabbc 100644 --- a/src/Vector2_TEST.cc +++ b/src/Vector2_TEST.cc @@ -18,10 +18,10 @@ #include #include -#include "ignition/math/Helpers.hh" -#include "ignition/math/Vector2.hh" +#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 10ad3a248..be3c910ac 100644 --- a/src/Vector3Stats.cc +++ b/src/Vector3Stats.cc @@ -14,10 +14,10 @@ * limitations under the License. * */ -#include +#include #include "Vector3StatsPrivate.hh" -using namespace ignition; +using namespace gz; using namespace math; ////////////////////////////////////////////////// diff --git a/src/Vector3StatsPrivate.hh b/src/Vector3StatsPrivate.hh index 6715876a9..ecbcf3336 100644 --- a/src/Vector3StatsPrivate.hh +++ b/src/Vector3StatsPrivate.hh @@ -14,11 +14,11 @@ * limitations under the License. * */ -#ifndef IGNITION_MATH_VECTOR3STATSPRIVATE_HH_ -#define IGNITION_MATH_VECTOR3STATSPRIVATE_HH_ +#ifndef GZ_MATH_VECTOR3STATSPRIVATE_HH_ +#define GZ_MATH_VECTOR3STATSPRIVATE_HH_ -#include -#include +#include +#include namespace ignition { diff --git a/src/Vector3Stats_TEST.cc b/src/Vector3Stats_TEST.cc index 39fc5a5eb..b720e989e 100644 --- a/src/Vector3Stats_TEST.cc +++ b/src/Vector3Stats_TEST.cc @@ -17,9 +17,9 @@ #include -#include +#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 9a4615aa1..affade714 100644 --- a/src/Vector3_TEST.cc +++ b/src/Vector3_TEST.cc @@ -20,10 +20,10 @@ #include #include -#include "ignition/math/Vector3.hh" -#include "ignition/math/Helpers.hh" +#include "gz/math/Vector3.hh" +#include "gz/math/Helpers.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(Vector3dTest, Construction) diff --git a/src/Vector4_TEST.cc b/src/Vector4_TEST.cc index 400a1f90c..216bc4a36 100644 --- a/src/Vector4_TEST.cc +++ b/src/Vector4_TEST.cc @@ -17,11 +17,11 @@ #include -#include "ignition/math/Helpers.hh" -#include "ignition/math/Matrix4.hh" -#include "ignition/math/Vector4.hh" +#include "gz/math/Helpers.hh" +#include "gz/math/Matrix4.hh" +#include "gz/math/Vector4.hh" -using namespace ignition; +using namespace gz; ///////////////////////////////////////////////// TEST(Vector4dTest, Construction) diff --git a/src/graph/Edge_TEST.cc b/src/graph/Edge_TEST.cc index ac6c1a247..85486b431 100644 --- a/src/graph/Edge_TEST.cc +++ b/src/graph/Edge_TEST.cc @@ -19,10 +19,10 @@ #include #include -#include "ignition/math/graph/Edge.hh" -#include "ignition/math/graph/Vertex.hh" +#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 87e238abb..1130f7e94 100644 --- a/src/graph/GraphAlgorithms_TEST.cc +++ b/src/graph/GraphAlgorithms_TEST.cc @@ -18,10 +18,10 @@ #include #include -#include "ignition/math/graph/Graph.hh" -#include "ignition/math/graph/GraphAlgorithms.hh" +#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 81984f5aa..f9f338383 100644 --- a/src/graph/GraphDirected_TEST.cc +++ b/src/graph/GraphDirected_TEST.cc @@ -19,9 +19,9 @@ #include #include -#include "ignition/math/graph/Graph.hh" +#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 dd34afc36..a49ee4337 100644 --- a/src/graph/GraphUndirected_TEST.cc +++ b/src/graph/GraphUndirected_TEST.cc @@ -21,9 +21,9 @@ #include #include -#include "ignition/math/graph/Graph.hh" +#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 e58c9bdee..01fb7fbac 100644 --- a/src/graph/Graph_TEST.cc +++ b/src/graph/Graph_TEST.cc @@ -18,9 +18,9 @@ #include #include -#include "ignition/math/graph/Graph.hh" +#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 2bc0b0634..b0b9030ff 100644 --- a/src/graph/Vertex_TEST.cc +++ b/src/graph/Vertex_TEST.cc @@ -19,9 +19,9 @@ #include #include -#include "ignition/math/graph/Vertex.hh" +#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 a0574c17e..5b632cb5a 100644 --- a/src/python_pybind11/src/Angle.cc +++ b/src/python_pybind11/src/Angle.cc @@ -17,7 +17,7 @@ #include -#include +#include #include #include "Angle.hh" @@ -32,7 +32,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; diff --git a/src/python_pybind11/src/Angle.hh b/src/python_pybind11/src/Angle.hh index f0b304d0e..f1d3a3714 100644 --- a/src/python_pybind11/src/Angle.hh +++ b/src/python_pybind11/src/Angle.hh @@ -29,7 +29,7 @@ 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 diff --git a/src/python_pybind11/src/AxisAlignedBox.cc b/src/python_pybind11/src/AxisAlignedBox.cc index 6ba253946..bb93abf38 100644 --- a/src/python_pybind11/src/AxisAlignedBox.cc +++ b/src/python_pybind11/src/AxisAlignedBox.cc @@ -21,8 +21,8 @@ #include "AxisAlignedBox.hh" -#include -#include +#include +#include using namespace pybind11::literals; @@ -34,7 +34,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; @@ -49,8 +49,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") @@ -74,8 +74,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", diff --git a/src/python_pybind11/src/AxisAlignedBox.hh b/src/python_pybind11/src/AxisAlignedBox.hh index 057852353..87d3a7a43 100644 --- a/src/python_pybind11/src/AxisAlignedBox.hh +++ b/src/python_pybind11/src/AxisAlignedBox.hh @@ -29,7 +29,7 @@ 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 diff --git a/src/python_pybind11/src/Box.hh b/src/python_pybind11/src/Box.hh index 49a7c79ab..72c53de5d 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 @@ -25,7 +25,7 @@ #include #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -36,7 +36,7 @@ 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) { @@ -135,4 +135,4 @@ void defineMathBox(py::module &m, const std::string &typestr) } // namespace math } // namespace ignition -#endif // IGNITION_MATH_PYTHON__BOX_HH_ +#endif // GZ_MATH_PYTHON__BOX_HH_ diff --git a/src/python_pybind11/src/Capsule.hh b/src/python_pybind11/src/Capsule.hh index fef96cfe4..7a4c57a7a 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 @@ -24,7 +24,7 @@ #include #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -35,7 +35,7 @@ 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 @@ -104,4 +104,4 @@ void defineMathCapsule(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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 7fc0a2584..ba887f3aa 100644 --- a/src/python_pybind11/src/Color.cc +++ b/src/python_pybind11/src/Color.cc @@ -18,7 +18,7 @@ #include #include "Color.hh" -#include +#include #include @@ -32,7 +32,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; diff --git a/src/python_pybind11/src/Color.hh b/src/python_pybind11/src/Color.hh index 7306bcb99..9986244a7 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 @@ -29,7 +29,7 @@ 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 @@ -39,4 +39,4 @@ void defineMathColor(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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 eb7ecc722..8661829af 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 @@ -24,7 +24,7 @@ #include #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -35,7 +35,7 @@ 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, @@ -114,4 +114,4 @@ void defineMathCylinder(py::module &m, const std::string &typestr) } // namespace math } // namespace ignition -#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..672569cc6 100644 --- a/src/python_pybind11/src/DiffDriveOdometry.cc +++ b/src/python_pybind11/src/DiffDriveOdometry.cc @@ -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 math } // namespace ignition diff --git a/src/python_pybind11/src/DiffDriveOdometry.hh b/src/python_pybind11/src/DiffDriveOdometry.hh index bc261df2d..9895f8c32 100644 --- a/src/python_pybind11/src/DiffDriveOdometry.hh +++ b/src/python_pybind11/src/DiffDriveOdometry.hh @@ -14,15 +14,15 @@ * 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 #include #include -#include +#include namespace py = pybind11; @@ -32,14 +32,14 @@ namespace math { namespace python { -/// Define a py:: wrapper for an ignition::gazebo::DiffDriveOdometry +/// Define a py:: wrapper for an gz::sim::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 math } // namespace ignition -#endif // IGNITION_MATH_PYTHON__DIFFDRIVEODOMETRY_HH_ +#endif // GZ_MATH_PYTHON__DIFFDRIVEODOMETRY_HH_ diff --git a/src/python_pybind11/src/Ellipsoid.hh b/src/python_pybind11/src/Ellipsoid.hh index 418cd17e0..c55e60869 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 @@ -24,8 +24,8 @@ #include #include -#include -#include +#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -36,7 +36,7 @@ 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 @@ -100,4 +100,4 @@ void defineMathEllipsoid(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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..e40559372 100644 --- a/src/python_pybind11/src/Filter.cc +++ b/src/python_pybind11/src/Filter.cc @@ -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(), diff --git a/src/python_pybind11/src/Filter.hh b/src/python_pybind11/src/Filter.hh index df8b59e80..4b33118a7 100644 --- a/src/python_pybind11/src/Filter.hh +++ b/src/python_pybind11/src/Filter.hh @@ -15,16 +15,16 @@ * */ -#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 #include -#include -#include -#include +#include +#include +#include namespace py = pybind11; @@ -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 @@ -264,4 +264,4 @@ void defineMathBiQuadVector3(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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 7434ff440..70ed41319 100644 --- a/src/python_pybind11/src/Frustum.cc +++ b/src/python_pybind11/src/Frustum.cc @@ -17,7 +17,7 @@ #include #include "Frustum.hh" -#include +#include #include #include @@ -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,30 +84,30 @@ 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 diff --git a/src/python_pybind11/src/Frustum.hh b/src/python_pybind11/src/Frustum.hh index 688baf013..1a9723e52 100644 --- a/src/python_pybind11/src/Frustum.hh +++ b/src/python_pybind11/src/Frustum.hh @@ -15,8 +15,8 @@ * */ -#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 @@ -29,7 +29,7 @@ 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 @@ -39,4 +39,4 @@ void defineMathFrustum(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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 928744409..3b218b2e2 100644 --- a/src/python_pybind11/src/GaussMarkovProcess.cc +++ b/src/python_pybind11/src/GaussMarkovProcess.cc @@ -22,7 +22,7 @@ #include #include -#include +#include #include "GaussMarkovProcess.hh" @@ -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(), diff --git a/src/python_pybind11/src/GaussMarkovProcess.hh b/src/python_pybind11/src/GaussMarkovProcess.hh index c100c684f..66a21f006 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 @@ -30,7 +30,7 @@ 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 @@ -40,4 +40,4 @@ void defineMathGaussMarkovProcess(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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 dcd0934e8..c4d3a2a6f 100644 --- a/src/python_pybind11/src/Helpers.cc +++ b/src/python_pybind11/src/Helpers.cc @@ -19,8 +19,8 @@ #include #include "Helpers.hh" -#include -#include +#include +#include namespace ignition { @@ -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,23 +149,23 @@ 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("is_time_string", - &ignition::math::isTimeString, + &gz::math::isTimeString, "An example time string is \"0 00:00:00.000\", which has the format " "DAYS HOURS:MINUTES:SECONDS.MILLISECONDS") .def("ign_sphere_volume", @@ -231,5 +231,5 @@ void defineMathHelpers(py::module &m) .def_readonly_static("NAN_I", &NAN_I); } } // namespace python -} // namespace gazebo +} // namespace math } // namespace ignition diff --git a/src/python_pybind11/src/Helpers.hh b/src/python_pybind11/src/Helpers.hh index ed22bd325..c83bd4b59 100644 --- a/src/python_pybind11/src/Helpers.hh +++ b/src/python_pybind11/src/Helpers.hh @@ -15,8 +15,8 @@ * */ -#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 @@ -28,13 +28,13 @@ 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 math } // namespace ignition -#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 94b1de7b3..54c6fe70c 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 @@ -24,7 +24,7 @@ #include #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -35,7 +35,7 @@ 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.") @@ -98,4 +98,4 @@ void defineMathInertial(py::module &m, const std::string &typestr) } // namespace math } // namespace ignition -#endif // IGNITION_MATH_PYTHON__INERTIAL_HH_ +#endif // GZ_MATH_PYTHON__INERTIAL_HH_ diff --git a/src/python_pybind11/src/Interval.hh b/src/python_pybind11/src/Interval.hh index 7539bff31..2a1c70744 100644 --- a/src/python_pybind11/src/Interval.hh +++ b/src/python_pybind11/src/Interval.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__INTERVAL_HH_ -#define IGNITION_MATH_PYTHON__INTERVAL_HH_ +#ifndef GZ_MATH_PYTHON__INTERVAL_HH_ +#define GZ_MATH_PYTHON__INTERVAL_HH_ #include #include @@ -24,7 +24,7 @@ #include #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -35,7 +35,7 @@ namespace math { namespace python { -/// Help define a pybind11 wrapper for an ignition::math::Interval +/// Help define a pybind11 wrapper for an gz::math::Interval /** * \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 helpDefineMathInterval(py::module &m, const std::string &typestr) { - using Class = ignition::math::Interval; + using Class = gz::math::Interval; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -104,7 +104,7 @@ void helpDefineMathInterval(py::module &m, const std::string &typestr) .def("__repr__", toString); } -/// Define a pybind11 wrapper for an ignition::math::Interval +/// Define a pybind11 wrapper for an gz::math::Interval /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -115,4 +115,4 @@ void defineMathInterval(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#endif // IGNITION_MATH_PYTHON__INTERVAL_HH_ +#endif // GZ_MATH_PYTHON__INTERVAL_HH_ diff --git a/src/python_pybind11/src/Kmeans.cc b/src/python_pybind11/src/Kmeans.cc index 13af747dc..78f028f4f 100644 --- a/src/python_pybind11/src/Kmeans.cc +++ b/src/python_pybind11/src/Kmeans.cc @@ -18,7 +18,7 @@ #include #include "Kmeans.hh" -#include +#include #include namespace ignition @@ -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); diff --git a/src/python_pybind11/src/Kmeans.hh b/src/python_pybind11/src/Kmeans.hh index d9c1de4e0..030b2c998 100644 --- a/src/python_pybind11/src/Kmeans.hh +++ b/src/python_pybind11/src/Kmeans.hh @@ -15,8 +15,8 @@ * */ -#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 @@ -29,7 +29,7 @@ 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 @@ -39,4 +39,4 @@ void defineMathKmeans(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#endif // IGNITION_MATH_PYTHON__KMEANS_HH_ +#endif // GZ_MATH_PYTHON__KMEANS_HH_ diff --git a/src/python_pybind11/src/Line2.hh b/src/python_pybind11/src/Line2.hh index 351035443..fc06b7e85 100644 --- a/src/python_pybind11/src/Line2.hh +++ b/src/python_pybind11/src/Line2.hh @@ -15,15 +15,15 @@ * */ -#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 #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -34,7 +34,7 @@ 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 @@ -42,7 +42,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; @@ -53,14 +53,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), @@ -69,13 +69,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", @@ -97,11 +97,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", @@ -128,7 +128,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 @@ -139,4 +139,4 @@ void defineMathLine2(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#endif // IGNITION_MATH_PYTHON__LINE2_HH_ +#endif // GZ_MATH_PYTHON__LINE2_HH_ diff --git a/src/python_pybind11/src/Line3.hh b/src/python_pybind11/src/Line3.hh index 854ee8f43..3da0f8376 100644 --- a/src/python_pybind11/src/Line3.hh +++ b/src/python_pybind11/src/Line3.hh @@ -15,16 +15,16 @@ * */ -#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 #include -#include -#include +#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -35,7 +35,7 @@ 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 @@ -43,7 +43,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; @@ -56,8 +56,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") @@ -67,8 +67,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, @@ -100,17 +100,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", @@ -127,7 +127,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.") @@ -145,7 +145,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 @@ -155,4 +155,4 @@ void defineMathLine3(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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..ad9c647f6 100644 --- a/src/python_pybind11/src/MassMatrix3.cc +++ b/src/python_pybind11/src/MassMatrix3.cc @@ -32,5 +32,5 @@ void defineMathMassMatrix3(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo +} // namespace math } // namespace ignition diff --git a/src/python_pybind11/src/MassMatrix3.hh b/src/python_pybind11/src/MassMatrix3.hh index 97f9e830f..2650a446c 100644 --- a/src/python_pybind11/src/MassMatrix3.hh +++ b/src/python_pybind11/src/MassMatrix3.hh @@ -15,15 +15,15 @@ * */ -#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 #include -#include -#include +#include +#include namespace py = pybind11; @@ -33,14 +33,14 @@ 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 " @@ -204,4 +204,4 @@ void helpDefineMathMassMatrix3(py::module &m, const std::string &typestr) } // namespace math } // namespace ignition -#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 929293e97..1b215d90d 100644 --- a/src/python_pybind11/src/Material.cc +++ b/src/python_pybind11/src/Material.cc @@ -19,8 +19,8 @@ #include #include "Material.hh" -#include -#include +#include +#include #include #include @@ -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,22 +83,22 @@ 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 diff --git a/src/python_pybind11/src/Material.hh b/src/python_pybind11/src/Material.hh index a8029c707..163cf5120 100644 --- a/src/python_pybind11/src/Material.hh +++ b/src/python_pybind11/src/Material.hh @@ -15,8 +15,8 @@ * */ -#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 @@ -29,7 +29,7 @@ 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 @@ -39,4 +39,4 @@ void defineMathMaterial(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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..011bf3410 100644 --- a/src/python_pybind11/src/Matrix3.cc +++ b/src/python_pybind11/src/Matrix3.cc @@ -33,5 +33,5 @@ void defineMathMatrix3(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo +} // namespace math } // namespace ignition diff --git a/src/python_pybind11/src/Matrix3.hh b/src/python_pybind11/src/Matrix3.hh index bd2cb6a1a..8b3c5e85e 100644 --- a/src/python_pybind11/src/Matrix3.hh +++ b/src/python_pybind11/src/Matrix3.hh @@ -15,15 +15,15 @@ * */ -#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 #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -34,14 +34,14 @@ 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 @@ -49,7 +49,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; @@ -63,12 +63,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) @@ -125,4 +125,4 @@ void helpDefineMathMatrix3(py::module &m, const std::string &typestr) } // namespace math } // namespace ignition -#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..56c6974e5 100644 --- a/src/python_pybind11/src/Matrix4.cc +++ b/src/python_pybind11/src/Matrix4.cc @@ -33,5 +33,5 @@ void defineMathMatrix4(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo +} // namespace math } // namespace ignition diff --git a/src/python_pybind11/src/Matrix4.hh b/src/python_pybind11/src/Matrix4.hh index 0782de3ad..0fda03b2d 100644 --- a/src/python_pybind11/src/Matrix4.hh +++ b/src/python_pybind11/src/Matrix4.hh @@ -15,15 +15,15 @@ * */ -#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 #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -34,14 +34,14 @@ 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 @@ -49,7 +49,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; @@ -63,10 +63,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__", @@ -79,7 +79,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", @@ -110,7 +110,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", @@ -120,8 +120,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", @@ -129,9 +129,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") @@ -147,7 +147,7 @@ void helpDefineMathMatrix4(py::module &m, const std::string &typestr) .def("__repr__", toString); } } // namespace python -} // namespace gazebo +} // namespace math } // namespace ignition -#endif // IGNITION_MATH_PYTHON__MATRIX4_HH_ +#endif // GZ_MATH_PYTHON__MATRIX4_HH_ diff --git a/src/python_pybind11/src/Matrix6.hh b/src/python_pybind11/src/Matrix6.hh index 9a2e87786..06580ad7e 100644 --- a/src/python_pybind11/src/Matrix6.hh +++ b/src/python_pybind11/src/Matrix6.hh @@ -23,7 +23,7 @@ #include #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; diff --git a/src/python_pybind11/src/MovingWindowFilter.cc b/src/python_pybind11/src/MovingWindowFilter.cc index 264178e52..c27679c11 100644 --- a/src/python_pybind11/src/MovingWindowFilter.cc +++ b/src/python_pybind11/src/MovingWindowFilter.cc @@ -17,7 +17,7 @@ #include -#include +#include #include "MovingWindowFilter.hh" namespace ignition @@ -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 math } // namespace ignition diff --git a/src/python_pybind11/src/MovingWindowFilter.hh b/src/python_pybind11/src/MovingWindowFilter.hh index 0e4988899..68651766d 100644 --- a/src/python_pybind11/src/MovingWindowFilter.hh +++ b/src/python_pybind11/src/MovingWindowFilter.hh @@ -15,14 +15,14 @@ * */ -#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 #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -33,7 +33,7 @@ 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 @@ -67,4 +67,4 @@ void defineMathMovingWindowFilter(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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 37587380a..c416370bc 100644 --- a/src/python_pybind11/src/OrientedBox.hh +++ b/src/python_pybind11/src/OrientedBox.hh @@ -15,15 +15,15 @@ * */ -#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 #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -34,7 +34,7 @@ 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 @@ -43,7 +43,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; @@ -55,19 +55,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_), @@ -76,7 +76,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", @@ -125,4 +125,4 @@ void defineMathOrientedBox(py::module &m, const std::string &typestr) } // namespace math } // namespace ignition -#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 fe53e00a0..9e273d1a6 100644 --- a/src/python_pybind11/src/PID.cc +++ b/src/python_pybind11/src/PID.cc @@ -18,7 +18,7 @@ #include #include -#include +#include #include "PID.hh" @@ -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(), diff --git a/src/python_pybind11/src/PID.hh b/src/python_pybind11/src/PID.hh index 819fba131..fe8791e5d 100644 --- a/src/python_pybind11/src/PID.hh +++ b/src/python_pybind11/src/PID.hh @@ -15,8 +15,8 @@ * */ -#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 @@ -28,7 +28,7 @@ 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 @@ -38,4 +38,4 @@ void defineMathPID(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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 deadb6526..79e9d4c09 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 @@ -24,7 +24,7 @@ #include #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -35,7 +35,7 @@ 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,11 +109,11 @@ 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(); } @@ -121,4 +121,4 @@ void defineMathPlane(py::module &m, const std::string &typestr) } // namespace math } // namespace ignition -#endif // IGNITION_MATH_PYTHON__PLANE_HH_ +#endif // GZ_MATH_PYTHON__PLANE_HH_ diff --git a/src/python_pybind11/src/Polynomial3.hh b/src/python_pybind11/src/Polynomial3.hh index 7b0fede59..27dec56c7 100644 --- a/src/python_pybind11/src/Polynomial3.hh +++ b/src/python_pybind11/src/Polynomial3.hh @@ -15,16 +15,16 @@ * */ -#ifndef IGNITION_MATH_PYTHON__POLYNOMIAL3_HH_ -#define IGNITION_MATH_PYTHON__POLYNOMIAL3_HH_ +#ifndef GZ_MATH_PYTHON__POLYNOMIAL3_HH_ +#define GZ_MATH_PYTHON__POLYNOMIAL3_HH_ #include #include #include -#include -#include +#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -35,7 +35,7 @@ namespace math { namespace python { -/// Help define a pybind11 wrapper for an ignition::math::Polynomial3 +/// Help define a pybind11 wrapper for an gz::math::Polynomial3 /** * \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 helpDefineMathPolynomial3(py::module &m, const std::string &typestr) { - using Class = ignition::math::Polynomial3; + using Class = gz::math::Polynomial3; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -97,7 +97,7 @@ void helpDefineMathPolynomial3(py::module &m, const std::string &typestr) .def("__repr__", toString); } -/// Define a pybind11 wrapper for an ignition::math::Polynomial3 +/// Define a pybind11 wrapper for an gz::math::Polynomial3 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -108,4 +108,4 @@ void defineMathPolynomial3(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#endif // IGNITION_MATH_PYTHON__POLYNOMIAL3_HH_ +#endif // GZ_MATH_PYTHON__POLYNOMIAL3_HH_ diff --git a/src/python_pybind11/src/Pose3.cc b/src/python_pybind11/src/Pose3.cc index b79de9d8e..2a9e1d117 100644 --- a/src/python_pybind11/src/Pose3.cc +++ b/src/python_pybind11/src/Pose3.cc @@ -33,5 +33,5 @@ void defineMathPose3(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo +} // namespace math } // namespace ignition diff --git a/src/python_pybind11/src/Pose3.hh b/src/python_pybind11/src/Pose3.hh index 16635b9aa..0441ce104 100644 --- a/src/python_pybind11/src/Pose3.hh +++ b/src/python_pybind11/src/Pose3.hh @@ -15,15 +15,15 @@ * */ -#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 #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -34,14 +34,14 @@ 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 @@ -49,7 +49,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; @@ -61,8 +61,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()) @@ -76,12 +76,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), @@ -96,7 +96,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", @@ -151,7 +151,7 @@ void helpDefineMathPose3(py::module &m, const std::string &typestr) .def("__repr__", toString); } } // namespace python -} // namespace gazebo +} // namespace math } // namespace ignition -#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..3f05f53ef 100644 --- a/src/python_pybind11/src/Quaternion.cc +++ b/src/python_pybind11/src/Quaternion.cc @@ -33,5 +33,5 @@ void defineMathQuaternion(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo +} // namespace math } // namespace ignition diff --git a/src/python_pybind11/src/Quaternion.hh b/src/python_pybind11/src/Quaternion.hh index 5f5b96ac1..7d78882b3 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 @@ -24,9 +24,9 @@ #include #include -#include -#include -#include +#include +#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -37,14 +37,14 @@ 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 @@ -52,7 +52,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; @@ -66,9 +66,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) @@ -77,7 +77,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) @@ -105,13 +105,13 @@ void helpDefineMathQuaternion(py::module &m, const std::string &typestr) py::overload_cast(&Class::Axis), "Set the quaternion from an axis and angle") .def("axis", - py::overload_cast&, T>(&Class::Axis), + py::overload_cast&, T>(&Class::Axis), "Set the quaternion from an axis and angle") .def("set", &Class::Set, "Set this quaternion from 4 floating numbers") .def("euler", - py::overload_cast&>(&Class::Euler), + py::overload_cast&>(&Class::Euler), "Set the quaternion from Euler angles. The order of operations " "is roll, pitch, yaw around a fixed body frame axis " "(the original frame of the object before rotation is applied).") @@ -122,7 +122,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", @@ -133,7 +133,7 @@ void helpDefineMathQuaternion(py::module &m, const std::string &typestr) .def("yaw", &Class::Yaw, "Get the Euler yaw angle in radians") .def("to_axis", [](const Class &self) { - ignition::math::Vector3 _axis; + gz::math::Vector3 _axis; T _angle; self.ToAxis(_axis, _angle); return std::make_tuple(_axis, _angle); @@ -214,4 +214,4 @@ void helpDefineMathQuaternion(py::module &m, const std::string &typestr) } // namespace math } // namespace ignition -#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 eae9181e6..b9aff9cc8 100644 --- a/src/python_pybind11/src/Rand.cc +++ b/src/python_pybind11/src/Rand.cc @@ -17,7 +17,7 @@ #include #include "Rand.hh" -#include +#include namespace ignition { @@ -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 math } // namespace ignition diff --git a/src/python_pybind11/src/Rand.hh b/src/python_pybind11/src/Rand.hh index 9242fdbf6..231d6275c 100644 --- a/src/python_pybind11/src/Rand.hh +++ b/src/python_pybind11/src/Rand.hh @@ -15,8 +15,8 @@ * */ -#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 @@ -29,13 +29,13 @@ 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 math } // namespace ignition -#endif // IGNITION_MATH_PYTHON__RAND_HH_ +#endif // GZ_MATH_PYTHON__RAND_HH_ diff --git a/src/python_pybind11/src/Region3.hh b/src/python_pybind11/src/Region3.hh index 9ca4cce73..90234cc31 100644 --- a/src/python_pybind11/src/Region3.hh +++ b/src/python_pybind11/src/Region3.hh @@ -15,8 +15,8 @@ * */ -#ifndef IGNITION_MATH_PYTHON__REGION3_HH_ -#define IGNITION_MATH_PYTHON__REGION3_HH_ +#ifndef GZ_MATH_PYTHON__REGION3_HH_ +#define GZ_MATH_PYTHON__REGION3_HH_ #include #include @@ -24,8 +24,8 @@ #include #include -#include -#include +#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -36,7 +36,7 @@ namespace math { namespace python { -/// Help define a pybind11 wrapper for an ignition::math::Region3 +/// Help define a pybind11 wrapper for an gz::math::Region3 /** * \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 helpDefineMathRegion3(py::module &m, const std::string &typestr) { - using Class = ignition::math::Region3; + using Class = gz::math::Region3; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -96,7 +96,7 @@ void helpDefineMathRegion3(py::module &m, const std::string &typestr) .def("__repr__", toString); } -/// Define a pybind11 wrapper for an ignition::math::Region3 +/// Define a pybind11 wrapper for an gz::math::Region3 /** * \param[in] module a pybind11 module to add the definition to * \param[in] typestr name of the type used by Python @@ -107,4 +107,4 @@ void defineMathRegion3(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#endif // IGNITION_MATH_PYTHON__REGION3_HH_ +#endif // GZ_MATH_PYTHON__REGION3_HH_ diff --git a/src/python_pybind11/src/RollingMean.cc b/src/python_pybind11/src/RollingMean.cc index c84279451..7719188b0 100644 --- a/src/python_pybind11/src/RollingMean.cc +++ b/src/python_pybind11/src/RollingMean.cc @@ -16,7 +16,7 @@ */ #include #include "RollingMean.hh" -#include +#include namespace ignition { @@ -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(), diff --git a/src/python_pybind11/src/RollingMean.hh b/src/python_pybind11/src/RollingMean.hh index 122e513fc..44f9b8d39 100644 --- a/src/python_pybind11/src/RollingMean.hh +++ b/src/python_pybind11/src/RollingMean.hh @@ -15,8 +15,8 @@ * */ -#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 @@ -29,7 +29,7 @@ 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 @@ -39,4 +39,4 @@ void defineMathRollingMean(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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 f457a9ba3..8413992d0 100644 --- a/src/python_pybind11/src/RotationSpline.cc +++ b/src/python_pybind11/src/RotationSpline.cc @@ -16,7 +16,7 @@ */ #include #include "RotationSpline.hh" -#include +#include namespace ignition { @@ -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(), diff --git a/src/python_pybind11/src/RotationSpline.hh b/src/python_pybind11/src/RotationSpline.hh index 670b2ad97..8814c5521 100644 --- a/src/python_pybind11/src/RotationSpline.hh +++ b/src/python_pybind11/src/RotationSpline.hh @@ -15,8 +15,8 @@ * */ -#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 @@ -29,7 +29,7 @@ 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 @@ -39,4 +39,4 @@ void defineMathRotationSpline(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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 3b8280fd5..6c4e30a23 100644 --- a/src/python_pybind11/src/SemanticVersion.cc +++ b/src/python_pybind11/src/SemanticVersion.cc @@ -17,7 +17,7 @@ #include -#include +#include #include #include "SemanticVersion.hh" @@ -32,7 +32,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; diff --git a/src/python_pybind11/src/SemanticVersion.hh b/src/python_pybind11/src/SemanticVersion.hh index 0c600c2a3..8fede5de3 100644 --- a/src/python_pybind11/src/SemanticVersion.hh +++ b/src/python_pybind11/src/SemanticVersion.hh @@ -15,8 +15,8 @@ * */ -#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 @@ -29,7 +29,7 @@ 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 @@ -39,4 +39,4 @@ void defineMathSemanticVersion(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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 69b31e661..afc7f07dd 100644 --- a/src/python_pybind11/src/SignalStats.cc +++ b/src/python_pybind11/src/SignalStats.cc @@ -20,7 +20,7 @@ #include #include "SignalStats.hh" -#include +#include namespace ignition { @@ -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(), diff --git a/src/python_pybind11/src/SignalStats.hh b/src/python_pybind11/src/SignalStats.hh index 7e92e1940..fac514b64 100644 --- a/src/python_pybind11/src/SignalStats.hh +++ b/src/python_pybind11/src/SignalStats.hh @@ -15,8 +15,8 @@ * */ -#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 @@ -29,42 +29,42 @@ 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 @@ -89,4 +89,4 @@ void defineMathSignalMean(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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 4e005e80c..12c1bc638 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 @@ -24,7 +24,7 @@ #include #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -35,7 +35,7 @@ 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", @@ -100,4 +100,4 @@ void defineMathSphere(py::module &m, const std::string &typestr) } // namespace math } // namespace ignition -#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 9bf0dee7c..442587243 100644 --- a/src/python_pybind11/src/SphericalCoordinates.cc +++ b/src/python_pybind11/src/SphericalCoordinates.cc @@ -17,8 +17,8 @@ #include #include "SphericalCoordinates.hh" -#include -#include +#include +#include namespace ignition { @@ -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", diff --git a/src/python_pybind11/src/SphericalCoordinates.hh b/src/python_pybind11/src/SphericalCoordinates.hh index e7a2b83cd..927dfe060 100644 --- a/src/python_pybind11/src/SphericalCoordinates.hh +++ b/src/python_pybind11/src/SphericalCoordinates.hh @@ -15,8 +15,8 @@ * */ -#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 @@ -29,7 +29,7 @@ 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 @@ -39,4 +39,4 @@ void defineMathSphericalCoordinates(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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 c5ce95ecc..be0fd1723 100644 --- a/src/python_pybind11/src/Spline.cc +++ b/src/python_pybind11/src/Spline.cc @@ -16,7 +16,7 @@ */ #include #include "Spline.hh" -#include +#include namespace ignition { @@ -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(), diff --git a/src/python_pybind11/src/Spline.hh b/src/python_pybind11/src/Spline.hh index b0fbd17d8..099a39a67 100644 --- a/src/python_pybind11/src/Spline.hh +++ b/src/python_pybind11/src/Spline.hh @@ -15,8 +15,8 @@ * */ -#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 @@ -29,7 +29,7 @@ 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 @@ -39,4 +39,4 @@ void defineMathSpline(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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 2d2dbe5cf..302c8cd39 100644 --- a/src/python_pybind11/src/StopWatch.cc +++ b/src/python_pybind11/src/StopWatch.cc @@ -21,7 +21,7 @@ #include "StopWatch.hh" -#include +#include namespace ignition { @@ -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(), diff --git a/src/python_pybind11/src/StopWatch.hh b/src/python_pybind11/src/StopWatch.hh index 672ee00f1..c62e8fce3 100644 --- a/src/python_pybind11/src/StopWatch.hh +++ b/src/python_pybind11/src/StopWatch.hh @@ -15,8 +15,8 @@ * */ -#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 @@ -29,7 +29,7 @@ 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 @@ -39,4 +39,4 @@ void defineMathStopwatch(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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 32c260b42..c3de5ecb2 100644 --- a/src/python_pybind11/src/Temperature.cc +++ b/src/python_pybind11/src/Temperature.cc @@ -17,7 +17,7 @@ #include -#include +#include #include "Temperature.hh" #include @@ -32,7 +32,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; diff --git a/src/python_pybind11/src/Temperature.hh b/src/python_pybind11/src/Temperature.hh index 9307a1f05..2624bed25 100644 --- a/src/python_pybind11/src/Temperature.hh +++ b/src/python_pybind11/src/Temperature.hh @@ -15,8 +15,8 @@ * */ -#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 @@ -29,7 +29,7 @@ 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 @@ -39,4 +39,4 @@ void defineMathTemperature(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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..ffe303e42 100644 --- a/src/python_pybind11/src/Triangle.cc +++ b/src/python_pybind11/src/Triangle.cc @@ -33,5 +33,5 @@ void defineMathTriangle(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo +} // namespace math } // namespace ignition diff --git a/src/python_pybind11/src/Triangle.hh b/src/python_pybind11/src/Triangle.hh index 407ee207f..8366c1283 100644 --- a/src/python_pybind11/src/Triangle.hh +++ b/src/python_pybind11/src/Triangle.hh @@ -15,15 +15,15 @@ * */ -#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 #include #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -34,14 +34,14 @@ 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 math } // namespace ignition -#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..8e3de24e1 100644 --- a/src/python_pybind11/src/Triangle3.cc +++ b/src/python_pybind11/src/Triangle3.cc @@ -33,5 +33,5 @@ void defineMathTriangle3(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo +} // namespace math } // namespace ignition diff --git a/src/python_pybind11/src/Triangle3.hh b/src/python_pybind11/src/Triangle3.hh index 9d0a8b223..a076bbceb 100644 --- a/src/python_pybind11/src/Triangle3.hh +++ b/src/python_pybind11/src/Triangle3.hh @@ -15,15 +15,15 @@ * */ -#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 #include #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -34,14 +34,14 @@ 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 math } // namespace ignition -#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..1e135c352 100644 --- a/src/python_pybind11/src/Vector2.cc +++ b/src/python_pybind11/src/Vector2.cc @@ -33,5 +33,5 @@ void defineMathVector2(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo +} // namespace math } // namespace ignition diff --git a/src/python_pybind11/src/Vector2.hh b/src/python_pybind11/src/Vector2.hh index 171980d88..ea1076db9 100644 --- a/src/python_pybind11/src/Vector2.hh +++ b/src/python_pybind11/src/Vector2.hh @@ -15,15 +15,15 @@ * */ -#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 #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -34,14 +34,14 @@ 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; @@ -136,13 +136,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 math } // namespace ignition -#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..64a312c0e 100644 --- a/src/python_pybind11/src/Vector3.cc +++ b/src/python_pybind11/src/Vector3.cc @@ -33,5 +33,5 @@ void defineMathVector3(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo +} // namespace math } // namespace ignition diff --git a/src/python_pybind11/src/Vector3.hh b/src/python_pybind11/src/Vector3.hh index a97fc3417..5d55c524c 100644 --- a/src/python_pybind11/src/Vector3.hh +++ b/src/python_pybind11/src/Vector3.hh @@ -15,15 +15,15 @@ * */ -#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 #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -34,14 +34,14 @@ 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; @@ -160,13 +160,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 math } // namespace ignition -#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 a0081819c..7df3426e1 100644 --- a/src/python_pybind11/src/Vector3Stats.cc +++ b/src/python_pybind11/src/Vector3Stats.cc @@ -17,7 +17,7 @@ #include -#include +#include #include "Vector3Stats.hh" @@ -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(), diff --git a/src/python_pybind11/src/Vector3Stats.hh b/src/python_pybind11/src/Vector3Stats.hh index bd1848ac3..fb8580c41 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 @@ -30,7 +30,7 @@ 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 @@ -40,4 +40,4 @@ void defineMathVector3Stats(py::module &m, const std::string &typestr); } // namespace math } // namespace ignition -#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..a28d33c37 100644 --- a/src/python_pybind11/src/Vector4.cc +++ b/src/python_pybind11/src/Vector4.cc @@ -33,5 +33,5 @@ void defineMathVector4(py::module &m, const std::string &typestr) } } // namespace python -} // namespace gazebo +} // namespace math } // namespace ignition diff --git a/src/python_pybind11/src/Vector4.hh b/src/python_pybind11/src/Vector4.hh index 6db87b36b..b74d7e4c2 100644 --- a/src/python_pybind11/src/Vector4.hh +++ b/src/python_pybind11/src/Vector4.hh @@ -15,15 +15,15 @@ * */ -#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 #include -#include +#include namespace py = pybind11; using namespace pybind11::literals; @@ -34,14 +34,14 @@ 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; @@ -145,13 +145,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 math } // namespace ignition -#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 a7e623101..c88ff50ca 100644 --- a/src/python_pybind11/src/_ignition_math_pybind11.cc +++ b/src/python_pybind11/src/_ignition_math_pybind11.cc @@ -67,121 +67,121 @@ PYBIND11_MODULE(math, m) { m.doc() = "Ignition 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::defineMathInterval(m, "Interval"); + gz::math::python::defineMathInterval(m, "Interval"); - ignition::math::python::defineMathRegion3(m, "Region3"); + gz::math::python::defineMathRegion3(m, "Region3"); - ignition::math::python::defineMathPolynomial3(m, "Polynomial3"); + gz::math::python::defineMathPolynomial3(m, "Polynomial3"); - 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::defineMathMatrix6(m, "Matrix6"); + gz::math::python::defineMathMatrix6(m, "Matrix6"); - 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/ruby/Angle.i b/src/ruby/Angle.i index 190d11c8b..47f72905e 100644 --- a/src/ruby/Angle.i +++ b/src/ruby/Angle.i @@ -17,7 +17,7 @@ %module angle %{ -#include +#include %} namespace ignition diff --git a/src/ruby/AxisAlignedBox.i b/src/ruby/AxisAlignedBox.i index a8d66ff9d..9c2c50874 100644 --- a/src/ruby/AxisAlignedBox.i +++ b/src/ruby/AxisAlignedBox.i @@ -19,11 +19,11 @@ %{ #include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include %} %include "typemaps.i" diff --git a/src/ruby/Box.i b/src/ruby/Box.i index dbdd32b5f..2d801601b 100644 --- a/src/ruby/Box.i +++ b/src/ruby/Box.i @@ -17,14 +17,14 @@ %module box %{ -#include -#include -#include -#include -#include -#include - -#include "ignition/math/detail/WellOrderedVector.hh" +#include +#include +#include +#include +#include +#include + +#include "gz/math/detail/WellOrderedVector.hh" #include #include diff --git a/src/ruby/Color.i b/src/ruby/Color.i index d916614e2..9c4dba572 100644 --- a/src/ruby/Color.i +++ b/src/ruby/Color.i @@ -17,10 +17,10 @@ %module Color %{ -#include -#include -#include -#include +#include +#include +#include +#include %} %include "std_string.i" diff --git a/src/ruby/Cylinder.i b/src/ruby/Cylinder.i index a5226ae27..3799d932f 100644 --- a/src/ruby/Cylinder.i +++ b/src/ruby/Cylinder.i @@ -17,11 +17,11 @@ %module cylinder %{ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include %} namespace ignition diff --git a/src/ruby/DiffDriveOdometry.i b/src/ruby/DiffDriveOdometry.i index 216c511c1..efb7d5901 100644 --- a/src/ruby/DiffDriveOdometry.i +++ b/src/ruby/DiffDriveOdometry.i @@ -19,10 +19,10 @@ %{ #include #include -#include -#include -#include -#include +#include +#include +#include +#include %} %include "typemaps.i" diff --git a/src/ruby/Filter.i b/src/ruby/Filter.i index be9e70562..dfcef607e 100644 --- a/src/ruby/Filter.i +++ b/src/ruby/Filter.i @@ -17,11 +17,11 @@ %module filter %{ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include %} %import Quaternion.i diff --git a/src/ruby/Frustum.i b/src/ruby/Frustum.i index ee756eed1..435950b1b 100644 --- a/src/ruby/Frustum.i +++ b/src/ruby/Frustum.i @@ -17,12 +17,12 @@ %module frustum %{ -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include %} namespace ignition diff --git a/src/ruby/GaussMarkovProcess.i b/src/ruby/GaussMarkovProcess.i index d70bb0836..412840e3e 100644 --- a/src/ruby/GaussMarkovProcess.i +++ b/src/ruby/GaussMarkovProcess.i @@ -17,7 +17,7 @@ %module gaussMarkovProcess %{ -#include +#include %} namespace ignition diff --git a/src/ruby/Helpers.i b/src/ruby/Helpers.i index 408cb549c..97f8d88f0 100644 --- a/src/ruby/Helpers.i +++ b/src/ruby/Helpers.i @@ -17,7 +17,7 @@ %module helpers %{ -#include +#include %} %include "std_string.i" diff --git a/src/ruby/Inertial.i b/src/ruby/Inertial.i index c85cdcdee..ee36cb1b2 100644 --- a/src/ruby/Inertial.i +++ b/src/ruby/Inertial.i @@ -17,10 +17,10 @@ %module inertial %{ -#include -#include -#include "ignition/math/MassMatrix3.hh" -#include "ignition/math/Pose3.hh" +#include +#include +#include "gz/math/MassMatrix3.hh" +#include "gz/math/Pose3.hh" %} namespace ignition diff --git a/src/ruby/Kmeans.i b/src/ruby/Kmeans.i index c1c26ac10..5c7fd2ca8 100644 --- a/src/ruby/Kmeans.i +++ b/src/ruby/Kmeans.i @@ -17,9 +17,9 @@ %module kmeans %{ -#include -#include -#include +#include +#include +#include %} %include "std_vector.i" diff --git a/src/ruby/Line2.i b/src/ruby/Line2.i index 658c98ab4..78a0e8978 100644 --- a/src/ruby/Line2.i +++ b/src/ruby/Line2.i @@ -17,9 +17,9 @@ %module line2 %{ -#include -#include -#include +#include +#include +#include %} %include "std_string.i" diff --git a/src/ruby/Line3.i b/src/ruby/Line3.i index 476abfced..82f5c7abc 100644 --- a/src/ruby/Line3.i +++ b/src/ruby/Line3.i @@ -17,9 +17,9 @@ %module line3 %{ -#include -#include -#include +#include +#include +#include %} %include "std_string.i" diff --git a/src/ruby/MassMatrix3.i b/src/ruby/MassMatrix3.i index 6fea9dd2c..1727e525d 100644 --- a/src/ruby/MassMatrix3.i +++ b/src/ruby/MassMatrix3.i @@ -17,14 +17,14 @@ %module massmatrix3 %{ -#include "ignition/math/MassMatrix3.hh" +#include "gz/math/MassMatrix3.hh" -#include "ignition/math/Helpers.hh" -#include "ignition/math/Material.hh" -#include "ignition/math/Quaternion.hh" -#include "ignition/math/Vector2.hh" -#include "ignition/math/Vector3.hh" -#include "ignition/math/Matrix3.hh" +#include "gz/math/Helpers.hh" +#include "gz/math/Material.hh" +#include "gz/math/Quaternion.hh" +#include "gz/math/Vector2.hh" +#include "gz/math/Vector3.hh" +#include "gz/math/Matrix3.hh" %} namespace ignition diff --git a/src/ruby/Material.i b/src/ruby/Material.i index 74669b44e..80f08fcdf 100644 --- a/src/ruby/Material.i +++ b/src/ruby/Material.i @@ -17,10 +17,10 @@ %module material %{ -#include -#include -#include -#include +#include +#include +#include +#include %} %include "std_string.i" diff --git a/src/ruby/MaterialType.i b/src/ruby/MaterialType.i index 45864fc13..f7a10ccac 100644 --- a/src/ruby/MaterialType.i +++ b/src/ruby/MaterialType.i @@ -17,9 +17,9 @@ %module materialtype %{ -#include -#include -#include +#include +#include +#include %} namespace ignition diff --git a/src/ruby/Matrix3.i b/src/ruby/Matrix3.i index 5aa049134..22f8028a4 100644 --- a/src/ruby/Matrix3.i +++ b/src/ruby/Matrix3.i @@ -17,11 +17,11 @@ %module matrix3 %{ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include %} %include "std_string.i" diff --git a/src/ruby/Matrix4.i b/src/ruby/Matrix4.i index 35f93b2e6..3a6238ef6 100644 --- a/src/ruby/Matrix4.i +++ b/src/ruby/Matrix4.i @@ -17,12 +17,12 @@ %module matrix4 %{ -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include %} %include "std_string.i" diff --git a/src/ruby/MovingWindowFilter.i b/src/ruby/MovingWindowFilter.i index ea6fc003d..bd9f26428 100644 --- a/src/ruby/MovingWindowFilter.i +++ b/src/ruby/MovingWindowFilter.i @@ -16,8 +16,8 @@ */ %module movingwindowfilter %{ -#include "ignition/math/MovingWindowFilter.hh" -#include "ignition/math/Vector3.hh" +#include "gz/math/MovingWindowFilter.hh" +#include "gz/math/Vector3.hh" %} namespace ignition diff --git a/src/ruby/OrientedBox.i b/src/ruby/OrientedBox.i index ca32b3121..6c6ee9587 100644 --- a/src/ruby/OrientedBox.i +++ b/src/ruby/OrientedBox.i @@ -18,14 +18,14 @@ %module orientedbox %{ #include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include %} namespace ignition diff --git a/src/ruby/PID.i b/src/ruby/PID.i index 452e73045..7861cfcc2 100644 --- a/src/ruby/PID.i +++ b/src/ruby/PID.i @@ -16,7 +16,7 @@ */ %module pid %{ - #include + #include %} %include "typemaps.i" diff --git a/src/ruby/Plane.i b/src/ruby/Plane.i index 0c35aa481..892e3fe91 100644 --- a/src/ruby/Plane.i +++ b/src/ruby/Plane.i @@ -17,13 +17,13 @@ %module plane %{ -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include #include %} diff --git a/src/ruby/Pose3.i b/src/ruby/Pose3.i index 5b94579ba..202cc2e8c 100644 --- a/src/ruby/Pose3.i +++ b/src/ruby/Pose3.i @@ -17,10 +17,10 @@ %module quaternion %{ - #include - #include - #include - #include + #include + #include + #include + #include %} %include "std_string.i" diff --git a/src/ruby/Quaternion.i b/src/ruby/Quaternion.i index 0bc6d70bf..c97f45e38 100644 --- a/src/ruby/Quaternion.i +++ b/src/ruby/Quaternion.i @@ -17,10 +17,10 @@ %module quaternion %{ -#include -#include -#include -#include +#include +#include +#include +#include %} %include "std_string.i" diff --git a/src/ruby/Rand.i b/src/ruby/Rand.i index 0e7aa25cf..3ef19f5a7 100644 --- a/src/ruby/Rand.i +++ b/src/ruby/Rand.i @@ -17,7 +17,7 @@ %module rand %{ -#include +#include %} namespace ignition diff --git a/src/ruby/RollingMean.i b/src/ruby/RollingMean.i index be96792d4..0788de76c 100644 --- a/src/ruby/RollingMean.i +++ b/src/ruby/RollingMean.i @@ -17,7 +17,7 @@ %module rollingMean %{ -#include +#include %} namespace ignition diff --git a/src/ruby/RotationSpline.i b/src/ruby/RotationSpline.i index 7f62e815d..8af437de5 100644 --- a/src/ruby/RotationSpline.i +++ b/src/ruby/RotationSpline.i @@ -17,9 +17,9 @@ %module rotationspline %{ -#include -#include -#include +#include +#include +#include %} namespace ignition diff --git a/src/ruby/SemanticVersion.i b/src/ruby/SemanticVersion.i index cb105adfd..9d2e2becd 100644 --- a/src/ruby/SemanticVersion.i +++ b/src/ruby/SemanticVersion.i @@ -17,7 +17,7 @@ %module semanticversion %{ - #include + #include %} %include "std_string.i" diff --git a/src/ruby/SignalStats.i b/src/ruby/SignalStats.i index b918d3f35..406f922f8 100644 --- a/src/ruby/SignalStats.i +++ b/src/ruby/SignalStats.i @@ -18,7 +18,7 @@ %module signalStats %{ -#include +#include %} %include "std_string.i" diff --git a/src/ruby/Sphere.i b/src/ruby/Sphere.i index c2fa4b1a4..3c67ab3d5 100644 --- a/src/ruby/Sphere.i +++ b/src/ruby/Sphere.i @@ -17,11 +17,11 @@ %module sphere %{ -#include "ignition/math/Sphere.hh" -#include "ignition/math/MassMatrix3.hh" -#include "ignition/math/Material.hh" -#include "ignition/math/Quaternion.hh" -#include "ignition/math/Plane.hh" +#include "gz/math/Sphere.hh" +#include "gz/math/MassMatrix3.hh" +#include "gz/math/Material.hh" +#include "gz/math/Quaternion.hh" +#include "gz/math/Plane.hh" %} %include "typemaps.i" diff --git a/src/ruby/SphericalCoordinates.i b/src/ruby/SphericalCoordinates.i index 6b006f173..ce98ad306 100644 --- a/src/ruby/SphericalCoordinates.i +++ b/src/ruby/SphericalCoordinates.i @@ -20,10 +20,10 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include %} namespace ignition diff --git a/src/ruby/Spline.i b/src/ruby/Spline.i index cf086a577..f68c181ae 100644 --- a/src/ruby/Spline.i +++ b/src/ruby/Spline.i @@ -17,10 +17,10 @@ %module spline %{ -#include -#include -#include -#include +#include +#include +#include +#include %} namespace ignition diff --git a/src/ruby/StopWatch.i b/src/ruby/StopWatch.i index 161bb6105..7a640767d 100644 --- a/src/ruby/StopWatch.i +++ b/src/ruby/StopWatch.i @@ -19,9 +19,9 @@ %{ #include #include -#include "ignition/math/Stopwatch.hh" -#include -#include +#include "gz/math/Stopwatch.hh" +#include +#include %} %include "typemaps.i" diff --git a/src/ruby/Temperature.i b/src/ruby/Temperature.i index 27043ea62..8c538c647 100644 --- a/src/ruby/Temperature.i +++ b/src/ruby/Temperature.i @@ -17,7 +17,7 @@ %module temperature %{ -#include +#include %} %include "std_string.i" diff --git a/src/ruby/Triangle.i b/src/ruby/Triangle.i index 08c5f5370..966b29e7e 100644 --- a/src/ruby/Triangle.i +++ b/src/ruby/Triangle.i @@ -17,12 +17,12 @@ %module triangle %{ -#include -#include -#include +#include +#include +#include #include -#include -#include +#include +#include %} namespace ignition diff --git a/src/ruby/Triangle3.i b/src/ruby/Triangle3.i index 78c20e10b..2ad52da92 100644 --- a/src/ruby/Triangle3.i +++ b/src/ruby/Triangle3.i @@ -17,12 +17,12 @@ %module triangle3 %{ -#include -#include -#include +#include +#include +#include #include -#include -#include +#include +#include %} namespace ignition diff --git a/src/ruby/Vector2.i b/src/ruby/Vector2.i index cad4128ea..055bca283 100644 --- a/src/ruby/Vector2.i +++ b/src/ruby/Vector2.i @@ -23,7 +23,7 @@ %module vector2 %{ -#include +#include %} namespace ignition diff --git a/src/ruby/Vector3.i b/src/ruby/Vector3.i index 0acf12da5..09188b53a 100644 --- a/src/ruby/Vector3.i +++ b/src/ruby/Vector3.i @@ -23,7 +23,7 @@ %module vector3 %{ -#include +#include %} namespace ignition diff --git a/src/ruby/Vector3Stats.i b/src/ruby/Vector3Stats.i index 460733282..ba0060cb4 100644 --- a/src/ruby/Vector3Stats.i +++ b/src/ruby/Vector3Stats.i @@ -17,10 +17,10 @@ %module vector3stats %{ -#include -#include -#include -#include +#include +#include +#include +#include %} %include "std_string.i" diff --git a/src/ruby/Vector4.i b/src/ruby/Vector4.i index a9235cae3..7ae792253 100644 --- a/src/ruby/Vector4.i +++ b/src/ruby/Vector4.i @@ -23,7 +23,7 @@ %module vector4 %{ -#include +#include %} namespace ignition diff --git a/test/integration/deprecated_TEST.cc b/test/integration/deprecated_TEST.cc new file mode 100644 index 000000000..24126f603 --- /dev/null +++ b/test/integration/deprecated_TEST.cc @@ -0,0 +1,27 @@ +/* + * 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 +#include + +///////////////////////////////////////////////// +// Make sure the ignition namespace still works +TEST(Deprecated, IgnitionNamespace) +{ + gz::math::Angle angle; + (void) angle; +} diff --git a/tutorials/cppgetstarted.md b/tutorials/cppgetstarted.md index cffc8fe62..c9f1fed20 100644 --- a/tutorials/cppgetstarted.md +++ b/tutorials/cppgetstarted.md @@ -24,7 +24,7 @@ For this example, we'll take the short and easy approach. At this point your main file should look like ```{.cpp} -#include +#include int main() { @@ -38,7 +38,7 @@ ignition::math::Vector3d type which is a typedef of `Vector3`. The resul addition will be a main file similar to the following. ```{.cpp} -#include +#include int main() { @@ -53,7 +53,7 @@ Finally, we can compute the distance between `point1` and `point2` using the ignition::math::Vector3::Distance() function and output the distance value. ```{.cpp} -#include +#include int main() {