@@ -688,16 +688,16 @@ bool MoveItVisualTools::publishCollisionCuboid(const geometry_msgs::Point& point
688
688
return processCollisionObjectMsg (collision_obj, color);
689
689
}
690
690
691
- bool MoveItVisualTools::publishCollisionCuboid (const Eigen::Affine3d& pose, double x , double y , double z ,
691
+ bool MoveItVisualTools::publishCollisionCuboid (const Eigen::Affine3d& pose, double width , double depth , double height ,
692
692
const std::string& name, const rviz_visual_tools::colors& color)
693
693
{
694
- geometry_msgs::Pose pose_msg;
695
- tf::poseEigenToMsg (pose, pose_msg);
696
- return publishCollisionCuboid (pose_msg, x, y, z, name, color);
694
+ geometry_msgs::Pose pose_msg = tf2::toMsg (pose);
695
+ return publishCollisionCuboid (pose_msg, width, depth, height, name, color);
697
696
}
698
697
699
- bool MoveItVisualTools::publishCollisionCuboid (const geometry_msgs::Pose& pose, double width, double depth, double height,
700
- const std::string& name, const rviz_visual_tools::colors& color)
698
+ bool MoveItVisualTools::publishCollisionCuboid (const geometry_msgs::Pose& pose, double width, double depth,
699
+ double height, const std::string& name,
700
+ const rviz_visual_tools::colors& color)
701
701
{
702
702
moveit_msgs::CollisionObject collision_obj;
703
703
collision_obj.header .stamp = ros::Time::now ();
0 commit comments