Skip to content

Commit 39fabdf

Browse files
authored
fixing melodic branch with tf2 updates (#34)
1 parent 7f0a988 commit 39fabdf

File tree

2 files changed

+10
-10
lines changed

2 files changed

+10
-10
lines changed

include/moveit_visual_tools/moveit_visual_tools.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -357,11 +357,11 @@ class MoveItVisualTools : public rviz_visual_tools::RvizVisualTools
357357
* \param color to display the collision object with
358358
* \return true on sucess
359359
**/
360-
bool publishCollisionCuboid(const Eigen::Affine3d& pose, double width, double depth, double height, const std::string& name,
361-
const rviz_visual_tools::colors& color);
360+
bool publishCollisionCuboid(const Eigen::Affine3d& pose, double width, double depth, double height,
361+
const std::string& name, const rviz_visual_tools::colors& color);
362362

363-
bool publishCollisionCuboid(const geometry_msgs::Pose& pose, double x, double y, double z, const std::string& name,
364-
const rviz_visual_tools::colors& color);
363+
bool publishCollisionCuboid(const geometry_msgs::Pose& pose, double width, double depth, double height,
364+
const std::string& name, const rviz_visual_tools::colors& color);
365365

366366
/**
367367
* \brief Create a MoveIt Collision cylinder between two points

src/moveit_visual_tools.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -688,16 +688,16 @@ bool MoveItVisualTools::publishCollisionCuboid(const geometry_msgs::Point& point
688688
return processCollisionObjectMsg(collision_obj, color);
689689
}
690690

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,
692692
const std::string& name, const rviz_visual_tools::colors& color)
693693
{
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);
697696
}
698697

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)
701701
{
702702
moveit_msgs::CollisionObject collision_obj;
703703
collision_obj.header.stamp = ros::Time::now();

0 commit comments

Comments
 (0)