Public Member Functions | Static Public Member Functions | Protected Attributes | Private Member Functions
moveit_visual_tools::VisualTools Class Reference

#include <visual_tools.h>

List of all members.

Public Member Functions

bool attachCO (const std::string &name, const std::string &ee_parent_link)
 Attach a collision object from the planning scene.
bool cleanupACO (const std::string &name)
 Remove an active collision object from the planning scene.
bool cleanupCO (std::string name)
 Remove a collision object from the planning scene.
void deleteAllMarkers ()
 Tell Rviz to clear all markers on a particular display. Note: only works on ROS Indigo and newer.
void generateRandomPose (geometry_msgs::Pose &pose)
 Create a random pose.
const std::string getBaseFrame ()
 Get the base frame.
MOVEIT_DEPRECATED const std::string getBaseLink ()
Eigen::Vector3d getCenterPoint (Eigen::Vector3d a, Eigen::Vector3d b)
 Find the center between to points.
void getCollisionWallMsg (double x, double y, double angle, double width, const std::string name, moveit_msgs::CollisionObject &collision_obj)
 Helper for publishCollisionWall.
std_msgs::ColorRGBA getColor (const rviz_colors &color)
 Get the RGB value of standard colors.
double getGlobalScale ()
 Getter for the global scale used for changing size of all markers.
const rviz_colors getRandColor ()
 Get a random color from the list of hardcoded enum color types.
geometry_msgs::Vector3 getScale (const rviz_scales &scale, bool arrow_scale=false, double marker_scale=1.0)
 Get the rviz marker scale of standard sizes.
Eigen::Affine3d getVectorBetweenPoints (Eigen::Vector3d a, Eigen::Vector3d b)
 Create a vector that points from point a to point b.
bool hideRobot ()
 Fake removing a Robot State display in Rviz by simply moving it very far away.
bool isMuted ()
 Return if we are in verbose mode.
void loadAttachedPub ()
void loadCollisionPub ()
bool loadCollisionSceneFromFile (const std::string &path)
 Load a planning scene to a planning_scene_monitor from file.
bool loadEEMarker (const std::string &ee_group_name, const std::string &planning_group)
 Call this once at begining to load the robot marker.
void loadMarkerPub ()
 Load publishers as needed.
void loadPlanningPub ()
bool loadPlanningSceneMonitor ()
 Load a planning scene monitor if one was not passed into the constructor.
bool loadRobotMarkers ()
 Caches the meshes and geometry of a robot. NOTE: perhaps not maintained...
void loadRobotStatePub (const std::string &marker_topic=DISPLAY_ROBOT_STATE_TOPIC)
bool loadRvizMarkers ()
 Pre-load rviz markers for better efficiency.
bool loadSharedRobotState ()
 Load robot state only as needed.
void loadTrajectoryPub ()
void print ()
 Debug variables to console.
bool processCollisionObjectMsg (moveit_msgs::CollisionObject msg)
 Skip a ROS message call by sending directly to planning scene monitor.
bool publishAnimatedGrasp (const moveit_msgs::Grasp &grasp, const std::string &ee_parent_link, double animate_speed)
 Animate a single grasp in its movement direction.
bool publishAnimatedGrasps (const std::vector< moveit_msgs::Grasp > &possible_grasps, const std::string &ee_parent_link, double animate_speed=0.01)
 Display an animated vector of grasps including its approach movement in Rviz.
bool publishArrow (const Eigen::Affine3d &pose, const rviz_colors color=BLUE, const rviz_scales scale=REGULAR)
 Publish a marker of an arrow to rviz.
bool publishArrow (const geometry_msgs::Pose &pose, const rviz_colors color=BLUE, const rviz_scales scale=REGULAR)
bool publishBlock (const geometry_msgs::Pose &pose, const rviz_colors color=BLUE, const double &block_size=0.1)
 Publish a marker of a block to Rviz.
bool publishCollisionBlock (geometry_msgs::Pose block_pose, std::string block_name, double block_size)
 Create a MoveIt Collision block at the given pose.
bool publishCollisionCylinder (geometry_msgs::Point a, geometry_msgs::Point b, std::string object_name, double radius)
 Create a MoveIt Collision cylinder between two points.
bool publishCollisionCylinder (Eigen::Vector3d a, Eigen::Vector3d b, std::string object_name, double radius)
bool publishCollisionCylinder (Eigen::Affine3d object_pose, std::string object_name, double radius, double height)
 Create a MoveIt Collision cylinder with a center point pose.
bool publishCollisionCylinder (geometry_msgs::Pose object_pose, std::string object_name, double radius, double height)
bool publishCollisionFloor (double z, std::string plane_name)
 Make the floor a collision object.
bool publishCollisionGraph (const graph_msgs::GeometryGraph &graph, const std::string &object_name, double radius)
 Publish a connected birectional graph.
bool publishCollisionTable (double x, double y, double angle, double width, double height, double depth, const std::string name)
 Publish a typical room table.
bool publishCollisionWall (double x, double y, double angle, double width, const std::string name)
 Publish a typical room wall.
bool publishCylinder (const geometry_msgs::Pose &pose, const rviz_colors color=BLUE, double height=0.1, double radius=0.1)
 Publish a marker of a cylinder to Rviz.
bool publishEEMarkers (const geometry_msgs::Pose &pose, const rviz_colors &color=WHITE, const std::string &ns="end_effector")
 Publish an end effector to rviz.
bool publishGraph (const graph_msgs::GeometryGraph &graph, const rviz_colors color, double radius)
 Publish a graph.
bool publishGrasps (const std::vector< moveit_msgs::Grasp > &possible_grasps, const std::string &ee_parent_link)
 Show grasps generated from moveit_simple_grasps or other MoveIt Grasp message sources.
bool publishIKSolutions (const std::vector< trajectory_msgs::JointTrajectoryPoint > &ik_solutions, const std::string &planning_group, double display_time=0.4)
 Display an vector of inverse kinematic solutions for the IK service in Rviz Note: this is published to the 'Planned Path' section of the 'MotionPlanning' display in Rviz.
bool publishLine (const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, const rviz_colors color=BLUE, const rviz_scales scale=REGULAR)
 Publish a marker of line to rviz.
bool publishMarker (const visualization_msgs::Marker &marker)
 Publish a visualization_msgs Marker of a custom type. Allows reuse of the ros publisher.
bool publishPath (const std::vector< geometry_msgs::Point > &path, const rviz_colors color=RED, const rviz_scales scale=REGULAR, const std::string &ns="Path")
 Publish a marker of a series of connected lines to rviz.
bool publishPolygon (const geometry_msgs::Polygon &polygon, const rviz_colors color=RED, const rviz_scales scale=REGULAR, const std::string &ns="Polygon")
 Publish a marker of a polygon to Rviz.
bool publishRectangle (const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, const rviz_colors color=BLUE)
 Publish a marker of rectangle to rviz.
bool publishRemoveAllCollisionObjects ()
bool publishRobotState (const robot_state::RobotState &robot_state)
 Publish a complete robot state to Rviz To use, add a RobotState marker to Rviz and subscribe to the DISPLAY_ROBOT_STATE_TOPIC, above.
bool publishRobotState (const robot_state::RobotStatePtr &robot_state)
bool publishRobotState (const trajectory_msgs::JointTrajectoryPoint &trajectory_pt, const std::string &group_name)
 Publish a MoveIt robot state to a topic that the Rviz "RobotState" display can show.
bool publishSphere (const Eigen::Affine3d &pose, const rviz_colors color=BLUE, const rviz_scales scale=REGULAR, const std::string &ns="Sphere")
 Publish a marker of a sphere to rviz.
bool publishSphere (const Eigen::Vector3d &point, const rviz_colors color=BLUE, const rviz_scales scale=REGULAR, const std::string &ns="Sphere")
bool publishSphere (const geometry_msgs::Point &point, const rviz_colors color=BLUE, const rviz_scales scale=REGULAR, const std::string &ns="Sphere")
bool publishSphere (const geometry_msgs::Pose &pose, const rviz_colors color=BLUE, const rviz_scales scale=REGULAR, const std::string &ns="Sphere")
bool publishSphere (const geometry_msgs::Pose &pose, const rviz_colors color, const double scale, const std::string &ns="Sphere")
bool publishSphere (const geometry_msgs::Pose &pose, const rviz_colors color, const geometry_msgs::Vector3 scale, const std::string &ns="Sphere")
bool publishSpheres (const std::vector< geometry_msgs::Point > &points, const rviz_colors color=BLUE, const rviz_scales scale=REGULAR, const std::string &ns="Spheres")
 Publish a marker of a series of spheres to rviz.
bool publishTest ()
 Run a simple test of all visual_tool's features.
bool publishText (const geometry_msgs::Pose &pose, const std::string &text, const rviz_colors &color=WHITE, const rviz_scales scale=REGULAR)
 Publish a marker of a text to Rviz.
bool publishText (const geometry_msgs::Pose &pose, const std::string &text, const rviz_colors &color, const geometry_msgs::Vector3 scale, bool static_id=true)
bool publishTrajectoryPath (const robot_trajectory::RobotTrajectory &trajectory, bool blocking=false)
 Animate trajectory in rviz.
bool publishTrajectoryPath (const moveit_msgs::RobotTrajectory &trajectory_msg, bool blocking=false)
bool publishTrajectoryPoint (const trajectory_msgs::JointTrajectoryPoint &trajectory_pt, const std::string &group_name, double display_time=0.1)
 Move a joint group in MoveIt for visualization make sure you have already set the planning group name this assumes the trajectory_pt position is the size of the number of joints in the planning group This will be displayed in the Planned Path section of the MoveIt Rviz plugin.
MOVEIT_DEPRECATED bool removeAllCollisionObjects ()
 Remove all collision objects that this class has added to the MoveIt! planning scene Communicates to a remote move_group node through a ROS message.
bool removeAllCollisionObjectsPS ()
 Remove all collision objects that this class has added to the MoveIt! planning scene Communicates directly to a planning scene monitor e.g. if this is the move_group node.
void resetMarkerCounts ()
 Reset the id's of all published markers so that they overwrite themselves in the future NOTE you may prefer deleteAllMarkers()
void setAlpha (double alpha)
 Change the transparency of all markers published.
void setBaseFrame (const std::string &base_frame)
 Change the global base frame Note: this might reset all your current markers.
void setFloorToBaseHeight (double floor_to_base_height)
 Allows an offset between base link and floor where objects are built. Default is zero.
void setGlobalScale (double global_scale)
 Setter for the global scale used for changing size of all markers.
void setGraspPoseToEEFPose (geometry_msgs::Pose grasp_pose_to_eef_pose)
 Convert generic grasp pose to this end effector's frame of reference.
void setLifetime (double lifetime)
 Set the lifetime of markers published to rviz.
void setMuted (bool muted)
 Set this class to not actually publish anything to Rviz.
void setPlanningSceneMonitor (planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor)
 Allow a pre-configured planning scene monitor to be set for publishing collision objects, etc.
 VisualTools (const std::string &base_frame, const std::string &marker_topic, planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor)
 Constructor.
 VisualTools (const std::string &base_frame, const std::string &marker_topic=RVIZ_MARKER_TOPIC, robot_model::RobotModelConstPtr robot_model=robot_model::RobotModelConstPtr())
 Constructor.
 ~VisualTools ()
 Deconstructor.

Static Public Member Functions

static Eigen::Vector3d convertPoint (const geometry_msgs::Point &point)
 Convert a geometry_msg point to an Eigen point Note: NOT memory efficient.
static Eigen::Vector3d convertPoint32 (const geometry_msgs::Point32 &point)
 Convert a geometry_msg point to an Eigen point Note: NOT memory efficient.
static geometry_msgs::Point32 convertPoint32 (const Eigen::Vector3d &point)
 Convert an Eigen point to a 32 bit geometry_msg point Note: NOT memory efficient.
static Eigen::Affine3d convertPoint32ToPose (const geometry_msgs::Point32 &point)
 Convert a geometry_msg point (32bit) to an Eigen pose Note: NOT memory efficient.
static geometry_msgs::Pose convertPointToPose (const geometry_msgs::Point &point)
static geometry_msgs::Pose convertPose (const Eigen::Affine3d &pose)
 Convert an Eigen pose to a geometry_msg pose Note: NOT memory efficient.
static Eigen::Affine3d convertPose (const geometry_msgs::Pose &pose)
 Convert a geometry_msg pose to an Eigen pose Note: NOT memory efficient.
static geometry_msgs::Point convertPoseToPoint (const Eigen::Affine3d &pose)
 Convert an Eigen pose to a geometry_msg point Note: NOT memory efficient.
static double dRand (double dMin, double dMax)
 Get random between min and max.
static float fRand (float dMin, float dMax)
static int iRand (int dMin, int dMax)

Protected Attributes

double alpha_
visualization_msgs::Marker arrow_marker_
std::string base_frame_
visualization_msgs::Marker block_marker_
visualization_msgs::Marker cylinder_marker_
moveit_msgs::DisplayRobotState display_robot_msg_
visualization_msgs::MarkerArray ee_marker_array_
double floor_to_base_height_
double global_scale_
geometry_msgs::Pose grasp_pose_to_eef_pose_
visualization_msgs::Marker line_marker_
ros::Duration marker_lifetime_
std::vector< geometry_msgs::Posemarker_poses_
std::string marker_topic_
bool muted_
ros::NodeHandle nh_
visualization_msgs::Marker path_marker_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
ros::Publisher pub_attach_collision_obj_
ros::Publisher pub_collision_obj_
ros::Publisher pub_display_path_
ros::Publisher pub_planning_scene_diff_
ros::Publisher pub_robot_state_
ros::Publisher pub_rviz_marker_
visualization_msgs::Marker rectangle_marker_
visualization_msgs::Marker reset_marker_
robot_model_loader::RobotModelLoaderPtr rm_loader_
robot_state::RobotModelConstPtr robot_model_
robot_state::RobotStatePtr shared_robot_state_
visualization_msgs::Marker sphere_marker_
visualization_msgs::Marker spheres_marker_
visualization_msgs::Marker text_marker_
tf::Pose tf_root_to_link_

Private Member Functions

planning_scene_monitor::PlanningSceneMonitorPtr getPlanningSceneMonitor ()
 Get the planning scene monitor that this class is using.
void initialize ()
 Shared function for initilization by constructors.

Detailed Description

Definition at line 100 of file visual_tools.h.


Constructor & Destructor Documentation

moveit_visual_tools::VisualTools::VisualTools ( const std::string &  base_frame,
const std::string &  marker_topic,
planning_scene_monitor::PlanningSceneMonitorPtr  planning_scene_monitor 
)

Constructor.

Parameters:
base_frame- common base for all visualization markers, usually "/world" or "/odom"
marker_topic- rostopic to publish markers to - your Rviz display should match
planning_scene_monitor- optionally pass in a pre-loaded planning scene monitor to avoid having to re-load the URDF, kinematic solvers, etc

Definition at line 58 of file visual_tools.cpp.

moveit_visual_tools::VisualTools::VisualTools ( const std::string &  base_frame,
const std::string &  marker_topic = RVIZ_MARKER_TOPIC,
robot_model::RobotModelConstPtr  robot_model = robot_model::RobotModelConstPtr() 
)

Constructor.

Parameters:
base_frame- common base for all visualization markers, usually "/world" or "/odom"
marker_topic- rostopic to publish markers to - your Rviz display should match
robot_model- load robot model pointer so that we don't have do re-parse it here

Definition at line 69 of file visual_tools.cpp.

Deconstructor.

Definition at line 191 of file visual_tools.h.


Member Function Documentation

bool moveit_visual_tools::VisualTools::attachCO ( const std::string &  name,
const std::string &  ee_parent_link 
)

Attach a collision object from the planning scene.

Parameters:
Nameof object
\returntrue on sucess

Definition at line 1498 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::cleanupACO ( const std::string &  name)

Remove an active collision object from the planning scene.

Parameters:
Nameof object
Returns:
true on sucess

Definition at line 1480 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::cleanupCO ( std::string  name)

Remove a collision object from the planning scene.

Parameters:
Nameof object
Returns:
true on sucess

Definition at line 1465 of file visual_tools.cpp.

Eigen::Vector3d moveit_visual_tools::VisualTools::convertPoint ( const geometry_msgs::Point point) [static]

Convert a geometry_msg point to an Eigen point Note: NOT memory efficient.

Parameters:
point
Returns:
converted pose

Definition at line 2017 of file visual_tools.cpp.

Eigen::Vector3d moveit_visual_tools::VisualTools::convertPoint32 ( const geometry_msgs::Point32 &  point) [static]

Convert a geometry_msg point to an Eigen point Note: NOT memory efficient.

Parameters:
point
Returns:
converted pose

Definition at line 2026 of file visual_tools.cpp.

geometry_msgs::Point32 moveit_visual_tools::VisualTools::convertPoint32 ( const Eigen::Vector3d &  point) [static]

Convert an Eigen point to a 32 bit geometry_msg point Note: NOT memory efficient.

Parameters:
point
Returns:
converted pose

Definition at line 2035 of file visual_tools.cpp.

Eigen::Affine3d moveit_visual_tools::VisualTools::convertPoint32ToPose ( const geometry_msgs::Point32 &  point) [static]

Convert a geometry_msg point (32bit) to an Eigen pose Note: NOT memory efficient.

Parameters:
pose
Returns:
converted point with default rotation matrix

Definition at line 1994 of file visual_tools.cpp.

Parameters:
input- description
input- description
Returns:

Definition at line 2003 of file visual_tools.cpp.

geometry_msgs::Pose moveit_visual_tools::VisualTools::convertPose ( const Eigen::Affine3d &  pose) [static]

Convert an Eigen pose to a geometry_msg pose Note: NOT memory efficient.

Parameters:
pose
Returns:
converted pose

Definition at line 1980 of file visual_tools.cpp.

Eigen::Affine3d moveit_visual_tools::VisualTools::convertPose ( const geometry_msgs::Pose pose) [static]

Convert a geometry_msg pose to an Eigen pose Note: NOT memory efficient.

Parameters:
pose
Returns:
converted pose

Definition at line 1987 of file visual_tools.cpp.

static geometry_msgs::Point moveit_visual_tools::VisualTools::convertPoseToPoint ( const Eigen::Affine3d &  pose) [static]

Convert an Eigen pose to a geometry_msg point Note: NOT memory efficient.

Parameters:
pose
Returns:
converted point with orientation discarded

Tell Rviz to clear all markers on a particular display. Note: only works on ROS Indigo and newer.

Definition at line 91 of file visual_tools.cpp.

double moveit_visual_tools::VisualTools::dRand ( double  dMin,
double  dMax 
) [static]

Get random between min and max.

Definition at line 2060 of file visual_tools.cpp.

float moveit_visual_tools::VisualTools::fRand ( float  dMin,
float  dMax 
) [static]

Definition at line 2066 of file visual_tools.cpp.

Create a random pose.

Parameters:
Poseto fill in

Definition at line 2044 of file visual_tools.cpp.

const std::string moveit_visual_tools::VisualTools::getBaseFrame ( ) [inline]

Get the base frame.

Returns:
name of base frame

Definition at line 348 of file visual_tools.h.

Definition at line 352 of file visual_tools.h.

Eigen::Vector3d moveit_visual_tools::VisualTools::getCenterPoint ( Eigen::Vector3d  a,
Eigen::Vector3d  b 
)

Find the center between to points.

Parameters:
pointa - x,y,z in space of a point
pointb - x,y,z in space of a point
Returns:
center point

Definition at line 722 of file visual_tools.cpp.

void moveit_visual_tools::VisualTools::getCollisionWallMsg ( double  x,
double  y,
double  angle,
double  width,
const std::string  name,
moveit_msgs::CollisionObject &  collision_obj 
)

Helper for publishCollisionWall.

Definition at line 1711 of file visual_tools.cpp.

std_msgs::ColorRGBA moveit_visual_tools::VisualTools::getColor ( const rviz_colors color)

Get the RGB value of standard colors.

Parameters:
color- an enum pre-defined name of a color
Returns:
the RGB message equivalent

Definition at line 558 of file visual_tools.cpp.

Getter for the global scale used for changing size of all markers.

Definition at line 371 of file visual_tools.h.

Get the planning scene monitor that this class is using.

Returns:
a ptr to a planning scene

Definition at line 691 of file visual_tools.cpp.

Get a random color from the list of hardcoded enum color types.

Returns:
Random color from rviz_colors

Definition at line 541 of file visual_tools.cpp.

geometry_msgs::Vector3 moveit_visual_tools::VisualTools::getScale ( const rviz_scales scale,
bool  arrow_scale = false,
double  marker_scale = 1.0 
)

Get the rviz marker scale of standard sizes.

Parameters:
scale- an enum pre-defined name of a size
arrow_scale- they do not have an even scaling, compensate
marker_scale- amount to scale the scale for accounting for different types of markers
Returns:
vector of 3 scales

Definition at line 635 of file visual_tools.cpp.

Eigen::Affine3d moveit_visual_tools::VisualTools::getVectorBetweenPoints ( Eigen::Vector3d  a,
Eigen::Vector3d  b 
)

Create a vector that points from point a to point b.

Parameters:
pointa - x,y,z in space of a point
pointb - x,y,z in space of a point
Returns:
vector from a to b

Definition at line 731 of file visual_tools.cpp.

Fake removing a Robot State display in Rviz by simply moving it very far away.

Returns:
true on success

Definition at line 1955 of file visual_tools.cpp.

Shared function for initilization by constructors.

Definition at line 80 of file visual_tools.cpp.

int moveit_visual_tools::VisualTools::iRand ( int  dMin,
int  dMax 
) [static]

Definition at line 2072 of file visual_tools.cpp.

Return if we are in verbose mode.

Definition at line 256 of file visual_tools.h.

Definition at line 461 of file visual_tools.cpp.

Definition at line 447 of file visual_tools.cpp.

Load a planning scene to a planning_scene_monitor from file.

Parameters:
path- path to planning scene, e.g. as exported from Rviz Plugin
planningscene monitor that is already setup
Returns:
true on success

Definition at line 1804 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::loadEEMarker ( const std::string &  ee_group_name,
const std::string &  planning_group 
)

Call this once at begining to load the robot marker.

Parameters:
\param
Returns:
true if it is successful

Definition at line 362 of file visual_tools.cpp.

Load publishers as needed.

Definition at line 433 of file visual_tools.cpp.

Definition at line 475 of file visual_tools.cpp.

Load a planning scene monitor if one was not passed into the constructor.

Returns:
true if successful in loading

Definition at line 256 of file visual_tools.cpp.

Caches the meshes and geometry of a robot. NOTE: perhaps not maintained...

Returns:
true if successful in loading

Definition at line 322 of file visual_tools.cpp.

Definition at line 503 of file visual_tools.cpp.

Pre-load rviz markers for better efficiency.

Returns:
converted pose *
true on sucess

Definition at line 111 of file visual_tools.cpp.

Load robot state only as needed.

Returns:
true if successful in loading

Definition at line 702 of file visual_tools.cpp.

Definition at line 489 of file visual_tools.cpp.

Debug variables to console.

Definition at line 2078 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::processCollisionObjectMsg ( moveit_msgs::CollisionObject  msg)

Skip a ROS message call by sending directly to planning scene monitor.

Parameters:
collisionobject message
Returns:
true on success

Definition at line 308 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishAnimatedGrasp ( const moveit_msgs::Grasp &  grasp,
const std::string &  ee_parent_link,
double  animate_speed 
)

Animate a single grasp in its movement direction.

Parameters:
grasp
ee_parent_link- end effector's attachment link
animate_speed- how fast the gripper approach is animated
Returns:
true on sucess

Definition at line 1302 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishAnimatedGrasps ( const std::vector< moveit_msgs::Grasp > &  possible_grasps,
const std::string &  ee_parent_link,
double  animate_speed = 0.01 
)

Display an animated vector of grasps including its approach movement in Rviz.

Parameters:
possible_grasps- a set of grasp positions to visualize
ee_parent_link- end effector's attachment link
animate_speed- how fast the gripper approach is animated, optional

Definition at line 1276 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishArrow ( const Eigen::Affine3d &  pose,
const rviz_colors  color = BLUE,
const rviz_scales  scale = REGULAR 
)

Publish a marker of an arrow to rviz.

Parameters:
pose- the location to publish the marker with respect to the base frame
color- an enum pre-defined name of a color
scale- an enum pre-defined name of a size
Returns:
true on success

Definition at line 916 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishArrow ( const geometry_msgs::Pose pose,
const rviz_colors  color = BLUE,
const rviz_scales  scale = REGULAR 
)

Definition at line 921 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishBlock ( const geometry_msgs::Pose pose,
const rviz_colors  color = BLUE,
const double &  block_size = 0.1 
)

Publish a marker of a block to Rviz.

Parameters:
pose- the location to publish the marker with respect to the base frame
color- an enum pre-defined name of a color
size- height=width=depth=size
Returns:
true on success

Definition at line 941 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishCollisionBlock ( geometry_msgs::Pose  block_pose,
std::string  block_name,
double  block_size 
)

Create a MoveIt Collision block at the given pose.

Parameters:
pose- location of center of block
name- semantic name of MoveIt collision object
size- height=width=depth=size
Returns:
true on sucess

Definition at line 1556 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishCollisionCylinder ( geometry_msgs::Point  a,
geometry_msgs::Point  b,
std::string  object_name,
double  radius 
)

Create a MoveIt Collision cylinder between two points.

Parameters:
pointa - x,y,z in space of a point
pointb - x,y,z in space of a point
name- semantic name of MoveIt collision object
radius- size of cylinder
Returns:
true on sucess

Definition at line 1582 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishCollisionCylinder ( Eigen::Vector3d  a,
Eigen::Vector3d  b,
std::string  object_name,
double  radius 
)

Definition at line 1587 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishCollisionCylinder ( Eigen::Affine3d  object_pose,
std::string  object_name,
double  radius,
double  height 
)

Create a MoveIt Collision cylinder with a center point pose.

Parameters:
pose- vector pointing along axis of cylinder
name- semantic name of MoveIt collision object
radius- size of cylinder
height- size of cylinder
Returns:
true on sucess

Definition at line 1607 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishCollisionCylinder ( geometry_msgs::Pose  object_pose,
std::string  object_name,
double  radius,
double  height 
)

Definition at line 1612 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishCollisionFloor ( double  z,
std::string  plane_name 
)

Make the floor a collision object.

Parameters:
zlocation of floor
nameof floor
Returns:
true on success

Definition at line 1517 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishCollisionGraph ( const graph_msgs::GeometryGraph &  graph,
const std::string &  object_name,
double  radius 
)

Publish a connected birectional graph.

Parameters:
graphof nodes and edges
nameof collision object
Returns:
true on sucess

Definition at line 1637 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishCollisionTable ( double  x,
double  y,
double  angle,
double  width,
double  height,
double  depth,
const std::string  name 
)

Publish a typical room table.

Parameters:
x
y
angle
width
height
depth
name
Returns:
true on sucess

Definition at line 1763 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishCollisionWall ( double  x,
double  y,
double  angle,
double  width,
const std::string  name 
)

Publish a typical room wall.

Parameters:
x
y
angle
width
name
Returns:
true on sucess

Definition at line 1751 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishCylinder ( const geometry_msgs::Pose pose,
const rviz_colors  color = BLUE,
double  height = 0.1,
double  radius = 0.1 
)

Publish a marker of a cylinder to Rviz.

Parameters:
pose- the location to publish the marker with respect to the base frame
color- an enum pre-defined name of a color
height- geometry of cylinder
radius- geometry of cylinder
Returns:
true on success

Definition at line 969 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishEEMarkers ( const geometry_msgs::Pose pose,
const rviz_colors color = WHITE,
const std::string &  ns = "end_effector" 
)

Publish an end effector to rviz.

Parameters:
pose- the location to publish the marker with respect to the base frame
Returns:
true on success

Definition at line 776 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishGraph ( const graph_msgs::GeometryGraph &  graph,
const rviz_colors  color,
double  radius 
)

Publish a graph.

Parameters:
graphof nodes and edges
color- an enum pre-defined name of a color
radius- width of cylinders
Returns:
true on success

Definition at line 997 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishGrasps ( const std::vector< moveit_msgs::Grasp > &  possible_grasps,
const std::string &  ee_parent_link 
)

Show grasps generated from moveit_simple_grasps or other MoveIt Grasp message sources.

Parameters:
possible_grasps- a set of grasp positions to visualize
ee_parent_link- end effector's attachment link

Definition at line 1248 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishIKSolutions ( const std::vector< trajectory_msgs::JointTrajectoryPoint > &  ik_solutions,
const std::string &  planning_group,
double  display_time = 0.4 
)

Display an vector of inverse kinematic solutions for the IK service in Rviz Note: this is published to the 'Planned Path' section of the 'MotionPlanning' display in Rviz.

Parameters:
ik_solutions- a set of corresponding arm positions to achieve each grasp
display_time- amount of time to sleep between sending trajectories, optional

Definition at line 1368 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishLine ( const geometry_msgs::Point point1,
const geometry_msgs::Point point2,
const rviz_colors  color = BLUE,
const rviz_scales  scale = REGULAR 
)

Publish a marker of line to rviz.

Parameters:
point1- x,y,z of start of line
point2- x,y,z of end of line
color- an enum pre-defined name of a color
scale- an enum pre-defined name of a size
Returns:
true on success

Definition at line 1081 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishMarker ( const visualization_msgs::Marker &  marker)

Publish a visualization_msgs Marker of a custom type. Allows reuse of the ros publisher.

Parameters:
marker- a pre-made marker ready to be published
Returns:
true on success

Definition at line 1236 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishPath ( const std::vector< geometry_msgs::Point > &  path,
const rviz_colors  color = RED,
const rviz_scales  scale = REGULAR,
const std::string &  ns = "Path" 
)

Publish a marker of a series of connected lines to rviz.

Parameters:
path- a series of points to connect with lines
color- an enum pre-defined name of a color
scale- an enum pre-defined name of a size
ns- namespace of marker
Returns:
true on success

Definition at line 1105 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishPolygon ( const geometry_msgs::Polygon &  polygon,
const rviz_colors  color = RED,
const rviz_scales  scale = REGULAR,
const std::string &  ns = "Polygon" 
)

Publish a marker of a polygon to Rviz.

Parameters:
polygon- a series of points to connect with lines
color- an enum pre-defined name of a color
scale- an enum pre-defined name of a size
ns- namespace of marker
Returns:
true on success

Definition at line 1146 of file visual_tools.cpp.

Publish a marker of rectangle to rviz.

Parameters:
point1- x,y,z top corner location of box
point2- x,y,z bottom opposite corner location of box
color- an enum pre-defined name of a color
Returns:
true on success

Definition at line 1051 of file visual_tools.cpp.

Definition at line 1432 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishRobotState ( const robot_state::RobotState &  robot_state)

Publish a complete robot state to Rviz To use, add a RobotState marker to Rviz and subscribe to the DISPLAY_ROBOT_STATE_TOPIC, above.

Parameters:
robot_state

Definition at line 1928 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishRobotState ( const robot_state::RobotStatePtr &  robot_state)

Definition at line 1923 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishRobotState ( const trajectory_msgs::JointTrajectoryPoint &  trajectory_pt,
const std::string &  group_name 
)

Publish a MoveIt robot state to a topic that the Rviz "RobotState" display can show.

Parameters:
robot_state
Returns:
true on success

Definition at line 1939 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishSphere ( const Eigen::Affine3d &  pose,
const rviz_colors  color = BLUE,
const rviz_scales  scale = REGULAR,
const std::string &  ns = "Sphere" 
)

Publish a marker of a sphere to rviz.

Parameters:
pose- the location to publish the sphere with respect to the base frame
color- an enum pre-defined name of a color
scale- an enum pre-defined name of a size
Returns:
true on success

Definition at line 859 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishSphere ( const Eigen::Vector3d &  point,
const rviz_colors  color = BLUE,
const rviz_scales  scale = REGULAR,
const std::string &  ns = "Sphere" 
)

Definition at line 864 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishSphere ( const geometry_msgs::Point point,
const rviz_colors  color = BLUE,
const rviz_scales  scale = REGULAR,
const std::string &  ns = "Sphere" 
)

Definition at line 871 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishSphere ( const geometry_msgs::Pose pose,
const rviz_colors  color = BLUE,
const rviz_scales  scale = REGULAR,
const std::string &  ns = "Sphere" 
)

Definition at line 878 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishSphere ( const geometry_msgs::Pose pose,
const rviz_colors  color,
const double  scale,
const std::string &  ns = "Sphere" 
)

Definition at line 883 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishSphere ( const geometry_msgs::Pose pose,
const rviz_colors  color,
const geometry_msgs::Vector3  scale,
const std::string &  ns = "Sphere" 
)

Definition at line 891 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishSpheres ( const std::vector< geometry_msgs::Point > &  points,
const rviz_colors  color = BLUE,
const rviz_scales  scale = REGULAR,
const std::string &  ns = "Spheres" 
)

Publish a marker of a series of spheres to rviz.

Parameters:
spheres- where to publish them
color- an enum pre-defined name of a color
scale- an enum pre-defined name of a size
ns- namespace of marker
Returns:
true on success

Definition at line 1165 of file visual_tools.cpp.

Run a simple test of all visual_tool's features.

Returns:
true on success

Definition at line 1967 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishText ( const geometry_msgs::Pose pose,
const std::string &  text,
const rviz_colors color = WHITE,
const rviz_scales  scale = REGULAR 
)

Publish a marker of a text to Rviz.

Parameters:
pose- the location to publish the marker with respect to the base frame
text- what to display
color- an enum pre-defined name of a colo
scale- an enum pre-defined name of a size
Returns:
true on success

Definition at line 1198 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishText ( const geometry_msgs::Pose pose,
const std::string &  text,
const rviz_colors color,
const geometry_msgs::Vector3  scale,
bool  static_id = true 
)

Definition at line 1203 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishTrajectoryPath ( const robot_trajectory::RobotTrajectory trajectory,
bool  blocking = false 
)

Animate trajectory in rviz.

Parameters:
trajectory_msgthe actual plan
blockingwhether we need to wait for the animation to complete
Returns:
true on success

Definition at line 1858 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishTrajectoryPath ( const moveit_msgs::RobotTrajectory &  trajectory_msg,
bool  blocking = false 
)

Definition at line 1880 of file visual_tools.cpp.

bool moveit_visual_tools::VisualTools::publishTrajectoryPoint ( const trajectory_msgs::JointTrajectoryPoint &  trajectory_pt,
const std::string &  group_name,
double  display_time = 0.1 
)

Move a joint group in MoveIt for visualization make sure you have already set the planning group name this assumes the trajectory_pt position is the size of the number of joints in the planning group This will be displayed in the Planned Path section of the MoveIt Rviz plugin.

Parameters:
trajectory_pts- a single joint configuration
group_name- the MoveIt planning group the trajectory applies to
display_time- amount of time for the trajectory to "execute"
Returns:
true on success

Definition at line 1828 of file visual_tools.cpp.

Remove all collision objects that this class has added to the MoveIt! planning scene Communicates to a remote move_group node through a ROS message.

Returns:
true on sucess

Definition at line 558 of file visual_tools.h.

Remove all collision objects that this class has added to the MoveIt! planning scene Communicates directly to a planning scene monitor e.g. if this is the move_group node.

Parameters:
thescene to directly clear the collision objects from
Returns:
true on sucess

Definition at line 1455 of file visual_tools.cpp.

Reset the id's of all published markers so that they overwrite themselves in the future NOTE you may prefer deleteAllMarkers()

Definition at line 98 of file visual_tools.cpp.

void moveit_visual_tools::VisualTools::setAlpha ( double  alpha) [inline]

Change the transparency of all markers published.

Parameters:
alpha- value 0 - 1 where 0 is invisible

Definition at line 286 of file visual_tools.h.

void moveit_visual_tools::VisualTools::setBaseFrame ( const std::string &  base_frame) [inline]

Change the global base frame Note: this might reset all your current markers.

Parameters:
nameof frame

Definition at line 362 of file visual_tools.h.

void moveit_visual_tools::VisualTools::setFloorToBaseHeight ( double  floor_to_base_height)

Allows an offset between base link and floor where objects are built. Default is zero.

Parameters:
floor_to_base_height- the offset

Definition at line 517 of file visual_tools.cpp.

void moveit_visual_tools::VisualTools::setGlobalScale ( double  global_scale) [inline]

Setter for the global scale used for changing size of all markers.

Definition at line 379 of file visual_tools.h.

Convert generic grasp pose to this end effector's frame of reference.

Parameters:
pose- the transform

Definition at line 522 of file visual_tools.cpp.

Set the lifetime of markers published to rviz.

Parameters:
lifetimeseconds of how long to show markers. 0 for inifinity

Definition at line 527 of file visual_tools.cpp.

void moveit_visual_tools::VisualTools::setMuted ( bool  muted) [inline]

Set this class to not actually publish anything to Rviz.

Parameters:
mutedtrue if verbose

Definition at line 265 of file visual_tools.h.

Allow a pre-configured planning scene monitor to be set for publishing collision objects, etc.

Parameters:
apointer to a load planning scen

Definition at line 295 of file visual_tools.h.


Member Data Documentation

Definition at line 137 of file visual_tools.h.

visualization_msgs::Marker moveit_visual_tools::VisualTools::arrow_marker_ [protected]

Definition at line 141 of file visual_tools.h.

Definition at line 121 of file visual_tools.h.

visualization_msgs::Marker moveit_visual_tools::VisualTools::block_marker_ [protected]

Definition at line 143 of file visual_tools.h.

visualization_msgs::Marker moveit_visual_tools::VisualTools::cylinder_marker_ [protected]

Definition at line 144 of file visual_tools.h.

moveit_msgs::DisplayRobotState moveit_visual_tools::VisualTools::display_robot_msg_ [protected]

Definition at line 153 of file visual_tools.h.

visualization_msgs::MarkerArray moveit_visual_tools::VisualTools::ee_marker_array_ [protected]

Definition at line 130 of file visual_tools.h.

Definition at line 124 of file visual_tools.h.

Definition at line 138 of file visual_tools.h.

Definition at line 132 of file visual_tools.h.

visualization_msgs::Marker moveit_visual_tools::VisualTools::line_marker_ [protected]

Definition at line 147 of file visual_tools.h.

Definition at line 127 of file visual_tools.h.

Definition at line 133 of file visual_tools.h.

Definition at line 120 of file visual_tools.h.

Definition at line 136 of file visual_tools.h.

Definition at line 105 of file visual_tools.h.

visualization_msgs::Marker moveit_visual_tools::VisualTools::path_marker_ [protected]

Definition at line 148 of file visual_tools.h.

Definition at line 116 of file visual_tools.h.

Definition at line 110 of file visual_tools.h.

Definition at line 109 of file visual_tools.h.

Definition at line 111 of file visual_tools.h.

Definition at line 112 of file visual_tools.h.

Definition at line 113 of file visual_tools.h.

Definition at line 108 of file visual_tools.h.

visualization_msgs::Marker moveit_visual_tools::VisualTools::rectangle_marker_ [protected]

Definition at line 146 of file visual_tools.h.

visualization_msgs::Marker moveit_visual_tools::VisualTools::reset_marker_ [protected]

Definition at line 150 of file visual_tools.h.

Definition at line 117 of file visual_tools.h.

robot_state::RobotModelConstPtr moveit_visual_tools::VisualTools::robot_model_ [protected]

Definition at line 157 of file visual_tools.h.

robot_state::RobotStatePtr moveit_visual_tools::VisualTools::shared_robot_state_ [protected]

Definition at line 156 of file visual_tools.h.

visualization_msgs::Marker moveit_visual_tools::VisualTools::sphere_marker_ [protected]

Definition at line 142 of file visual_tools.h.

visualization_msgs::Marker moveit_visual_tools::VisualTools::spheres_marker_ [protected]

Definition at line 149 of file visual_tools.h.

visualization_msgs::Marker moveit_visual_tools::VisualTools::text_marker_ [protected]

Definition at line 145 of file visual_tools.h.

Definition at line 131 of file visual_tools.h.


The documentation for this class was generated from the following files:


moveit_visual_tools
Author(s): Dave Coleman
autogenerated on Wed Aug 26 2015 14:54:49