Skip to content

Commit

Permalink
pilz_industrial_motion_planner: Use tf2::fromMsg instead of tf2::conv…
Browse files Browse the repository at this point in the history
…ert (#3219)
  • Loading branch information
traversaro authored Jan 10, 2025
1 parent 549a2ee commit cd26fc0
Showing 1 changed file with 2 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ bool pilz_industrial_motion_planner::computePoseIK(const planning_scene::Plannin
const double timeout)
{
Eigen::Isometry3d pose_eigen;
tf2::convert<geometry_msgs::msg::Pose, Eigen::Isometry3d>(pose, pose_eigen);
tf2::fromMsg(pose, pose_eigen);
return computePoseIK(scene, group_name, link_name, pose_eigen, frame_id, seed, solution, check_self_collision,
timeout);
}
Expand Down Expand Up @@ -591,7 +591,7 @@ bool pilz_industrial_motion_planner::isStateColliding(const planning_scene::Plan
void normalizeQuaternion(geometry_msgs::msg::Quaternion& quat)
{
tf2::Quaternion q;
tf2::convert<geometry_msgs::msg::Quaternion, tf2::Quaternion>(quat, q);
tf2::fromMsg(quat, q);
quat = tf2::toMsg(q.normalized());
}

Expand Down

0 comments on commit cd26fc0

Please sign in to comment.