Skip to content

Commit

Permalink
publish cuboids with size
Browse files Browse the repository at this point in the history
  • Loading branch information
Mike Lautman committed Aug 18, 2019
1 parent 4adf323 commit 705aeba
Showing 1 changed file with 19 additions and 0 deletions.
19 changes: 19 additions & 0 deletions include/moveit_visual_tools/moveit_visual_tools.h
Original file line number Diff line number Diff line change
Expand Up @@ -366,6 +366,25 @@ class MoveItVisualTools : public rviz_visual_tools::RvizVisualTools
bool publishCollisionCuboid(const geometry_msgs::Pose& pose, double width, double depth, double height,
const std::string& name, const rviz_visual_tools::colors& color);

/**
* \brief Create a MoveIt collision rectangular cuboid at the given pose
* \param pose - position of the centroid of the cube
* \param size - the size (x,y,z) of the object in its local frame
* \param name - semantic name of MoveIt collision object
* \param color to display the collision object with
* \return true on sucess
**/
bool publishCollisionCuboid(const Eigen::Isometry3d& pose, const Eigen::Vector3d& size, const std::string& name,
const rviz_visual_tools::colors& color)
{
return publishCollisionCuboid(pose, size.x(), size.y(), size.z(), name, color);
}
bool publishCollisionCuboid(const geometry_msgs::Pose& pose, const geometry_msgs::Vector3& size,
const std::string& name, const rviz_visual_tools::colors& color)
{
return publishCollisionCuboid(pose, size.x, size.y, size.z, name, color);
}

/**
* \brief Create a MoveIt Collision cylinder between two points
* \param point a - x,y,z in space of a point
Expand Down

0 comments on commit 705aeba

Please sign in to comment.