Skip to content

Commit

Permalink
Switch to gz_math_vendor. (#1177)
Browse files Browse the repository at this point in the history
Ignition is no more, long live Gazebo.

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Apr 1, 2024
1 parent f3f8c1f commit ebca223
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 14 deletions.
6 changes: 3 additions & 3 deletions rviz_default_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -61,8 +61,8 @@ find_package(Qt5 REQUIRED COMPONENTS Widgets Test)

find_package(geometry_msgs REQUIRED)

find_package(ignition_math6_vendor REQUIRED)
find_package(ignition-math6 REQUIRED)
find_package(gz_math_vendor REQUIRED)
find_package(gz-math REQUIRED)

find_package(image_transport REQUIRED)
find_package(interactive_markers REQUIRED)
Expand Down Expand Up @@ -265,7 +265,7 @@ target_link_libraries(rviz_default_plugins PUBLIC
)

target_link_libraries(rviz_default_plugins PRIVATE
ignition-math6
gz-math::core
resource_retriever::resource_retriever
)

Expand Down
2 changes: 1 addition & 1 deletion rviz_default_plugins/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
<exec_depend>rviz_ogre_vendor</exec_depend>

<depend>geometry_msgs</depend>
<depend>ignition_math6_vendor</depend>
<depend>gz_math_vendor</depend>
<depend>image_transport</depend>
<depend>interactive_markers</depend>
<depend>laser_geometry</depend>
Expand Down
20 changes: 10 additions & 10 deletions rviz_default_plugins/src/rviz_default_plugins/robot/robot_link.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,11 +50,11 @@

#include <QFileInfo> // NOLINT cpplint cannot handle include order here

#include <ignition/math/Inertial.hh>
#include <ignition/math/MassMatrix3.hh>
#include <ignition/math/Pose3.hh>
#include <ignition/math/Quaternion.hh>
#include <ignition/math/Vector3.hh>
#include <gz/math/Inertial.hh>
#include <gz/math/MassMatrix3.hh>
#include <gz/math/Pose3.hh>
#include <gz/math/Quaternion.hh>
#include <gz/math/Vector3.hh>

#include "resource_retriever/retriever.hpp"

Expand Down Expand Up @@ -871,18 +871,18 @@ void RobotLink::createMass(const urdf::LinkConstSharedPtr & link)
void RobotLink::createInertia(const urdf::LinkConstSharedPtr & link)
{
if (link->inertial) {
const ignition::math::Vector3d i_xx_yy_zz(
const gz::math::Vector3d i_xx_yy_zz(
link->inertial->ixx,
link->inertial->iyy,
link->inertial->izz);
const ignition::math::Vector3d Ixyxzyz(
const gz::math::Vector3d Ixyxzyz(
link->inertial->ixy,
link->inertial->ixz,
link->inertial->iyz);
ignition::math::MassMatrix3d mass_matrix(link->inertial->mass, i_xx_yy_zz, Ixyxzyz);
gz::math::MassMatrix3d mass_matrix(link->inertial->mass, i_xx_yy_zz, Ixyxzyz);

ignition::math::Vector3d box_scale;
ignition::math::Quaterniond box_rot;
gz::math::Vector3d box_scale;
gz::math::Quaterniond box_rot;
if (!mass_matrix.EquivalentBox(box_scale, box_rot)) {
// Invalid inertia, load with default scale
if (link->parent_joint && link->parent_joint->type != urdf::Joint::FIXED) {
Expand Down

0 comments on commit ebca223

Please sign in to comment.