Skip to content

Commit

Permalink
Support migration
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon committed Aug 26, 2022
1 parent e13493f commit 90dcc7c
Show file tree
Hide file tree
Showing 355 changed files with 2,905 additions and 1,693 deletions.
2 changes: 1 addition & 1 deletion BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -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",
])

Expand Down
5 changes: 4 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 2 additions & 2 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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)


Expand Down
2 changes: 2 additions & 0 deletions eigen3/include/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
add_subdirectory(gz)
install(DIRECTORY ignition DESTINATION ${IGN_INCLUDE_INSTALL_DIR_FULL})
94 changes: 47 additions & 47 deletions eigen3/include/gz/math/eigen3/Conversions.hh
Original file line number Diff line number Diff line change
Expand Up @@ -15,45 +15,45 @@
*
*/

#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 <Eigen/Geometry>
#include <ignition/math/AxisAlignedBox.hh>
#include <ignition/math/Matrix3.hh>
#include <ignition/math/Matrix6.hh>
#include <ignition/math/Pose3.hh>
#include <ignition/math/Quaternion.hh>
#include <ignition/math/Vector3.hh>
#include <gz/math/AxisAlignedBox.hh>
#include <gz/math/Matrix3.hh>
#include <gz/math/Matrix6.hh>
#include <gz/math/Pose3.hh>
#include <gz/math/Quaternion.hh>
#include <gz/math/Vector3.hh>

namespace ignition
{
namespace math
{
namespace eigen3
{
/// \brief Convert from ignition::math::Vector3d to Eigen::Vector3d.
/// \param[in] _v ignition::math::Vector3d to convert
/// \brief Convert from gz::math::Vector3d to Eigen::Vector3d.
/// \param[in] _v gz::math::Vector3d to convert
/// \return The equivalent Eigen::Vector3d.
inline Eigen::Vector3d convert(const ignition::math::Vector3d &_v)
inline Eigen::Vector3d convert(const gz::math::Vector3d &_v)
{
return Eigen::Vector3d(_v[0], _v[1], _v[2]);
}

/// \brief Convert from ignition::math::AxisAlignedBox to
/// \brief Convert from gz::math::AxisAlignedBox to
/// Eigen::AlignedBox3d.
/// \param[in] _b ignition::math::AxisAlignedBox to convert
/// \param[in] _b gz::math::AxisAlignedBox to convert
/// \return The equivalent Eigen::AlignedBox3d.
inline Eigen::AlignedBox3d convert(
const ignition::math::AxisAlignedBox &_b)
const gz::math::AxisAlignedBox &_b)
{
return Eigen::AlignedBox3d(convert(_b.Min()), convert(_b.Max()));
}

/// \brief Convert from ignition::math::Matrix3d to Eigen::Matrix3d.
/// \param[in] _m ignition::math::Matrix3d to convert.
/// \brief Convert from gz::math::Matrix3d to Eigen::Matrix3d.
/// \param[in] _m gz::math::Matrix3d to convert.
/// \return The equivalent Eigen::Matrix3d.
inline Eigen::Matrix3d convert(const ignition::math::Matrix3d &_m)
inline Eigen::Matrix3d convert(const gz::math::Matrix3d &_m)
{
Eigen::Matrix3d matrix;
for (std::size_t i=0; i < 3; ++i)
Expand All @@ -67,9 +67,9 @@ namespace ignition
return matrix;
}

/// \brief Convert from ignition::math::Matrix6d to
/// \brief Convert from gz::math::Matrix6d to
/// Eigen::Matrix<Precision, 6, 6>.
/// \param[in] _m ignition::math::Matrix6d to convert.
/// \param[in] _m gz::math::Matrix6d to convert.
/// \return The equivalent Eigen::Matrix<Precision, 6, 6>.
/// \tparam Precision Precision such as int, double or float.
template<typename Precision>
Expand All @@ -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();
Expand All @@ -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());
Expand All @@ -114,38 +114,38 @@ 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];

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)
Expand All @@ -158,9 +158,9 @@ namespace ignition
}

/// \brief Convert Eigen::Matrix<Precision, 6, 6> to
/// ignition::math::Matrix6d.
/// gz::math::Matrix6d.
/// \param[in] _m Eigen::Matrix<Precision, 6, 6> to convert.
/// \return The equivalent ignition::math::Matrix6d.
/// \return The equivalent gz::math::Matrix6d.
/// \tparam Precision Precision such as int, double or float.
template<typename Precision>
inline
Expand All @@ -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();
Expand All @@ -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()));

Expand Down
20 changes: 10 additions & 10 deletions eigen3/include/gz/math/eigen3/Util.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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 <vector>

#include <Eigen/Geometry>
#include <Eigen/Eigenvalues>

#include <ignition/math/AxisAlignedBox.hh>
#include <ignition/math/Matrix3.hh>
#include <ignition/math/OrientedBox.hh>
#include <ignition/math/Pose3.hh>
#include <ignition/math/Quaternion.hh>
#include <ignition/math/Vector3.hh>
#include <ignition/math/eigen3/Conversions.hh>
#include <gz/math/AxisAlignedBox.hh>
#include <gz/math/Matrix3.hh>
#include <gz/math/OrientedBox.hh>
#include <gz/math/Pose3.hh>
#include <gz/math/Quaternion.hh>
#include <gz/math/Vector3.hh>
#include <gz/math/eigen3/Conversions.hh>

namespace ignition
{
Expand Down Expand Up @@ -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<math::Vector3d> &_vertices)
{
math::OrientedBoxd box;
Expand Down
19 changes: 19 additions & 0 deletions eigen3/include/ignition/math/eigen3.hh
Original file line number Diff line number Diff line change
@@ -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 <gz/math/eigen3.hh>
#include <ignition/math/config.hh>
19 changes: 19 additions & 0 deletions eigen3/include/ignition/math/eigen3/Conversions.hh
Original file line number Diff line number Diff line change
@@ -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 <gz/math/eigen3/Conversions.hh>
#include <ignition/math/config.hh>
19 changes: 19 additions & 0 deletions eigen3/include/ignition/math/eigen3/Util.hh
Original file line number Diff line number Diff line change
@@ -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 <gz/math/eigen3/Util.hh>
#include <ignition/math/config.hh>
Loading

0 comments on commit 90dcc7c

Please sign in to comment.