From 1d21fe97132d79402804a0a2f39291e01a91b8a1 Mon Sep 17 00:00:00 2001 From: Silvio Traversaro Date: Fri, 10 Jan 2025 01:22:28 +0100 Subject: [PATCH] pilz_industrial_motion_planner: Use tf2::fromMsg instead of tf2::convert (#3219) (cherry picked from commit cd26fc038f0449849cba5084b23d33dfe52ac5a1) --- .../src/trajectory_functions.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp index 2248d38a3f..077456a3a0 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp @@ -113,7 +113,7 @@ bool pilz_industrial_motion_planner::computePoseIK(const planning_scene::Plannin const double timeout) { Eigen::Isometry3d pose_eigen; - tf2::convert(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); } @@ -589,7 +589,7 @@ bool pilz_industrial_motion_planner::isStateColliding(const planning_scene::Plan void normalizeQuaternion(geometry_msgs::msg::Quaternion& quat) { tf2::Quaternion q; - tf2::convert(quat, q); + tf2::fromMsg(quat, q); quat = tf2::toMsg(q.normalized()); }