Public Member Functions | Static Public Member Functions | Protected Attributes | Static Private Member Functions | List of all members
moveit_visual_tools::MoveItVisualTools Class Reference

#include <moveit_visual_tools.h>

Inheritance diagram for moveit_visual_tools::MoveItVisualTools:
Inheritance graph
[legend]

Public Member Functions

bool attachCO (const std::string &name, const std::string &ee_parent_link)
 Attach a collision object from the planning scene. More...
 
bool checkAndPublishCollision (const moveit::core::RobotState &robot_state, const planning_scene::PlanningScene *planning_scene, const rviz_visual_tools::colors &highlight_link_color=rviz_visual_tools::RED, const rviz_visual_tools::colors &contact_point_color=rviz_visual_tools::PURPLE)
 Check if the robot state is in collision inside the planning scene and visualize the result. If the state is not colliding only the robot state is published. If there is a collision the colliding links are ghlighted and the contact points are visualized with markers. More...
 
bool cleanupACO (const std::string &name)
 Remove an active collision object from the planning scene. More...
 
bool cleanupCO (const std::string &name)
 Remove a collision object from the planning scene. More...
 
void disableRobotStateRootOffet ()
 Turn off the root offset feature. More...
 
void enableRobotStateRootOffet (const Eigen::Isometry3d &offset)
 All published robot states will have their virtual joint moved by offset. More...
 
void getCollisionWallMsg (double x, double y, double z, double angle, double width, double height, const std::string &name, moveit_msgs::CollisionObject &collision_obj)
 Helper for publishCollisionWall. More...
 
planning_scene_monitor::PlanningSceneMonitorPtr getPlanningSceneMonitor ()
 Get the planning scene monitor that this class is using. More...
 
moveit::core::RobotModelConstPtr getRobotModel ()
 Get a pointer to the robot model. More...
 
moveit::core::RobotStatePtr & getRootRobotState ()
 Allow robot state to be altered. More...
 
moveit::core::RobotStatePtr & getSharedRobotState ()
 Allow robot state to be altered. More...
 
bool hideRobot ()
 Hide robot in RobotState display in Rviz. More...
 
bool loadCollisionSceneFromFile (const std::string &path)
 Load a planning scene to a planning_scene_monitor from file. More...
 
bool loadCollisionSceneFromFile (const std::string &path, const Eigen::Isometry3d &offset)
 
bool loadEEMarker (const moveit::core::JointModelGroup *ee_jmg, const std::vector< double > &ee_joint_pos={})
 Call this once at begining to load the end effector markers and then whenever a joint changes. More...
 
bool loadPlanningSceneMonitor ()
 Load a planning scene monitor if one was not passed into the constructor. More...
 
void loadRobotStatePub (const std::string &robot_state_topic="", bool blocking=true)
 
bool loadSharedRobotState ()
 Load robot state only as needed. More...
 
void loadTrajectoryPub (const std::string &display_planned_path_topic=DISPLAY_PLANNED_PATH_TOPIC, bool blocking=true)
 Load publishers as needed. More...
 
bool moveCollisionObject (const Eigen::Isometry3d &pose, const std::string &name, const rviz_visual_tools::colors &color)
 Move an already published collision object to a new location in space. More...
 
bool moveCollisionObject (const geometry_msgs::Pose &pose, const std::string &name, const rviz_visual_tools::colors &color)
 
 MoveItVisualTools ()
 Constructor. More...
 
 MoveItVisualTools (const std::string &base_frame, const std::string &marker_topic, planning_scene_monitor::PlanningSceneMonitorPtr psm)
 Constructor. More...
 
 MoveItVisualTools (const std::string &base_frame, const std::string &marker_topic=rviz_visual_tools::RVIZ_MARKER_TOPIC, moveit::core::RobotModelConstPtr robot_model=moveit::core::RobotModelConstPtr())
 Constructor. More...
 
bool processAttachedCollisionObjectMsg (const moveit_msgs::AttachedCollisionObject &msg)
 Skip a ROS message call by sending directly to planning scene monitor. More...
 
bool processCollisionObjectMsg (const moveit_msgs::CollisionObject &msg, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN)
 Skip a ROS message call by sending directly to planning scene monitor. More...
 
bool publishAnimatedGrasp (const moveit_msgs::Grasp &grasp, const moveit::core::JointModelGroup *ee_jmg, double animate_speed)
 Animate a single grasp in its movement direction Note this function calls publish() automatically in order to achieve animations. More...
 
bool publishAnimatedGrasps (const std::vector< moveit_msgs::Grasp > &possible_grasps, const moveit::core::JointModelGroup *ee_jmg, double animate_speed=0.01)
 Display an animated vector of grasps including its approach movement in Rviz Note this function calls publish() automatically in order to achieve animations. More...
 
bool publishCollisionBlock (const geometry_msgs::Pose &block_pose, const std::string &block_name="block", double block_size=0.1, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN)
 Create a MoveIt Collision block at the given pose. More...
 
bool publishCollisionCuboid (const Eigen::Isometry3d &pose, const Eigen::Vector3d &size, const std::string &name, const rviz_visual_tools::colors &color)
 Create a MoveIt collision rectangular cuboid at the given pose. More...
 
bool publishCollisionCuboid (const Eigen::Isometry3d &pose, double width, double depth, double height, const std::string &name, const rviz_visual_tools::colors &color)
 Create a MoveIt collision rectangular cuboid at the given pose. More...
 
bool publishCollisionCuboid (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const std::string &name, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN)
 Create a MoveIt collision rectangular cuboid at the given pose. More...
 
bool publishCollisionCuboid (const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, const std::string &name, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN)
 
bool publishCollisionCuboid (const geometry_msgs::Pose &pose, const geometry_msgs::Vector3 &size, const std::string &name, const rviz_visual_tools::colors &color)
 
bool publishCollisionCuboid (const geometry_msgs::Pose &pose, double width, double depth, double height, const std::string &name, const rviz_visual_tools::colors &color)
 
bool publishCollisionCylinder (const Eigen::Isometry3d &object_pose, const std::string &object_name, double radius, double height, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN)
 Create a MoveIt Collision cylinder with a center point pose. More...
 
bool publishCollisionCylinder (const Eigen::Vector3d &a, const Eigen::Vector3d &b, const std::string &object_name, double radius, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN)
 
bool publishCollisionCylinder (const geometry_msgs::Point &a, const geometry_msgs::Point &b, const std::string &object_name, double radius, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN)
 Create a MoveIt Collision cylinder between two points. More...
 
bool publishCollisionCylinder (const geometry_msgs::Pose &object_pose, const std::string &object_name, double radius, double height, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN)
 
bool publishCollisionFloor (double z=0.0, const std::string &plane_name="Floor", const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN)
 Make the floor a collision object. More...
 
bool publishCollisionGraph (const graph_msgs::GeometryGraph &graph, const std::string &object_name, double radius, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN)
 Publish a connected birectional graph. More...
 
bool publishCollisionMesh (const Eigen::Isometry3d &object_pose, const std::string &object_name, const shape_msgs::Mesh &mesh_msg, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN)
 
bool publishCollisionMesh (const Eigen::Isometry3d &object_pose, const std::string &object_name, const std::string &mesh_path, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN)
 
bool publishCollisionMesh (const geometry_msgs::Pose &object_pose, const std::string &object_name, const shape_msgs::Mesh &mesh_msg, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN)
 
bool publishCollisionMesh (const geometry_msgs::Pose &object_pose, const std::string &object_name, const std::string &mesh_path, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN)
 Create a collision object using a mesh. More...
 
bool publishCollisionTable (double x, double y, double z, double angle, double width, double height, double depth, const std::string &name, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN)
 Publish a typical room table. More...
 
bool publishCollisionWall (double x, double y, double angle=0.0, double width=2.0, double height=1.5, const std::string &name="wall", const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN)
 Publish a typical room wall. More...
 
bool publishCollisionWall (double x, double y, double z, double angle=0.0, double width=2.0, double height=1.5, const std::string &name="wall", const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN)
 
bool publishContactPoints (const collision_detection::CollisionResult::ContactMap &contacts, const planning_scene::PlanningScene *planning_scene, const rviz_visual_tools::colors &color=rviz_visual_tools::RED)
 Given a contact map and planning scene, publish the contact points. More...
 
bool publishContactPoints (const moveit::core::RobotState &robot_state, const planning_scene::PlanningScene *planning_scene, const rviz_visual_tools::colors &color=rviz_visual_tools::RED)
 Given a planning scene and robot state, publish any collisions. More...
 
bool publishEEMarkers (const Eigen::Isometry3d &pose, const moveit::core::JointModelGroup *ee_jmg, const rviz_visual_tools::colors &color=rviz_visual_tools::DEFAULT, const std::string &ns="end_effector")
 
bool publishEEMarkers (const Eigen::Isometry3d &pose, const moveit::core::JointModelGroup *ee_jmg, const std::vector< double > &ee_joint_pos, const rviz_visual_tools::colors &color=rviz_visual_tools::DEFAULT, const std::string &ns="end_effector")
 Publish an end effector to rviz. More...
 
bool publishEEMarkers (const geometry_msgs::Pose &pose, const moveit::core::JointModelGroup *ee_jmg, const rviz_visual_tools::colors &color=rviz_visual_tools::DEFAULT, const std::string &ns="end_effector")
 
bool publishEEMarkers (const geometry_msgs::Pose &pose, const moveit::core::JointModelGroup *ee_jmg, const std::vector< double > &ee_joint_pos, const rviz_visual_tools::colors &color=rviz_visual_tools::DEFAULT, const std::string &ns="end_effector")
 
bool publishGrasps (const std::vector< moveit_msgs::Grasp > &possible_grasps, const moveit::core::JointModelGroup *ee_jmg, double animate_speed=0.1)
 Show grasps generated from moveit_simple_grasps or other MoveIt Grasp message sources. More...
 
bool publishIKSolutions (const std::vector< trajectory_msgs::JointTrajectoryPoint > &ik_solutions, const moveit::core::JointModelGroup *arm_jmg, 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. More...
 
bool publishRobotState (const moveit::core::RobotState &robot_state, const rviz_visual_tools::colors &color=rviz_visual_tools::DEFAULT, const std::vector< std::string > &highlight_links={})
 Publish a complete robot state to Rviz To use, add a RobotState marker to Rviz and subscribe to the DISPLAY_ROBOT_STATE_TOPIC, above. More...
 
bool publishRobotState (const moveit::core::RobotStatePtr &robot_state, const rviz_visual_tools::colors &color=rviz_visual_tools::DEFAULT, const std::vector< std::string > &highlight_links={})
 
void publishRobotState (const moveit_msgs::DisplayRobotState &display_robot_state_msg)
 
bool publishRobotState (const std::vector< double > &joint_positions, const moveit::core::JointModelGroup *jmg, const rviz_visual_tools::colors &color=rviz_visual_tools::DEFAULT)
 Publish a MoveIt robot state to a topic that the Rviz "RobotState" display can show. More...
 
bool publishRobotState (const trajectory_msgs::JointTrajectoryPoint &trajectory_pt, const moveit::core::JointModelGroup *jmg, const rviz_visual_tools::colors &color=rviz_visual_tools::DEFAULT)
 Publish a MoveIt robot state to a topic that the Rviz "RobotState" display can show. More...
 
bool publishTrajectoryLine (const moveit_msgs::RobotTrajectory &trajectory_msg, const moveit::core::JointModelGroup *arm_jmg, const rviz_visual_tools::colors &color=rviz_visual_tools::LIME_GREEN)
 Display a line of the end effector(s) path(s) from a robot trajectory path This version can visualize multiple end effectors. More...
 
bool publishTrajectoryLine (const moveit_msgs::RobotTrajectory &trajectory_msg, const moveit::core::LinkModel *ee_parent_link, const moveit::core::JointModelGroup *arm_jmg, const rviz_visual_tools::colors &color=rviz_visual_tools::LIME_GREEN)
 Display a line of the end effector path from a robot trajectory path. More...
 
bool publishTrajectoryLine (const robot_trajectory::RobotTrajectory &robot_trajectory, const moveit::core::JointModelGroup *arm_jmg, const rviz_visual_tools::colors &color=rviz_visual_tools::LIME_GREEN)
 
bool publishTrajectoryLine (const robot_trajectory::RobotTrajectory &robot_trajectory, const moveit::core::LinkModel *ee_parent_link, const rviz_visual_tools::colors &color=rviz_visual_tools::LIME_GREEN)
 
bool publishTrajectoryLine (const robot_trajectory::RobotTrajectoryPtr &robot_trajectory, const moveit::core::JointModelGroup *arm_jmg, const rviz_visual_tools::colors &color=rviz_visual_tools::LIME_GREEN)
 
bool publishTrajectoryLine (const robot_trajectory::RobotTrajectoryPtr &robot_trajectory, const moveit::core::LinkModel *ee_parent_link, const rviz_visual_tools::colors &color=rviz_visual_tools::LIME_GREEN)
 
void publishTrajectoryPath (const moveit_msgs::DisplayTrajectory &display_trajectory_msg)
 
bool publishTrajectoryPath (const moveit_msgs::RobotTrajectory &trajectory_msg, const moveit::core::RobotState &robot_state, bool blocking=false)
 
bool publishTrajectoryPath (const moveit_msgs::RobotTrajectory &trajectory_msg, const moveit::core::RobotStateConstPtr &robot_state, bool blocking=false)
 
bool publishTrajectoryPath (const moveit_msgs::RobotTrajectory &trajectory_msg, const moveit_msgs::RobotState &robot_state, bool blocking=false)
 
bool publishTrajectoryPath (const robot_trajectory::RobotTrajectory &trajectory, bool blocking=false)
 
bool publishTrajectoryPath (const robot_trajectory::RobotTrajectoryPtr &trajectory, bool blocking=false)
 
bool publishTrajectoryPath (const std::vector< moveit::core::RobotStatePtr > &trajectory, const moveit::core::JointModelGroup *jmg, double speed=0.01, bool blocking=false)
 Animate trajectory in rviz. These functions do not need a trigger() called because use different publisher. More...
 
bool publishTrajectoryPoint (const trajectory_msgs::JointTrajectoryPoint &trajectory_pt, const std::string &planning_group, 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. More...
 
bool publishTrajectoryPoints (const std::vector< moveit::core::RobotStatePtr > &robot_state_trajectory, const moveit::core::LinkModel *ee_parent_link, const rviz_visual_tools::colors &color=rviz_visual_tools::YELLOW)
 Display trajectory as series of end effector position points. More...
 
bool publishWorkspaceParameters (const moveit_msgs::WorkspaceParameters &params)
 Display size of workspace used for planning with OMPL, etc. Important for virtual joints. More...
 
bool removeAllCollisionObjects ()
 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. More...
 
void setManualSceneUpdating (bool enable_manual=true)
 Prevent the planning scene from always auto-pushing, but rather do it manually. More...
 
void setPlanningSceneMonitor (planning_scene_monitor::PlanningSceneMonitorPtr psm)
 Allow a pre-configured planning scene monitor to be set for publishing collision objects, etc. More...
 
void setPlanningSceneTopic (const std::string &planning_scene_topic)
 Set the planning scene topic. More...
 
void setRobotStateTopic (const std::string &robot_state_topic)
 Set the ROS topic for publishing a robot state. More...
 
void showJointLimits (const moveit::core::RobotStatePtr &robot_state)
 Print to console the current robot state's joint values within its limits visually. More...
 
bool triggerPlanningSceneUpdate ()
 When mannual_trigger_update_ is true, use this to tell the planning scene to send an update out. Do not use otherwise. More...
 
- Public Member Functions inherited from rviz_visual_tools::RvizVisualTools
std_msgs::ColorRGBA createRandColor () const
 
bool deleteAllMarkers ()
 
void enableBatchPublishing (bool enable=true)
 
void enableFrameLocking (bool enable=true)
 
const std::string getBaseFrame () const
 
Eigen::Vector3d getCenterPoint (const Eigen::Vector3d &a, const Eigen::Vector3d &b) const
 
std_msgs::ColorRGBA getColor (colors color) const
 
std_msgs::ColorRGBA getColorScale (double value) const
 
double getGlobalScale () const
 
bool getPsychedelicMode () const
 
RemoteControlPtrgetRemoteControl ()
 
geometry_msgs::Vector3 getScale (scales scale, double marker_scale=1.0) const
 
Eigen::Isometry3d getVectorBetweenPoints (const Eigen::Vector3d &a, const Eigen::Vector3d &b) const
 
void loadMarkerPub (bool wait_for_subscriber=false, bool latched=false)
 
void loadRemoteControl ()
 
bool loadRvizMarkers ()
 
void prompt (const std::string &msg)
 
bool publishABCDPlane (const double A, const double B, const double C, const double D, colors color=TRANSLUCENT, double x_width=1.0, double y_width=1.0)
 
bool publishArrow (const Eigen::Isometry3d &pose, colors color=BLUE, scales scale=MEDIUM, double length=0.0, std::size_t id=0)
 
bool publishArrow (const geometry_msgs::Point &start, const geometry_msgs::Point &end, colors color=BLUE, scales scale=MEDIUM, std::size_t id=0)
 
bool publishArrow (const geometry_msgs::Pose &pose, colors color=BLUE, scales scale=MEDIUM, double length=0.0, std::size_t id=0)
 
bool publishArrow (const geometry_msgs::PoseStamped &pose, colors color=BLUE, scales scale=MEDIUM, double length=0.0, std::size_t id=0)
 
bool publishAxis (const Eigen::Isometry3d &pose, double length, double radius=0.01, const std::string &ns="Axis")
 
bool publishAxis (const Eigen::Isometry3d &pose, scales scale=MEDIUM, const std::string &ns="Axis")
 
bool publishAxis (const geometry_msgs::Pose &pose, double length, double radius=0.01, const std::string &ns="Axis")
 
bool publishAxis (const geometry_msgs::Pose &pose, scales scale=MEDIUM, const std::string &ns="Axis")
 
bool publishAxisLabeled (const Eigen::Isometry3d &pose, const std::string &label, scales scale=MEDIUM, colors color=WHITE)
 
bool publishAxisLabeled (const geometry_msgs::Pose &pose, const std::string &label, scales scale=MEDIUM, colors color=WHITE)
 
bool publishAxisPath (const EigenSTL::vector_Isometry3d &path, double length=0.1, double radius=0.01, const std::string &ns="Axis Path")
 
bool publishAxisPath (const EigenSTL::vector_Isometry3d &path, scales scale=MEDIUM, const std::string &ns="Axis Path")
 
bool publishCone (const Eigen::Isometry3d &pose, double angle, colors color=TRANSLUCENT, double scale=1.0)
 
bool publishCone (const geometry_msgs::Pose &pose, double angle, colors color=TRANSLUCENT, double scale=1.0)
 
bool publishCuboid (const Eigen::Isometry3d &pose, const Eigen::Vector3d &size, colors color=BLUE)
 
bool publishCuboid (const Eigen::Isometry3d &pose, double depth, double width, double height, colors color=BLUE)
 
bool publishCuboid (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, colors color=BLUE)
 
bool publishCuboid (const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, colors color=BLUE, const std::string &ns="Cuboid", std::size_t id=0)
 
bool publishCuboid (const geometry_msgs::Pose &pose, const geometry_msgs::Vector3 &size, colors color=BLUE)
 
bool publishCuboid (const geometry_msgs::Pose &pose, double depth, double width, double height, colors color=BLUE)
 
bool publishCylinder (const Eigen::Isometry3d &pose, colors color=BLUE, double height=0.1, double radius=0.01, const std::string &ns="Cylinder")
 
bool publishCylinder (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, colors color, double radius=0.01, const std::string &ns="Cylinder")
 
bool publishCylinder (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, colors color=BLUE, scales scale=MEDIUM, const std::string &ns="Cylinder")
 
bool publishCylinder (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const std_msgs::ColorRGBA &color, double radius=0.01, const std::string &ns="Cylinder")
 
bool publishCylinder (const geometry_msgs::Pose &pose, colors color=BLUE, double height=0.1, double radius=0.01, const std::string &ns="Cylinder")
 
bool publishCylinder (const geometry_msgs::Pose &pose, const std_msgs::ColorRGBA &color, double height=0.1, double radius=0.01, const std::string &ns="Cylinder")
 
bool publishGraph (const graph_msgs::GeometryGraph &graph, colors color, double radius)
 
bool publishLine (const Eigen::Isometry3d &point1, const Eigen::Isometry3d &point2, colors color=BLUE, scales scale=MEDIUM)
 
bool publishLine (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, colors color, double radius)
 
bool publishLine (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, colors color=BLUE, scales scale=MEDIUM)
 
bool publishLine (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const std_msgs::ColorRGBA &color, double radius)
 
bool publishLine (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const std_msgs::ColorRGBA &color, scales scale=MEDIUM)
 
bool publishLine (const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, colors color=BLUE, scales scale=MEDIUM)
 
bool publishLine (const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, const std_msgs::ColorRGBA &color, const geometry_msgs::Vector3 &scale)
 
bool publishLine (const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, const std_msgs::ColorRGBA &color, scales scale=MEDIUM)
 
bool publishLines (const EigenSTL::vector_Vector3d &aPoints, const EigenSTL::vector_Vector3d &bPoints, const std::vector< colors > &colors, scales scale=MEDIUM)
 
bool publishLines (const std::vector< geometry_msgs::Point > &aPoints, const std::vector< geometry_msgs::Point > &bPoints, const std::vector< std_msgs::ColorRGBA > &colors, const geometry_msgs::Vector3 &scale)
 
bool publishLineStrip (const std::vector< geometry_msgs::Point > &path, colors color=RED, scales scale=MEDIUM, const std::string &ns="Path")
 
bool publishMarker (visualization_msgs::Marker &marker)
 
bool publishMarkers (visualization_msgs::MarkerArray &markers)
 
bool publishMesh (const Eigen::Isometry3d &pose, const shape_msgs::Mesh &mesh, colors color=CLEAR, double scale=1, const std::string &ns="mesh", std::size_t id=0)
 
bool publishMesh (const Eigen::Isometry3d &pose, const std::string &file_name, colors color=CLEAR, double scale=1, const std::string &ns="mesh", std::size_t id=0)
 
bool publishMesh (const geometry_msgs::Pose &pose, const shape_msgs::Mesh &mesh, colors color=CLEAR, double scale=1, const std::string &ns="mesh", std::size_t id=0)
 
bool publishMesh (const geometry_msgs::Pose &pose, const std::string &file_name, colors color=CLEAR, double scale=1, const std::string &ns="mesh", std::size_t id=0)
 
bool publishPath (const EigenSTL::vector_Isometry3d &path, colors color, scales scale, const std::string &ns="Path")
 
bool publishPath (const EigenSTL::vector_Isometry3d &path, colors color=RED, double radius=0.01, const std::string &ns="Path")
 
bool publishPath (const EigenSTL::vector_Vector3d &path, colors color, scales scale, const std::string &ns="Path")
 
bool publishPath (const EigenSTL::vector_Vector3d &path, colors color=RED, double radius=0.01, const std::string &ns="Path")
 
bool publishPath (const EigenSTL::vector_Vector3d &path, const std::vector< colors > &colors, double radius=0.01, const std::string &ns="Path")
 
bool publishPath (const EigenSTL::vector_Vector3d &path, const std::vector< std_msgs::ColorRGBA > &colors, double radius, const std::string &ns="Path")
 
bool publishPath (const std::vector< geometry_msgs::Point > &path, colors color, scales scale, const std::string &ns="Path")
 
bool publishPath (const std::vector< geometry_msgs::Point > &path, colors color=RED, double radius=0.01, const std::string &ns="Path")
 
bool publishPath (const std::vector< geometry_msgs::Pose > &path, colors color=RED, scales scale=MEDIUM, const std::string &ns="Path")
 
bool publishPolygon (const geometry_msgs::Polygon &polygon, colors color=RED, scales scale=MEDIUM, const std::string &ns="Polygon")
 
bool publishSphere (const Eigen::Isometry3d &pose, colors color=BLUE, scales scale=MEDIUM, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSphere (const Eigen::Isometry3d &pose, const std_msgs::ColorRGBA &color, const geometry_msgs::Vector3 scale, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSphere (const Eigen::Vector3d &point, colors color, double scale, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSphere (const Eigen::Vector3d &point, colors color=BLUE, scales scale=MEDIUM, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSphere (const Eigen::Vector3d &point, const std_msgs::ColorRGBA &color, const geometry_msgs::Vector3 scale, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSphere (const geometry_msgs::Point &point, colors color=BLUE, scales scale=MEDIUM, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSphere (const geometry_msgs::Pose &pose, colors color, const geometry_msgs::Vector3 scale, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSphere (const geometry_msgs::Pose &pose, colors color, double scale, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSphere (const geometry_msgs::Pose &pose, colors color=BLUE, scales scale=MEDIUM, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSphere (const geometry_msgs::Pose &pose, const std_msgs::ColorRGBA &color, const geometry_msgs::Vector3 scale, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSphere (const geometry_msgs::PoseStamped &pose, colors color, const geometry_msgs::Vector3 scale, const std::string &ns="Sphere", std::size_t id=0)
 
bool publishSpheres (const EigenSTL::vector_Vector3d &points, colors color, double scale=0.1, const std::string &ns="Spheres")
 
bool publishSpheres (const EigenSTL::vector_Vector3d &points, colors color=BLUE, scales scale=MEDIUM, const std::string &ns="Spheres")
 
bool publishSpheres (const EigenSTL::vector_Vector3d &points, const std::vector< colors > &colors, scales scale=MEDIUM, const std::string &ns="Spheres")
 
bool publishSpheres (const std::vector< geometry_msgs::Point > &points, colors color, const geometry_msgs::Vector3 &scale, const std::string &ns="Spheres")
 
bool publishSpheres (const std::vector< geometry_msgs::Point > &points, colors color=BLUE, double scale=0.1, const std::string &ns="Spheres")
 
bool publishSpheres (const std::vector< geometry_msgs::Point > &points, colors color=BLUE, scales scale=MEDIUM, const std::string &ns="Spheres")
 
bool publishSpheres (const std::vector< geometry_msgs::Point > &points, const std::vector< std_msgs::ColorRGBA > &colors, const geometry_msgs::Vector3 &scale, const std::string &ns="Spheres")
 
bool publishText (const Eigen::Isometry3d &pose, const std::string &text, colors color, const geometry_msgs::Vector3 scale, bool static_id=true)
 
bool publishText (const Eigen::Isometry3d &pose, const std::string &text, colors color=WHITE, scales scale=MEDIUM, bool static_id=true)
 
bool publishText (const geometry_msgs::Pose &pose, const std::string &text, colors color, const geometry_msgs::Vector3 scale, bool static_id=true)
 
bool publishText (const geometry_msgs::Pose &pose, const std::string &text, colors color=WHITE, scales scale=MEDIUM, bool static_id=true)
 
bool publishWireframeCuboid (const Eigen::Isometry3d &pose, const Eigen::Vector3d &min_point, const Eigen::Vector3d &max_point, colors color=BLUE, const std::string &ns="Wireframe Cuboid", std::size_t id=0)
 
bool publishWireframeCuboid (const Eigen::Isometry3d &pose, double depth, double width, double height, colors color=BLUE, const std::string &ns="Wireframe Cuboid", std::size_t id=0)
 
bool publishWireframeRectangle (const Eigen::Isometry3d &pose, const Eigen::Vector3d &p1_in, const Eigen::Vector3d &p2_in, const Eigen::Vector3d &p3_in, const Eigen::Vector3d &p4_in, colors color, scales scale)
 
bool publishWireframeRectangle (const Eigen::Isometry3d &pose, double height, double width, colors color=BLUE, scales scale=MEDIUM, std::size_t id=0)
 
bool publishXArrow (const Eigen::Isometry3d &pose, colors color=RED, scales scale=MEDIUM, double length=0.0)
 
bool publishXArrow (const geometry_msgs::Pose &pose, colors color=RED, scales scale=MEDIUM, double length=0.0)
 
bool publishXArrow (const geometry_msgs::PoseStamped &pose, colors color=RED, scales scale=MEDIUM, double length=0.0)
 
bool publishXYPlane (const Eigen::Isometry3d &pose, colors color=TRANSLUCENT, double scale=1.0)
 
bool publishXYPlane (const geometry_msgs::Pose &pose, colors color=TRANSLUCENT, double scale=1.0)
 
bool publishXZPlane (const Eigen::Isometry3d &pose, colors color=TRANSLUCENT, double scale=1.0)
 
bool publishXZPlane (const geometry_msgs::Pose &pose, colors color=TRANSLUCENT, double scale=1.0)
 
bool publishYArrow (const Eigen::Isometry3d &pose, colors color=GREEN, scales scale=MEDIUM, double length=0.0)
 
bool publishYArrow (const geometry_msgs::Pose &pose, colors color=GREEN, scales scale=MEDIUM, double length=0.0)
 
bool publishYArrow (const geometry_msgs::PoseStamped &pose, colors color=GREEN, scales scale=MEDIUM, double length=0.0)
 
bool publishYZPlane (const Eigen::Isometry3d &pose, colors color=TRANSLUCENT, double scale=1.0)
 
bool publishYZPlane (const geometry_msgs::Pose &pose, colors color=TRANSLUCENT, double scale=1.0)
 
bool publishZArrow (const Eigen::Isometry3d &pose, colors color=BLUE, scales scale=MEDIUM, double length=0.0, std::size_t id=0)
 
bool publishZArrow (const geometry_msgs::Pose &pose, colors color=BLUE, scales scale=MEDIUM, double length=0.0)
 
bool publishZArrow (const geometry_msgs::PoseStamped &pose, colors color=BLUE, scales scale=MEDIUM, double length=0.0)
 
bool publishZArrow (const geometry_msgs::PoseStamped &pose, colors color=BLUE, scales scale=MEDIUM, double length=0.0, std::size_t id=0)
 
void resetMarkerCounts ()
 
 RvizVisualTools (std::string base_frame, std::string marker_topic=RVIZ_MARKER_TOPIC, ros::NodeHandle nh=ros::NodeHandle("~"))
 
void setAlpha (double alpha)
 
void setBaseFrame (const std::string &base_frame)
 
void setGlobalScale (double global_scale)
 
void setLifetime (double lifetime)
 
void setMarkerTopic (const std::string &topic)
 
void setPsychedelicMode (bool psychedelic_mode=true)
 
bool trigger ()
 
bool triggerEvery (std::size_t queueSize)
 
void waitForMarkerPub ()
 
void waitForMarkerPub (double wait_time)
 
bool waitForSubscriber (const ros::Publisher &pub, double wait_time=0.5, bool blocking=false)
 
 ~RvizVisualTools ()
 

Static Public Member Functions

static bool applyVirtualJointTransform (moveit::core::RobotState &robot_state, const Eigen::Isometry3d &offset)
 Before publishing a robot state, optionally change its root transform. More...
 
- Static Public Member Functions inherited from rviz_visual_tools::RvizVisualTools
static Eigen::Isometry3d convertFromXYZRPY (const std::vector< double > &transform6, EulerConvention convention)
 
static Eigen::Isometry3d convertFromXYZRPY (double tx, double ty, double tz, double rx, double ry, double rz, EulerConvention convention)
 
static geometry_msgs::Point convertPoint (const Eigen::Vector3d &point)
 
static Eigen::Vector3d convertPoint (const geometry_msgs::Point &point)
 
static geometry_msgs::Point convertPoint (const geometry_msgs::Vector3 &point)
 
static geometry_msgs::Point32 convertPoint32 (const Eigen::Vector3d &point)
 
static Eigen::Vector3d convertPoint32 (const geometry_msgs::Point32 &point)
 
static Eigen::Isometry3d convertPoint32ToPose (const geometry_msgs::Point32 &point)
 
static Eigen::Isometry3d convertPointToPose (const Eigen::Vector3d &point)
 
static geometry_msgs::Pose convertPointToPose (const geometry_msgs::Point &point)
 
static geometry_msgs::Pose convertPose (const Eigen::Isometry3d &pose)
 
static Eigen::Isometry3d convertPose (const geometry_msgs::Pose &pose)
 
static void convertPoseSafe (const Eigen::Isometry3d &pose, geometry_msgs::Pose &pose_msg)
 
static void convertPoseSafe (const geometry_msgs::Pose &pose_msg, Eigen::Isometry3d &pose)
 
static geometry_msgs::Point convertPoseToPoint (const Eigen::Isometry3d &pose)
 
static void convertToXYZRPY (const Eigen::Isometry3d &pose, double &x, double &y, double &z, double &roll, double &pitch, double &yaw)
 
static void convertToXYZRPY (const Eigen::Isometry3d &pose, std::vector< double > &xyzrpy)
 
static double dRand (double min, double max)
 
static float fRand (float min, float max)
 
static void generateRandomCuboid (geometry_msgs::Pose &cuboid_pose, double &depth, double &width, double &height, RandomPoseBounds pose_bounds=RandomPoseBounds(), RandomCuboidBounds cuboid_bounds=RandomCuboidBounds())
 
static void generateRandomPose (Eigen::Isometry3d &pose, RandomPoseBounds pose_bounds=RandomPoseBounds())
 
static void generateRandomPose (geometry_msgs::Pose &pose, RandomPoseBounds pose_bounds=RandomPoseBounds())
 
static geometry_msgs::Pose getIdentityPose ()
 
static colors getRandColor ()
 
static colors intToRvizColor (std::size_t color)
 
static rviz_visual_tools::scales intToRvizScale (std::size_t scale)
 
static int iRand (int min, int max)
 
static bool posesEqual (const Eigen::Isometry3d &pose1, const Eigen::Isometry3d &pose2, double threshold=0.000001)
 
static void printTransform (const Eigen::Isometry3d &transform)
 
static void printTransformFull (const Eigen::Isometry3d &transform)
 
static void printTransformRPY (const Eigen::Isometry3d &transform)
 
static void printTranslation (const Eigen::Vector3d &translation)
 
static std::string scaleToString (scales scale)
 
static double slerp (double start, double end, double range, double value)
 

Protected Attributes

std::map< rviz_visual_tools::colors, moveit_msgs::DisplayRobotState > display_robot_msgs_
 
std::map< const moveit::core::JointModelGroup *, std::vector< double > > ee_joint_pos_map_
 
std::map< const moveit::core::JointModelGroup *, visualization_msgs::MarkerArray > ee_markers_map_
 
std::map< const moveit::core::JointModelGroup *, EigenSTL::vector_Isometry3dee_poses_map_
 
moveit::core::RobotStatePtr hidden_robot_state_
 
bool mannual_trigger_update_ = false
 
std::string planning_scene_topic_
 
planning_scene_monitor::PlanningSceneMonitorPtr psm_
 
ros::Publisher pub_display_path_
 
ros::Publisher pub_robot_state_
 
robot_model_loader::RobotModelLoaderPtr rm_loader_
 
moveit::core::RobotModelConstPtr robot_model_
 
Eigen::Isometry3d robot_state_root_offset_
 
bool robot_state_root_offset_enabled_ = false
 
std::string robot_state_topic_
 
moveit::core::RobotStatePtr root_robot_state_
 
moveit::core::RobotStatePtr shared_robot_state_
 
- Protected Attributes inherited from rviz_visual_tools::RvizVisualTools
double alpha_
 
visualization_msgs::Marker arrow_marker_
 
std::string base_frame_
 
bool batch_publishing_enabled_
 
visualization_msgs::Marker block_marker_
 
visualization_msgs::Marker cuboid_marker_
 
visualization_msgs::Marker cylinder_marker_
 
bool frame_locking_enabled_
 
double global_scale_
 
visualization_msgs::Marker line_list_marker_
 
visualization_msgs::Marker line_strip_marker_
 
ros::Duration marker_lifetime_
 
std::string marker_topic_
 
visualization_msgs::MarkerArray markers_
 
visualization_msgs::Marker mesh_marker_
 
ros::NodeHandle nh_
 
bool psychedelic_mode_
 
ros::Publisher pub_rviz_markers_
 
bool pub_rviz_markers_connected_
 
bool pub_rviz_markers_waited_
 
RemoteControlPtr remote_control_
 
visualization_msgs::Marker reset_marker_
 
visualization_msgs::Marker sphere_marker_
 
visualization_msgs::Marker spheres_marker_
 
visualization_msgs::Marker text_marker_
 
visualization_msgs::Marker triangle_marker_
 

Static Private Member Functions

static bool checkForVirtualJoint (const moveit::core::RobotState &robot_state)
 Error check that the robot's SRDF was properly setup with a virtual joint that was named a certain way. More...
 

Additional Inherited Members

- Static Protected Attributes inherited from rviz_visual_tools::RvizVisualTools
static const std::array< colors, 14 > ALL_RAND_COLORS
 
static const RVIZ_VISUAL_TOOLS_DECL std::string NAME
 

Detailed Description

Definition at line 108 of file moveit_visual_tools.h.

Constructor & Destructor Documentation

◆ MoveItVisualTools() [1/3]

moveit_visual_tools::MoveItVisualTools::MoveItVisualTools ( )

Constructor.

All Markers will be rendered in the planning frame of the model ROBOT_DESCRIPTION and are published to rviz_visual_tools::RVIZ_MARKER_TOPIC

Definition at line 102 of file moveit_visual_tools.cpp.

◆ MoveItVisualTools() [2/3]

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

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 111 of file moveit_visual_tools.cpp.

◆ MoveItVisualTools() [3/3]

moveit_visual_tools::MoveItVisualTools::MoveItVisualTools ( const std::string &  base_frame,
const std::string &  marker_topic = rviz_visual_tools::RVIZ_MARKER_TOPIC,
moveit::core::RobotModelConstPtr  robot_model = moveit::core::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 120 of file moveit_visual_tools.cpp.

Member Function Documentation

◆ applyVirtualJointTransform()

bool moveit_visual_tools::MoveItVisualTools::applyVirtualJointTransform ( moveit::core::RobotState robot_state,
const Eigen::Isometry3d &  offset 
)
static

Before publishing a robot state, optionally change its root transform.

Definition at line 1697 of file moveit_visual_tools.cpp.

◆ attachCO()

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

Attach a collision object from the planning scene.

Parameters
Nameof object

Definition at line 654 of file moveit_visual_tools.cpp.

◆ checkAndPublishCollision()

bool moveit_visual_tools::MoveItVisualTools::checkAndPublishCollision ( const moveit::core::RobotState robot_state,
const planning_scene::PlanningScene planning_scene,
const rviz_visual_tools::colors highlight_link_color = rviz_visual_tools::RED,
const rviz_visual_tools::colors contact_point_color = rviz_visual_tools::PURPLE 
)

Check if the robot state is in collision inside the planning scene and visualize the result. If the state is not colliding only the robot state is published. If there is a collision the colliding links are ghlighted and the contact points are visualized with markers.

Parameters
robot_state- The robot state to check for collisions
planning_scene- The planning scene to use for collision checks
highlight_link_color- The color to use for highligting colliding links
contact_point_color- The color to use for contact point markers
Returns
- True if there is a collision

Definition at line 1102 of file moveit_visual_tools.cpp.

◆ checkForVirtualJoint()

bool moveit_visual_tools::MoveItVisualTools::checkForVirtualJoint ( const moveit::core::RobotState robot_state)
staticprivate

Error check that the robot's SRDF was properly setup with a virtual joint that was named a certain way.

Returns
true on success

Definition at line 1669 of file moveit_visual_tools.cpp.

◆ cleanupACO()

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

Remove an active collision object from the planning scene.

Parameters
Nameof object
Returns
true on sucess

Definition at line 641 of file moveit_visual_tools.cpp.

◆ cleanupCO()

bool moveit_visual_tools::MoveItVisualTools::cleanupCO ( const std::string &  name)

Remove a collision object from the planning scene.

Parameters
Nameof object
Returns
true on sucess

Definition at line 629 of file moveit_visual_tools.cpp.

◆ disableRobotStateRootOffet()

void moveit_visual_tools::MoveItVisualTools::disableRobotStateRootOffet ( )

Turn off the root offset feature.

Definition at line 1482 of file moveit_visual_tools.cpp.

◆ enableRobotStateRootOffet()

void moveit_visual_tools::MoveItVisualTools::enableRobotStateRootOffet ( const Eigen::Isometry3d &  offset)

All published robot states will have their virtual joint moved by offset.

Definition at line 1476 of file moveit_visual_tools.cpp.

◆ getCollisionWallMsg()

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

Helper for publishCollisionWall.

Definition at line 969 of file moveit_visual_tools.cpp.

◆ getPlanningSceneMonitor()

planning_scene_monitor::PlanningSceneMonitorPtr moveit_visual_tools::MoveItVisualTools::getPlanningSceneMonitor ( )

Get the planning scene monitor that this class is using.

Returns
a ptr to a planning scene

Private Functions

Definition at line 1657 of file moveit_visual_tools.cpp.

◆ getRobotModel()

moveit::core::RobotModelConstPtr moveit_visual_tools::MoveItVisualTools::getRobotModel ( )

Get a pointer to the robot model.

Returns
const RobotModel

Definition at line 274 of file moveit_visual_tools.cpp.

◆ getRootRobotState()

moveit::core::RobotStatePtr& moveit_visual_tools::MoveItVisualTools::getRootRobotState ( )
inline

Allow robot state to be altered.

Returns
shared pointer to robot state

Definition at line 212 of file moveit_visual_tools.h.

◆ getSharedRobotState()

moveit::core::RobotStatePtr & moveit_visual_tools::MoveItVisualTools::getSharedRobotState ( )

Allow robot state to be altered.

Returns
shared pointer to robot state

Definition at line 267 of file moveit_visual_tools.cpp.

◆ hideRobot()

bool moveit_visual_tools::MoveItVisualTools::hideRobot ( )

Hide robot in RobotState display in Rviz.

Returns
true on success

Definition at line 1589 of file moveit_visual_tools.cpp.

◆ loadCollisionSceneFromFile() [1/2]

bool moveit_visual_tools::MoveItVisualTools::loadCollisionSceneFromFile ( const std::string &  path)

Load a planning scene to a planning_scene_monitor from file.

Parameters
path- path to planning scene, e.g. as exported from Rviz Plugin
offsetfor scene to be placed
Returns
true on success

Definition at line 1062 of file moveit_visual_tools.cpp.

◆ loadCollisionSceneFromFile() [2/2]

bool moveit_visual_tools::MoveItVisualTools::loadCollisionSceneFromFile ( const std::string &  path,
const Eigen::Isometry3d &  offset 
)

Definition at line 1067 of file moveit_visual_tools.cpp.

◆ loadEEMarker()

bool moveit_visual_tools::MoveItVisualTools::loadEEMarker ( const moveit::core::JointModelGroup ee_jmg,
const std::vector< double > &  ee_joint_pos = {} 
)

Call this once at begining to load the end effector markers and then whenever a joint changes.

Parameters
ee_jmg- the set of joints to use, e.g. the MoveIt planning group, e.g. "left_gripper"
ee_joint_pos- the values of all active joints in this planning group
Returns
true if it is successful

Definition at line 281 of file moveit_visual_tools.cpp.

◆ loadPlanningSceneMonitor()

bool moveit_visual_tools::MoveItVisualTools::loadPlanningSceneMonitor ( )

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

Returns
true if successful in loading

Definition at line 126 of file moveit_visual_tools.cpp.

◆ loadRobotStatePub()

void moveit_visual_tools::MoveItVisualTools::loadRobotStatePub ( const std::string &  robot_state_topic = "",
bool  blocking = true 
)

Definition at line 386 of file moveit_visual_tools.cpp.

◆ loadSharedRobotState()

bool moveit_visual_tools::MoveItVisualTools::loadSharedRobotState ( )

Load robot state only as needed.

Returns
true if successful in loading

Definition at line 239 of file moveit_visual_tools.cpp.

◆ loadTrajectoryPub()

void moveit_visual_tools::MoveItVisualTools::loadTrajectoryPub ( const std::string &  display_planned_path_topic = DISPLAY_PLANNED_PATH_TOPIC,
bool  blocking = true 
)

Load publishers as needed.

Definition at line 372 of file moveit_visual_tools.cpp.

◆ moveCollisionObject() [1/2]

bool moveit_visual_tools::MoveItVisualTools::moveCollisionObject ( const Eigen::Isometry3d &  pose,
const std::string &  name,
const rviz_visual_tools::colors color 
)

Move an already published collision object to a new location in space.

Parameters
pose- location of center of object
name- semantic name of MoveIt collision object
Returns
true on success

Definition at line 208 of file moveit_visual_tools.cpp.

◆ moveCollisionObject() [2/2]

bool moveit_visual_tools::MoveItVisualTools::moveCollisionObject ( const geometry_msgs::Pose pose,
const std::string &  name,
const rviz_visual_tools::colors color 
)

Definition at line 214 of file moveit_visual_tools.cpp.

◆ processAttachedCollisionObjectMsg()

bool moveit_visual_tools::MoveItVisualTools::processAttachedCollisionObjectMsg ( const moveit_msgs::AttachedCollisionObject &  msg)

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

Parameters
attachedcollision object message
Returns
true on success

Definition at line 190 of file moveit_visual_tools.cpp.

◆ processCollisionObjectMsg()

bool moveit_visual_tools::MoveItVisualTools::processCollisionObjectMsg ( const moveit_msgs::CollisionObject &  msg,
const rviz_visual_tools::colors color = rviz_visual_tools::GREEN 
)

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

Parameters
collisionobject message
colorto display the collision object with
Returns
true on success

Definition at line 171 of file moveit_visual_tools.cpp.

◆ publishAnimatedGrasp()

bool moveit_visual_tools::MoveItVisualTools::publishAnimatedGrasp ( const moveit_msgs::Grasp &  grasp,
const moveit::core::JointModelGroup ee_jmg,
double  animate_speed 
)

Animate a single grasp in its movement direction Note this function calls publish() automatically in order to achieve animations.

Parameters
grasp
ee_jmg- the set of joints to use, e.g. the MoveIt planning group, e.g. "left_arm"
animate_speed- how fast the gripper approach is animated
Returns
true on sucess

Definition at line 497 of file moveit_visual_tools.cpp.

◆ publishAnimatedGrasps()

bool moveit_visual_tools::MoveItVisualTools::publishAnimatedGrasps ( const std::vector< moveit_msgs::Grasp > &  possible_grasps,
const moveit::core::JointModelGroup ee_jmg,
double  animate_speed = 0.01 
)

Display an animated vector of grasps including its approach movement in Rviz Note this function calls publish() automatically in order to achieve animations.

Parameters
possible_grasps- a set of grasp positions to visualize
ee_jmg- the set of joints to use, e.g. the MoveIt planning group, e.g. "left_arm"
animate_speed- how fast the gripper approach is animated, optional

Definition at line 478 of file moveit_visual_tools.cpp.

◆ publishCollisionBlock()

bool moveit_visual_tools::MoveItVisualTools::publishCollisionBlock ( const geometry_msgs::Pose block_pose,
const std::string &  block_name = "block",
double  block_size = 0.1,
const rviz_visual_tools::colors color = rviz_visual_tools::GREEN 
)

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
colorto display the collision object with
Returns
true on sucess

Definition at line 670 of file moveit_visual_tools.cpp.

◆ publishCollisionCuboid() [1/6]

bool moveit_visual_tools::MoveItVisualTools::publishCollisionCuboid ( const Eigen::Isometry3d &  pose,
const Eigen::Vector3d size,
const std::string &  name,
const rviz_visual_tools::colors color 
)
inline

Create a MoveIt collision rectangular cuboid at the given pose.

Parameters
pose- position of the centroid of the cube
size- the size (x,y,z) of the object in its local frame
name- semantic name of MoveIt collision object
colorto display the collision object with
Returns
true on sucess

Definition at line 418 of file moveit_visual_tools.h.

◆ publishCollisionCuboid() [2/6]

bool moveit_visual_tools::MoveItVisualTools::publishCollisionCuboid ( const Eigen::Isometry3d &  pose,
double  width,
double  depth,
double  height,
const std::string &  name,
const rviz_visual_tools::colors color 
)

Create a MoveIt collision rectangular cuboid at the given pose.

Parameters
pose- position of the centroid of the cube
width- width of the object in its local frame
depth- depth of the object in its local frame
height- height of the object in its local frame
name- semantic name of MoveIt collision object
colorto display the collision object with
Returns
true on sucess

Definition at line 736 of file moveit_visual_tools.cpp.

◆ publishCollisionCuboid() [3/6]

bool moveit_visual_tools::MoveItVisualTools::publishCollisionCuboid ( const Eigen::Vector3d point1,
const Eigen::Vector3d point2,
const std::string &  name,
const rviz_visual_tools::colors color = rviz_visual_tools::GREEN 
)

Create a MoveIt collision rectangular cuboid at the given pose.

Parameters
point1- top left of rectangle
point2- bottom right of rectangle
name- semantic name of MoveIt collision object
colorto display the collision object with
Returns
true on sucess

Definition at line 694 of file moveit_visual_tools.cpp.

◆ publishCollisionCuboid() [4/6]

bool moveit_visual_tools::MoveItVisualTools::publishCollisionCuboid ( const geometry_msgs::Point point1,
const geometry_msgs::Point point2,
const std::string &  name,
const rviz_visual_tools::colors color = rviz_visual_tools::GREEN 
)

Definition at line 700 of file moveit_visual_tools.cpp.

◆ publishCollisionCuboid() [5/6]

bool moveit_visual_tools::MoveItVisualTools::publishCollisionCuboid ( const geometry_msgs::Pose pose,
const geometry_msgs::Vector3 size,
const std::string &  name,
const rviz_visual_tools::colors color 
)
inline

Definition at line 423 of file moveit_visual_tools.h.

◆ publishCollisionCuboid() [6/6]

bool moveit_visual_tools::MoveItVisualTools::publishCollisionCuboid ( const geometry_msgs::Pose pose,
double  width,
double  depth,
double  height,
const std::string &  name,
const rviz_visual_tools::colors color 
)

Definition at line 743 of file moveit_visual_tools.cpp.

◆ publishCollisionCylinder() [1/4]

bool moveit_visual_tools::MoveItVisualTools::publishCollisionCylinder ( const Eigen::Isometry3d &  object_pose,
const std::string &  object_name,
double  radius,
double  height,
const rviz_visual_tools::colors color = rviz_visual_tools::GREEN 
)

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
colorto display the collision object with
Returns
true on sucess

Definition at line 824 of file moveit_visual_tools.cpp.

◆ publishCollisionCylinder() [2/4]

bool moveit_visual_tools::MoveItVisualTools::publishCollisionCylinder ( const Eigen::Vector3d a,
const Eigen::Vector3d b,
const std::string &  object_name,
double  radius,
const rviz_visual_tools::colors color = rviz_visual_tools::GREEN 
)

Definition at line 802 of file moveit_visual_tools.cpp.

◆ publishCollisionCylinder() [3/4]

bool moveit_visual_tools::MoveItVisualTools::publishCollisionCylinder ( const geometry_msgs::Point a,
const geometry_msgs::Point b,
const std::string &  object_name,
double  radius,
const rviz_visual_tools::colors color = rviz_visual_tools::GREEN 
)

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
colorto display the collision object with
Returns
true on sucess

Definition at line 795 of file moveit_visual_tools.cpp.

◆ publishCollisionCylinder() [4/4]

bool moveit_visual_tools::MoveItVisualTools::publishCollisionCylinder ( const geometry_msgs::Pose object_pose,
const std::string &  object_name,
double  radius,
double  height,
const rviz_visual_tools::colors color = rviz_visual_tools::GREEN 
)

Definition at line 830 of file moveit_visual_tools.cpp.

◆ publishCollisionFloor()

bool moveit_visual_tools::MoveItVisualTools::publishCollisionFloor ( double  z = 0.0,
const std::string &  plane_name = "Floor",
const rviz_visual_tools::colors color = rviz_visual_tools::GREEN 
)

Make the floor a collision object.

Parameters
zlocation of floor
nameof floor
colorto display the collision object with
Returns
true on success

Definition at line 777 of file moveit_visual_tools.cpp.

◆ publishCollisionGraph()

bool moveit_visual_tools::MoveItVisualTools::publishCollisionGraph ( const graph_msgs::GeometryGraph &  graph,
const std::string &  object_name,
double  radius,
const rviz_visual_tools::colors color = rviz_visual_tools::GREEN 
)

Publish a connected birectional graph.

Parameters
graphof nodes and edges
nameof collision object
colorto display the collision object with
Returns
true on sucess

Definition at line 898 of file moveit_visual_tools.cpp.

◆ publishCollisionMesh() [1/4]

bool moveit_visual_tools::MoveItVisualTools::publishCollisionMesh ( const Eigen::Isometry3d &  object_pose,
const std::string &  object_name,
const shape_msgs::Mesh &  mesh_msg,
const rviz_visual_tools::colors color = rviz_visual_tools::GREEN 
)

Definition at line 875 of file moveit_visual_tools.cpp.

◆ publishCollisionMesh() [2/4]

bool moveit_visual_tools::MoveItVisualTools::publishCollisionMesh ( const Eigen::Isometry3d &  object_pose,
const std::string &  object_name,
const std::string &  mesh_path,
const rviz_visual_tools::colors color = rviz_visual_tools::GREEN 
)

Definition at line 851 of file moveit_visual_tools.cpp.

◆ publishCollisionMesh() [3/4]

bool moveit_visual_tools::MoveItVisualTools::publishCollisionMesh ( const geometry_msgs::Pose object_pose,
const std::string &  object_name,
const shape_msgs::Mesh &  mesh_msg,
const rviz_visual_tools::colors color = rviz_visual_tools::GREEN 
)

Definition at line 881 of file moveit_visual_tools.cpp.

◆ publishCollisionMesh() [4/4]

bool moveit_visual_tools::MoveItVisualTools::publishCollisionMesh ( const geometry_msgs::Pose object_pose,
const std::string &  object_name,
const std::string &  mesh_path,
const rviz_visual_tools::colors color = rviz_visual_tools::GREEN 
)

Create a collision object using a mesh.

Parameters
pose- location of center of mesh
name- semantic name of MoveIt collision object
peth- file location to an .stl file
colorto display the collision object with
Returns
true on success

Definition at line 857 of file moveit_visual_tools.cpp.

◆ publishCollisionTable()

bool moveit_visual_tools::MoveItVisualTools::publishCollisionTable ( double  x,
double  y,
double  z,
double  angle,
double  width,
double  height,
double  depth,
const std::string &  name,
const rviz_visual_tools::colors color = rviz_visual_tools::GREEN 
)

Publish a typical room table.

Parameters
x
y
angle
width
height
depth
name
colorto display the collision object with
Returns
true on sucess

Definition at line 1024 of file moveit_visual_tools.cpp.

◆ publishCollisionWall() [1/2]

bool moveit_visual_tools::MoveItVisualTools::publishCollisionWall ( double  x,
double  y,
double  angle = 0.0,
double  width = 2.0,
double  height = 1.5,
const std::string &  name = "wall",
const rviz_visual_tools::colors color = rviz_visual_tools::GREEN 
)

Publish a typical room wall.

Parameters
x
y
angle
width
height
name
colorto display the collision object with
Returns
true on sucess

Definition at line 1009 of file moveit_visual_tools.cpp.

◆ publishCollisionWall() [2/2]

bool moveit_visual_tools::MoveItVisualTools::publishCollisionWall ( double  x,
double  y,
double  z,
double  angle = 0.0,
double  width = 2.0,
double  height = 1.5,
const std::string &  name = "wall",
const rviz_visual_tools::colors color = rviz_visual_tools::GREEN 
)

Definition at line 1015 of file moveit_visual_tools.cpp.

◆ publishContactPoints() [1/2]

bool moveit_visual_tools::MoveItVisualTools::publishContactPoints ( const collision_detection::CollisionResult::ContactMap contacts,
const planning_scene::PlanningScene planning_scene,
const rviz_visual_tools::colors color = rviz_visual_tools::RED 
)

Given a contact map and planning scene, publish the contact points.

Parameters
contacts- The populated contacts to visualize
planning_scene
color- display color of markers
Returns
true on success

Definition at line 1146 of file moveit_visual_tools.cpp.

◆ publishContactPoints() [2/2]

bool moveit_visual_tools::MoveItVisualTools::publishContactPoints ( const moveit::core::RobotState robot_state,
const planning_scene::PlanningScene planning_scene,
const rviz_visual_tools::colors color = rviz_visual_tools::RED 
)

Given a planning scene and robot state, publish any collisions.

Parameters
robot_state
planning_scene
color- display color of markers
Returns
true on success

Definition at line 1129 of file moveit_visual_tools.cpp.

◆ publishEEMarkers() [1/4]

bool moveit_visual_tools::MoveItVisualTools::publishEEMarkers ( const Eigen::Isometry3d &  pose,
const moveit::core::JointModelGroup ee_jmg,
const rviz_visual_tools::colors color = rviz_visual_tools::DEFAULT,
const std::string &  ns = "end_effector" 
)
inline

Definition at line 271 of file moveit_visual_tools.h.

◆ publishEEMarkers() [2/4]

bool moveit_visual_tools::MoveItVisualTools::publishEEMarkers ( const Eigen::Isometry3d &  pose,
const moveit::core::JointModelGroup ee_jmg,
const std::vector< double > &  ee_joint_pos,
const rviz_visual_tools::colors color = rviz_visual_tools::DEFAULT,
const std::string &  ns = "end_effector" 
)
inline

Publish an end effector to rviz.

Parameters
pose- the location to publish the marker with respect to the base frame
ee_jmg- joint model group of the end effector, e.g. "left_hand"
ee_joint_pos- position of all active joints in the end effector
colorto display the collision object with
Returns
true on success

Definition at line 264 of file moveit_visual_tools.h.

◆ publishEEMarkers() [3/4]

bool moveit_visual_tools::MoveItVisualTools::publishEEMarkers ( const geometry_msgs::Pose pose,
const moveit::core::JointModelGroup ee_jmg,
const rviz_visual_tools::colors color = rviz_visual_tools::DEFAULT,
const std::string &  ns = "end_effector" 
)
inline

Definition at line 277 of file moveit_visual_tools.h.

◆ publishEEMarkers() [4/4]

bool moveit_visual_tools::MoveItVisualTools::publishEEMarkers ( const geometry_msgs::Pose pose,
const moveit::core::JointModelGroup ee_jmg,
const std::vector< double > &  ee_joint_pos,
const rviz_visual_tools::colors color = rviz_visual_tools::DEFAULT,
const std::string &  ns = "end_effector" 
)

Definition at line 404 of file moveit_visual_tools.cpp.

◆ publishGrasps()

bool moveit_visual_tools::MoveItVisualTools::publishGrasps ( const std::vector< moveit_msgs::Grasp > &  possible_grasps,
const moveit::core::JointModelGroup ee_jmg,
double  animate_speed = 0.1 
)

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

Parameters
possible_grasps- a set of grasp positions to visualize
ee_jmg- the set of joints to use, e.g. the MoveIt planning group, e.g. "left_arm"
animate_speed- how fast the gripper approach is animated, optional

Definition at line 458 of file moveit_visual_tools.cpp.

◆ publishIKSolutions()

bool moveit_visual_tools::MoveItVisualTools::publishIKSolutions ( const std::vector< trajectory_msgs::JointTrajectoryPoint > &  ik_solutions,
const moveit::core::JointModelGroup arm_jmg,
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
arm_jmg- the set of joints to use, e.g. the MoveIt planning group, e.g. "left_arm"
display_time- amount of time to sleep between sending trajectories, optional

Definition at line 576 of file moveit_visual_tools.cpp.

◆ publishRobotState() [1/5]

bool moveit_visual_tools::MoveItVisualTools::publishRobotState ( const moveit::core::RobotState robot_state,
const rviz_visual_tools::colors color = rviz_visual_tools::DEFAULT,
const std::vector< std::string > &  highlight_links = {} 
)

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- joint values of robot
color- how to highlight the robot (solid-ly) if desired, default keeps color as specified in URDF
highlight_links- if the |color| is not |DEFAULT|, allows selective robot links to be highlighted. By default (empty) all links are highlighted.

Definition at line 1516 of file moveit_visual_tools.cpp.

◆ publishRobotState() [2/5]

bool moveit_visual_tools::MoveItVisualTools::publishRobotState ( const moveit::core::RobotStatePtr &  robot_state,
const rviz_visual_tools::colors color = rviz_visual_tools::DEFAULT,
const std::vector< std::string > &  highlight_links = {} 
)

Definition at line 1509 of file moveit_visual_tools.cpp.

◆ publishRobotState() [3/5]

void moveit_visual_tools::MoveItVisualTools::publishRobotState ( const moveit_msgs::DisplayRobotState &  display_robot_state_msg)

Definition at line 1582 of file moveit_visual_tools.cpp.

◆ publishRobotState() [4/5]

bool moveit_visual_tools::MoveItVisualTools::publishRobotState ( const std::vector< double > &  joint_positions,
const moveit::core::JointModelGroup jmg,
const rviz_visual_tools::colors color = rviz_visual_tools::DEFAULT 
)

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

Parameters
joint_positions- a vector of doubles corresponding 1-to-1 to the kinematic chain named in "jmg"
jmg- the set of joints to use, e.g. the MoveIt planning group, e.g. "left_arm"
color- how to highlight the robot (solid-ly) if desired, default keeps color as specified in URDF
Returns
true on success

Definition at line 1494 of file moveit_visual_tools.cpp.

◆ publishRobotState() [5/5]

bool moveit_visual_tools::MoveItVisualTools::publishRobotState ( const trajectory_msgs::JointTrajectoryPoint &  trajectory_pt,
const moveit::core::JointModelGroup jmg,
const rviz_visual_tools::colors color = rviz_visual_tools::DEFAULT 
)

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

Parameters
trajectory_ptof joint positions
jmg- the set of joints to use, e.g. the MoveIt planning group, e.g. "left_arm"
color- how to highlight the robot (solid-ly) if desired, default keeps color as specified in URDF
Returns
true on success

Definition at line 1487 of file moveit_visual_tools.cpp.

◆ publishTrajectoryLine() [1/6]

bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryLine ( const moveit_msgs::RobotTrajectory &  trajectory_msg,
const moveit::core::JointModelGroup arm_jmg,
const rviz_visual_tools::colors color = rviz_visual_tools::LIME_GREEN 
)

Display a line of the end effector(s) path(s) from a robot trajectory path This version can visualize multiple end effectors.

Parameters
trajectory_msg- the robot plan
arm_jmg- the set of joints to use, e.g. the MoveIt planning group, e.g. "left_arm".
color- display color of markers
Returns
true on success

Definition at line 1401 of file moveit_visual_tools.cpp.

◆ publishTrajectoryLine() [2/6]

bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryLine ( const moveit_msgs::RobotTrajectory &  trajectory_msg,
const moveit::core::LinkModel ee_parent_link,
const moveit::core::JointModelGroup arm_jmg,
const rviz_visual_tools::colors color = rviz_visual_tools::LIME_GREEN 
)

Display a line of the end effector path from a robot trajectory path.

Parameters
trajectory_msg- the robot plan
ee_parent_link- the link that we should trace a path of, e.g. the gripper link
arm_jmg- the set of joints to use, e.g. the MoveIt planning group, e.g. "left_arm"
color- display color of markers
Returns
true on success

Definition at line 1335 of file moveit_visual_tools.cpp.

◆ publishTrajectoryLine() [3/6]

bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryLine ( const robot_trajectory::RobotTrajectory robot_trajectory,
const moveit::core::JointModelGroup arm_jmg,
const rviz_visual_tools::colors color = rviz_visual_tools::LIME_GREEN 
)

Definition at line 1435 of file moveit_visual_tools.cpp.

◆ publishTrajectoryLine() [4/6]

bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryLine ( const robot_trajectory::RobotTrajectory robot_trajectory,
const moveit::core::LinkModel ee_parent_link,
const rviz_visual_tools::colors color = rviz_visual_tools::LIME_GREEN 
)

Definition at line 1365 of file moveit_visual_tools.cpp.

◆ publishTrajectoryLine() [5/6]

bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryLine ( const robot_trajectory::RobotTrajectoryPtr &  robot_trajectory,
const moveit::core::JointModelGroup arm_jmg,
const rviz_visual_tools::colors color = rviz_visual_tools::LIME_GREEN 
)

Definition at line 1428 of file moveit_visual_tools.cpp.

◆ publishTrajectoryLine() [6/6]

bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryLine ( const robot_trajectory::RobotTrajectoryPtr &  robot_trajectory,
const moveit::core::LinkModel ee_parent_link,
const rviz_visual_tools::colors color = rviz_visual_tools::LIME_GREEN 
)

Definition at line 1358 of file moveit_visual_tools.cpp.

◆ publishTrajectoryPath() [1/7]

void moveit_visual_tools::MoveItVisualTools::publishTrajectoryPath ( const moveit_msgs::DisplayTrajectory &  display_trajectory_msg)

Definition at line 1327 of file moveit_visual_tools.cpp.

◆ publishTrajectoryPath() [2/7]

bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryPath ( const moveit_msgs::RobotTrajectory &  trajectory_msg,
const moveit::core::RobotState robot_state,
bool  blocking = false 
)

Definition at line 1271 of file moveit_visual_tools.cpp.

◆ publishTrajectoryPath() [3/7]

bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryPath ( const moveit_msgs::RobotTrajectory &  trajectory_msg,
const moveit::core::RobotStateConstPtr &  robot_state,
bool  blocking = false 
)

Definition at line 1265 of file moveit_visual_tools.cpp.

◆ publishTrajectoryPath() [4/7]

bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryPath ( const moveit_msgs::RobotTrajectory &  trajectory_msg,
const moveit_msgs::RobotState &  robot_state,
bool  blocking = false 
)

Definition at line 1280 of file moveit_visual_tools.cpp.

◆ publishTrajectoryPath() [5/7]

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

Definition at line 1240 of file moveit_visual_tools.cpp.

◆ publishTrajectoryPath() [6/7]

bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryPath ( const robot_trajectory::RobotTrajectoryPtr &  trajectory,
bool  blocking = false 
)

Definition at line 1235 of file moveit_visual_tools.cpp.

◆ publishTrajectoryPath() [7/7]

bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryPath ( const std::vector< moveit::core::RobotStatePtr > &  trajectory,
const moveit::core::JointModelGroup jmg,
double  speed = 0.01,
bool  blocking = false 
)

Animate trajectory in rviz. These functions do not need a trigger() called because use different publisher.

Parameters
trajectorythe actual plan
blockingwhether we need to wait for the animation to complete
robot_state- the base state to add the joint trajectory message to
ee_jmg- the set of joints to use, e.g. the MoveIt planning group, e.g. "left_arm"
Returns
true on success

Definition at line 1206 of file moveit_visual_tools.cpp.

◆ publishTrajectoryPoint()

bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryPoint ( const trajectory_msgs::JointTrajectoryPoint &  trajectory_pt,
const std::string &  planning_group,
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
planning_group- 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 1177 of file moveit_visual_tools.cpp.

◆ publishTrajectoryPoints()

bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryPoints ( const std::vector< moveit::core::RobotStatePtr > &  robot_state_trajectory,
const moveit::core::LinkModel ee_parent_link,
const rviz_visual_tools::colors color = rviz_visual_tools::YELLOW 
)

Display trajectory as series of end effector position points.

Parameters
trajectorythe actual plan
color- display color of markers
Returns
true on success

Definition at line 1462 of file moveit_visual_tools.cpp.

◆ publishWorkspaceParameters()

bool moveit_visual_tools::MoveItVisualTools::publishWorkspaceParameters ( const moveit_msgs::WorkspaceParameters &  params)

Display size of workspace used for planning with OMPL, etc. Important for virtual joints.

Parameters
displaybounds of workspace
Returns
true on sucess

Definition at line 1096 of file moveit_visual_tools.cpp.

◆ removeAllCollisionObjects()

bool moveit_visual_tools::MoveItVisualTools::removeAllCollisionObjects ( )

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 618 of file moveit_visual_tools.cpp.

◆ setManualSceneUpdating()

void moveit_visual_tools::MoveItVisualTools::setManualSceneUpdating ( bool  enable_manual = true)
inline

Prevent the planning scene from always auto-pushing, but rather do it manually.

Parameters
booltrue to enable manual mode

Definition at line 251 of file moveit_visual_tools.h.

◆ setPlanningSceneMonitor()

void moveit_visual_tools::MoveItVisualTools::setPlanningSceneMonitor ( planning_scene_monitor::PlanningSceneMonitorPtr  psm)
inline

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 242 of file moveit_visual_tools.h.

◆ setPlanningSceneTopic()

void moveit_visual_tools::MoveItVisualTools::setPlanningSceneTopic ( const std::string &  planning_scene_topic)
inline

Set the planning scene topic.

Parameters
topic

Definition at line 152 of file moveit_visual_tools.h.

◆ setRobotStateTopic()

void moveit_visual_tools::MoveItVisualTools::setRobotStateTopic ( const std::string &  robot_state_topic)
inline

Set the ROS topic for publishing a robot state.

Parameters
topic

Definition at line 143 of file moveit_visual_tools.h.

◆ showJointLimits()

void moveit_visual_tools::MoveItVisualTools::showJointLimits ( const moveit::core::RobotStatePtr &  robot_state)

Print to console the current robot state's joint values within its limits visually.

Parameters
robot_state- the robot to show

Definition at line 1600 of file moveit_visual_tools.cpp.

◆ triggerPlanningSceneUpdate()

bool moveit_visual_tools::MoveItVisualTools::triggerPlanningSceneUpdate ( )

When mannual_trigger_update_ is true, use this to tell the planning scene to send an update out. Do not use otherwise.

Definition at line 231 of file moveit_visual_tools.cpp.

Member Data Documentation

◆ display_robot_msgs_

std::map<rviz_visual_tools::colors, moveit_msgs::DisplayRobotState> moveit_visual_tools::MoveItVisualTools::display_robot_msgs_
protected

Definition at line 759 of file moveit_visual_tools.h.

◆ ee_joint_pos_map_

std::map<const moveit::core::JointModelGroup*, std::vector<double> > moveit_visual_tools::MoveItVisualTools::ee_joint_pos_map_
protected

Definition at line 754 of file moveit_visual_tools.h.

◆ ee_markers_map_

std::map<const moveit::core::JointModelGroup*, visualization_msgs::MarkerArray> moveit_visual_tools::MoveItVisualTools::ee_markers_map_
protected

Definition at line 752 of file moveit_visual_tools.h.

◆ ee_poses_map_

std::map<const moveit::core::JointModelGroup*, EigenSTL::vector_Isometry3d> moveit_visual_tools::MoveItVisualTools::ee_poses_map_
protected

Definition at line 753 of file moveit_visual_tools.h.

◆ hidden_robot_state_

moveit::core::RobotStatePtr moveit_visual_tools::MoveItVisualTools::hidden_robot_state_
protected

Definition at line 768 of file moveit_visual_tools.h.

◆ mannual_trigger_update_

bool moveit_visual_tools::MoveItVisualTools::mannual_trigger_update_ = false
protected

Definition at line 739 of file moveit_visual_tools.h.

◆ planning_scene_topic_

std::string moveit_visual_tools::MoveItVisualTools::planning_scene_topic_
protected

Definition at line 743 of file moveit_visual_tools.h.

◆ psm_

planning_scene_monitor::PlanningSceneMonitorPtr moveit_visual_tools::MoveItVisualTools::psm_
protected

Definition at line 736 of file moveit_visual_tools.h.

◆ pub_display_path_

ros::Publisher moveit_visual_tools::MoveItVisualTools::pub_display_path_
protected

Definition at line 746 of file moveit_visual_tools.h.

◆ pub_robot_state_

ros::Publisher moveit_visual_tools::MoveItVisualTools::pub_robot_state_
protected

Definition at line 747 of file moveit_visual_tools.h.

◆ rm_loader_

robot_model_loader::RobotModelLoaderPtr moveit_visual_tools::MoveItVisualTools::rm_loader_
protected

Definition at line 749 of file moveit_visual_tools.h.

◆ robot_model_

moveit::core::RobotModelConstPtr moveit_visual_tools::MoveItVisualTools::robot_model_
protected

Definition at line 762 of file moveit_visual_tools.h.

◆ robot_state_root_offset_

Eigen::Isometry3d moveit_visual_tools::MoveItVisualTools::robot_state_root_offset_
protected

Definition at line 776 of file moveit_visual_tools.h.

◆ robot_state_root_offset_enabled_

bool moveit_visual_tools::MoveItVisualTools::robot_state_root_offset_enabled_ = false
protected

Definition at line 775 of file moveit_visual_tools.h.

◆ robot_state_topic_

std::string moveit_visual_tools::MoveItVisualTools::robot_state_topic_
protected

Definition at line 742 of file moveit_visual_tools.h.

◆ root_robot_state_

moveit::core::RobotStatePtr moveit_visual_tools::MoveItVisualTools::root_robot_state_
protected

Definition at line 772 of file moveit_visual_tools.h.

◆ shared_robot_state_

moveit::core::RobotStatePtr moveit_visual_tools::MoveItVisualTools::shared_robot_state_
protected

Definition at line 765 of file moveit_visual_tools.h.


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


moveit_visual_tools
Author(s): Dave Coleman
autogenerated on Fri May 19 2023 02:14:04