#include <moveit_visual_tools.h>
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 (const std::string &name) |
Remove a collision object from the planning scene. | |
void | getCollisionWallMsg (double x, double y, double angle, double width, const std::string name, moveit_msgs::CollisionObject &collision_obj) |
Helper for publishCollisionWall. | |
moveit::core::RobotModelConstPtr | getRobotModel () |
Get a pointer to the robot model. | |
moveit::core::RobotStatePtr & | getSharedRobotState () |
Allow robot state to be altered. | |
bool | hideRobot () |
Fake removing a Robot State display in Rviz by simply moving it very far away. | |
bool | loadCollisionSceneFromFile (const std::string &path) |
Load a planning scene to a planning_scene_monitor from file. | |
bool | loadCollisionSceneFromFile (const std::string &path, const Eigen::Affine3d &offset) |
RVIZ_VISUAL_TOOLS_DEPRECATED bool | loadEEMarker (const std::string &ee_group_name) |
Call this once at begining to load the robot marker. | |
bool | loadEEMarker (const robot_model::JointModelGroup *ee_jmg) |
Call this once at begining to load the robot marker. | |
bool | loadPlanningSceneMonitor () |
Load a planning scene monitor if one was not passed into the constructor. | |
void | loadRobotStatePub (const std::string &robot_state_topic="") |
bool | loadSharedRobotState () |
Load robot state only as needed. | |
void | loadTrajectoryPub (const std::string &display_planned_path_topic=DISPLAY_PLANNED_PATH_TOPIC) |
Load publishers as needed. | |
MoveItVisualTools (const std::string &base_frame, const std::string &marker_topic, planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor) | |
Constructor. | |
MoveItVisualTools (const std::string &base_frame, const std::string &marker_topic=rviz_visual_tools::RVIZ_MARKER_TOPIC, robot_model::RobotModelConstPtr robot_model=robot_model::RobotModelConstPtr()) | |
Constructor. | |
bool | processAttachedCollisionObjectMsg (const moveit_msgs::AttachedCollisionObject &msg) |
Skip a ROS message call by sending directly to planning scene monitor. | |
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. | |
bool | publishAnimatedGrasp (const moveit_msgs::Grasp &grasp, const robot_model::JointModelGroup *ee_jmg, double animate_speed) |
Animate a single grasp in its movement direction. | |
bool | publishAnimatedGrasps (const std::vector< moveit_msgs::Grasp > &possible_grasps, const robot_model::JointModelGroup *ee_jmg, double animate_speed=0.01) |
Display an animated vector of grasps including its approach movement in Rviz. | |
bool | publishCollisionBlock (const geometry_msgs::Pose &block_pose, const std::string &block_name, double block_size, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN) |
Create a MoveIt Collision block at the given pose. | |
bool | publishCollisionCuboid (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const std::string &name, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN) |
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 | 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. | |
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 Eigen::Affine3d &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. | |
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. | |
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. | |
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. | |
bool | publishCollisionMesh (const Eigen::Affine3d &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 Eigen::Affine3d &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 shape_msgs::Mesh &mesh_msg, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN) |
RVIZ_VISUAL_TOOLS_DEPRECATED bool | publishCollisionRectangle (const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const std::string &name, const rviz_visual_tools::colors &color) |
Create a MoveIt collision rectangular cuboid at the given pose. | |
RVIZ_VISUAL_TOOLS_DEPRECATED bool | publishCollisionRectangle (const geometry_msgs::Point &point1, const geometry_msgs::Point &point2, const std::string &name, const rviz_visual_tools::colors &color) |
bool | publishCollisionTable (double x, double y, 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. | |
RVIZ_VISUAL_TOOLS_DEPRECATED bool | publishCollisionTests () |
Simple tests for collision testing. | |
bool | publishCollisionWall (double x, double y, double angle, double width, const std::string name, const rviz_visual_tools::colors &color=rviz_visual_tools::GREEN) |
Publish a typical room wall. | |
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. | |
bool | publishEEMarkers (const Eigen::Affine3d &pose, const robot_model::JointModelGroup *ee_jmg, const rviz_visual_tools::colors &color=rviz_visual_tools::CLEAR, const std::string &ns="end_effector") |
Publish an end effector to rviz. | |
bool | publishEEMarkers (const geometry_msgs::Pose &pose, const robot_model::JointModelGroup *ee_jmg, const rviz_visual_tools::colors &color=rviz_visual_tools::CLEAR, const std::string &ns="end_effector") |
bool | publishGrasps (const std::vector< moveit_msgs::Grasp > &possible_grasps, const robot_model::JointModelGroup *ee_jmg, double animate_speed=0.1) |
Show grasps generated from moveit_simple_grasps or other MoveIt Grasp message sources. | |
bool | publishIKSolutions (const std::vector< trajectory_msgs::JointTrajectoryPoint > &ik_solutions, const robot_model::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. | |
bool | publishRobotState (const robot_state::RobotState &robot_state, const rviz_visual_tools::colors &color=rviz_visual_tools::DEFAULT) |
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, const rviz_visual_tools::colors &color=rviz_visual_tools::DEFAULT) |
bool | publishRobotState (const trajectory_msgs::JointTrajectoryPoint &trajectory_pt, const robot_model::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. | |
bool | publishTrajectoryLine (const moveit_msgs::RobotTrajectory &trajectory_msg, const moveit::core::LinkModel *ee_parent_link, const robot_model::JointModelGroup *arm_jmg, const rviz_visual_tools::colors &color, bool clear_all_markers=false) |
Display a line of the end effector path from a robot trajectory path. | |
bool | publishTrajectoryLine (const robot_trajectory::RobotTrajectoryPtr robot_trajectory, const moveit::core::LinkModel *ee_parent_link, const rviz_visual_tools::colors &color, bool clear_all_markers) |
bool | publishTrajectoryPath (const std::vector< robot_state::RobotStatePtr > &trajectory, const moveit::core::JointModelGroup *jmg, double speed=0.01, bool blocking=false) |
Animate trajectory in rviz. | |
bool | publishTrajectoryPath (const robot_trajectory::RobotTrajectory &trajectory, bool blocking=false) |
bool | publishTrajectoryPath (const moveit_msgs::RobotTrajectory &trajectory_msg, const robot_state::RobotStateConstPtr robot_state, bool blocking) |
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. | |
bool | publishTrajectoryPoints (const std::vector< robot_state::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. | |
bool | publishWorkspaceParameters (const moveit_msgs::WorkspaceParameters ¶ms) |
Display size of workspace used for planning with OMPL, etc. Important for virtual joints. | |
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. | |
void | setManualSceneUpdating (bool enable_manual) |
Prevent the planning scene from always auto-pushing, but rather do it manually. | |
void | setPlanningSceneMonitor (planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor) |
Allow a pre-configured planning scene monitor to be set for publishing collision objects, etc. | |
void | setPlanningSceneTopic (const std::string &planning_scene_topic) |
Set the planning scene topic. | |
void | setRobotStateTopic (const std::string &robot_state_topic) |
Set the ROS topic for publishing a robot state. | |
bool | triggerPlanningSceneUpdate () |
When mannual_trigger_update_ is true, use this to tell the planning scene to send an update out. Do not use otherwise. | |
~MoveItVisualTools () | |
Deconstructor. | |
Protected Attributes | |
std::map < rviz_visual_tools::colors, moveit_msgs::DisplayRobotState > | display_robot_msgs_ |
std::map< const robot_model::JointModelGroup *, visualization_msgs::MarkerArray > | ee_markers_map_ |
std::map< const robot_model::JointModelGroup *, EigenSTL::vector_Affine3d > | ee_poses_map_ |
robot_state::RobotStatePtr | hidden_robot_state_ |
bool | mannual_trigger_update_ |
std::string | name_ |
planning_scene_monitor::PlanningSceneMonitorPtr | planning_scene_monitor_ |
std::string | planning_scene_topic_ |
ros::Publisher | pub_display_path_ |
ros::Publisher | pub_robot_state_ |
robot_model_loader::RobotModelLoaderPtr | rm_loader_ |
robot_state::RobotModelConstPtr | robot_model_ |
std::string | robot_state_topic_ |
robot_state::RobotStatePtr | shared_robot_state_ |
Private Member Functions | |
planning_scene_monitor::PlanningSceneMonitorPtr | getPlanningSceneMonitor () |
Get the planning scene monitor that this class is using. |
Definition at line 71 of file moveit_visual_tools.h.
moveit_visual_tools::MoveItVisualTools::MoveItVisualTools | ( | const std::string & | base_frame, |
const std::string & | marker_topic, | ||
planning_scene_monitor::PlanningSceneMonitorPtr | planning_scene_monitor | ||
) |
Constructor.
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 moveit_visual_tools.cpp.
moveit_visual_tools::MoveItVisualTools::MoveItVisualTools | ( | const std::string & | base_frame, |
const std::string & | marker_topic = rviz_visual_tools::RVIZ_MARKER_TOPIC , |
||
robot_model::RobotModelConstPtr | robot_model = robot_model::RobotModelConstPtr() |
||
) |
Constructor.
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 70 of file moveit_visual_tools.cpp.
Deconstructor.
Definition at line 97 of file moveit_visual_tools.h.
bool moveit_visual_tools::MoveItVisualTools::attachCO | ( | const std::string & | name, |
const std::string & | ee_parent_link | ||
) |
Attach a collision object from the planning scene.
Name | of object |
\return | true on sucess |
Definition at line 595 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::cleanupACO | ( | const std::string & | name | ) |
Remove an active collision object from the planning scene.
Name | of object |
Definition at line 582 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::cleanupCO | ( | const std::string & | name | ) |
Remove a collision object from the planning scene.
Name | of object |
Definition at line 570 of file moveit_visual_tools.cpp.
void moveit_visual_tools::MoveItVisualTools::getCollisionWallMsg | ( | double | x, |
double | y, | ||
double | angle, | ||
double | width, | ||
const std::string | name, | ||
moveit_msgs::CollisionObject & | collision_obj | ||
) |
Helper for publishCollisionWall.
Definition at line 899 of file moveit_visual_tools.cpp.
planning_scene_monitor::PlanningSceneMonitorPtr moveit_visual_tools::MoveItVisualTools::getPlanningSceneMonitor | ( | ) | [private] |
Get the planning scene monitor that this class is using.
Definition at line 316 of file moveit_visual_tools.cpp.
moveit::core::RobotModelConstPtr moveit_visual_tools::MoveItVisualTools::getRobotModel | ( | ) |
Get a pointer to the robot model.
Definition at line 203 of file moveit_visual_tools.cpp.
moveit::core::RobotStatePtr & moveit_visual_tools::MoveItVisualTools::getSharedRobotState | ( | ) |
Allow robot state to be altered.
Definition at line 196 of file moveit_visual_tools.cpp.
Fake removing a Robot State display in Rviz by simply moving it very far away.
Definition at line 1370 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::loadCollisionSceneFromFile | ( | const std::string & | path | ) |
Load a planning scene to a planning_scene_monitor from file.
path | - path to planning scene, e.g. as exported from Rviz Plugin |
offset | for scene to be placed |
Definition at line 993 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::loadCollisionSceneFromFile | ( | const std::string & | path, |
const Eigen::Affine3d & | offset | ||
) |
Definition at line 998 of file moveit_visual_tools.cpp.
RVIZ_VISUAL_TOOLS_DEPRECATED bool moveit_visual_tools::MoveItVisualTools::loadEEMarker | ( | const std::string & | ee_group_name | ) | [inline] |
Call this once at begining to load the robot marker.
ee_group_name | - name of planning_group for the end effector |
Definition at line 169 of file moveit_visual_tools.h.
bool moveit_visual_tools::MoveItVisualTools::loadEEMarker | ( | const robot_model::JointModelGroup * | ee_jmg | ) |
Call this once at begining to load the robot marker.
ee_jmg | - the set of joints to use, e.g. the MoveIt! planning group, e.g. "left_arm" |
Definition at line 210 of file moveit_visual_tools.cpp.
Load a planning scene monitor if one was not passed into the constructor.
Definition at line 78 of file moveit_visual_tools.cpp.
void moveit_visual_tools::MoveItVisualTools::loadRobotStatePub | ( | const std::string & | robot_state_topic = "" | ) |
Definition at line 298 of file moveit_visual_tools.cpp.
Load robot state only as needed.
Definition at line 171 of file moveit_visual_tools.cpp.
void moveit_visual_tools::MoveItVisualTools::loadTrajectoryPub | ( | const std::string & | display_planned_path_topic = DISPLAY_PLANNED_PATH_TOPIC | ) |
Load publishers as needed.
Definition at line 283 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::processAttachedCollisionObjectMsg | ( | const moveit_msgs::AttachedCollisionObject & | msg | ) |
Skip a ROS message call by sending directly to planning scene monitor.
attached | collision object message |
Definition at line 144 of file moveit_visual_tools.cpp.
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.
collision | object message |
color | to display the collision object with |
Definition at line 125 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishAnimatedGrasp | ( | const moveit_msgs::Grasp & | grasp, |
const robot_model::JointModelGroup * | ee_jmg, | ||
double | animate_speed | ||
) |
Animate a single grasp in its movement direction.
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 |
Definition at line 426 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishAnimatedGrasps | ( | const std::vector< moveit_msgs::Grasp > & | possible_grasps, |
const robot_model::JointModelGroup * | ee_jmg, | ||
double | animate_speed = 0.01 |
||
) |
Display an animated vector of grasps including its approach movement in Rviz.
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 404 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishCollisionBlock | ( | const geometry_msgs::Pose & | block_pose, |
const std::string & | block_name, | ||
double | block_size, | ||
const rviz_visual_tools::colors & | color = rviz_visual_tools::GREEN |
||
) |
Create a MoveIt Collision block at the given pose.
pose | - location of center of block |
name | - semantic name of MoveIt collision object |
size | - height=width=depth=size |
color | to display the collision object with |
Definition at line 611 of file moveit_visual_tools.cpp.
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 |
||
) |
Definition at line 636 of file moveit_visual_tools.cpp.
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 644 of file moveit_visual_tools.cpp.
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.
point | a - x,y,z in space of a point |
point | b - x,y,z in space of a point |
name | - semantic name of MoveIt collision object |
radius | - size of cylinder |
color | to display the collision object with |
Definition at line 707 of file moveit_visual_tools.cpp.
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 715 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishCollisionCylinder | ( | const Eigen::Affine3d & | 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.
pose | - vector pointing along axis of cylinder |
name | - semantic name of MoveIt collision object |
radius | - size of cylinder |
height | - size of cylinder |
color | to display the collision object with |
Definition at line 737 of file moveit_visual_tools.cpp.
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 745 of file moveit_visual_tools.cpp.
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.
z | location of floor |
name | of floor |
color | to display the collision object with |
Definition at line 688 of file moveit_visual_tools.cpp.
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.
graph | of nodes and edges |
name | of collision object |
color | to display the collision object with |
Definition at line 826 of file moveit_visual_tools.cpp.
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.
pose | - location of center of mesh |
name | - semantic name of MoveIt collision object |
peth | - file location to an .stl file |
color | to display the collision object with |
Definition at line 776 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishCollisionMesh | ( | const Eigen::Affine3d & | 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 768 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishCollisionMesh | ( | const Eigen::Affine3d & | 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 799 of file moveit_visual_tools.cpp.
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 807 of file moveit_visual_tools.cpp.
RVIZ_VISUAL_TOOLS_DEPRECATED bool moveit_visual_tools::MoveItVisualTools::publishCollisionRectangle | ( | const Eigen::Vector3d & | point1, |
const Eigen::Vector3d & | point2, | ||
const std::string & | name, | ||
const rviz_visual_tools::colors & | color | ||
) | [inline] |
Create a MoveIt collision rectangular cuboid at the given pose.
point1 | - top left of rectangle |
point2 | - bottom right of rectangle |
name | - semantic name of MoveIt collision object |
color | to display the collision object with |
Definition at line 319 of file moveit_visual_tools.h.
RVIZ_VISUAL_TOOLS_DEPRECATED bool moveit_visual_tools::MoveItVisualTools::publishCollisionRectangle | ( | const geometry_msgs::Point & | point1, |
const geometry_msgs::Point & | point2, | ||
const std::string & | name, | ||
const rviz_visual_tools::colors & | color | ||
) | [inline] |
Definition at line 325 of file moveit_visual_tools.h.
bool moveit_visual_tools::MoveItVisualTools::publishCollisionTable | ( | double | x, |
double | y, | ||
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.
x | |
y | |
angle | |
width | |
height | |
depth | |
name | |
color | to display the collision object with |
Definition at line 953 of file moveit_visual_tools.cpp.
Simple tests for collision testing.
Definition at line 1028 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishCollisionWall | ( | double | x, |
double | y, | ||
double | angle, | ||
double | width, | ||
const std::string | name, | ||
const rviz_visual_tools::colors & | color = rviz_visual_tools::GREEN |
||
) |
Publish a typical room wall.
x | |
y | |
angle | |
width | |
name | |
color | to display the collision object with |
Definition at line 943 of file moveit_visual_tools.cpp.
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.
robot_state | |
planning_scene | |
color | - display color of markers |
Definition at line 1036 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishEEMarkers | ( | const Eigen::Affine3d & | pose, |
const robot_model::JointModelGroup * | ee_jmg, | ||
const rviz_visual_tools::colors & | color = rviz_visual_tools::CLEAR , |
||
const std::string & | ns = "end_effector" |
||
) | [inline] |
Publish an end effector to rviz.
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" |
color | to display the collision object with |
Definition at line 211 of file moveit_visual_tools.h.
bool moveit_visual_tools::MoveItVisualTools::publishEEMarkers | ( | const geometry_msgs::Pose & | pose, |
const robot_model::JointModelGroup * | ee_jmg, | ||
const rviz_visual_tools::colors & | color = rviz_visual_tools::CLEAR , |
||
const std::string & | ns = "end_effector" |
||
) |
Definition at line 329 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishGrasps | ( | const std::vector< moveit_msgs::Grasp > & | possible_grasps, |
const robot_model::JointModelGroup * | ee_jmg, | ||
double | animate_speed = 0.1 |
||
) |
Show grasps generated from moveit_simple_grasps or other MoveIt Grasp message sources.
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 382 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishIKSolutions | ( | const std::vector< trajectory_msgs::JointTrajectoryPoint > & | ik_solutions, |
const robot_model::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.
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 514 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishRobotState | ( | const robot_state::RobotState & | robot_state, |
const rviz_visual_tools::colors & | color = rviz_visual_tools::DEFAULT |
||
) |
Publish a complete robot state to Rviz To use, add a RobotState marker to Rviz and subscribe to the DISPLAY_ROBOT_STATE_TOPIC, above.
robot_state | - joint values of robot |
color | - how to highlight the robot (solid-ly) if desired, default keeps color as specified in URDF |
Definition at line 1287 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishRobotState | ( | const robot_state::RobotStatePtr & | robot_state, |
const rviz_visual_tools::colors & | color = rviz_visual_tools::DEFAULT |
||
) |
Definition at line 1281 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishRobotState | ( | const trajectory_msgs::JointTrajectoryPoint & | trajectory_pt, |
const robot_model::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.
trajectory_pt | of 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 |
Definition at line 1353 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryLine | ( | const moveit_msgs::RobotTrajectory & | trajectory_msg, |
const moveit::core::LinkModel * | ee_parent_link, | ||
const robot_model::JointModelGroup * | arm_jmg, | ||
const rviz_visual_tools::colors & | color, | ||
bool | clear_all_markers = false |
||
) |
Display a line of the end effector path from a robot trajectory path.
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 |
clear_all_markers | - optionally ability to delete all existing markers in Rviz before adding the trajectory path |
Definition at line 1199 of file moveit_visual_tools.cpp.
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, | ||
bool | clear_all_markers | ||
) |
Definition at line 1223 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryPath | ( | const std::vector< robot_state::RobotStatePtr > & | trajectory, |
const moveit::core::JointModelGroup * | jmg, | ||
double | speed = 0.01 , |
||
bool | blocking = false |
||
) |
Animate trajectory in rviz.
trajectory | the actual plan |
blocking | whether 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" |
Definition at line 1106 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryPath | ( | const robot_trajectory::RobotTrajectory & | trajectory, |
bool | blocking = false |
||
) |
Definition at line 1129 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryPath | ( | const moveit_msgs::RobotTrajectory & | trajectory_msg, |
const robot_state::RobotStateConstPtr | robot_state, | ||
bool | blocking | ||
) |
Definition at line 1151 of file moveit_visual_tools.cpp.
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.
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" |
Definition at line 1078 of file moveit_visual_tools.cpp.
bool moveit_visual_tools::MoveItVisualTools::publishTrajectoryPoints | ( | const std::vector< robot_state::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.
trajectory | the actual plan |
color | - display color of markers |
Definition at line 1266 of file moveit_visual_tools.cpp.
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.
display | bounds of workspace |
Definition at line 1030 of file moveit_visual_tools.cpp.
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.
the | scene to directly clear the collision objects from |
Definition at line 559 of file moveit_visual_tools.cpp.
void moveit_visual_tools::MoveItVisualTools::setManualSceneUpdating | ( | bool | enable_manual | ) | [inline] |
Prevent the planning scene from always auto-pushing, but rather do it manually.
bool | true to enable manual mode |
Definition at line 199 of file moveit_visual_tools.h.
void moveit_visual_tools::MoveItVisualTools::setPlanningSceneMonitor | ( | planning_scene_monitor::PlanningSceneMonitorPtr | planning_scene_monitor | ) | [inline] |
Allow a pre-configured planning scene monitor to be set for publishing collision objects, etc.
a | pointer to a load planning scen |
Definition at line 190 of file moveit_visual_tools.h.
void moveit_visual_tools::MoveItVisualTools::setPlanningSceneTopic | ( | const std::string & | planning_scene_topic | ) | [inline] |
Set the planning scene topic.
topic |
Definition at line 112 of file moveit_visual_tools.h.
void moveit_visual_tools::MoveItVisualTools::setRobotStateTopic | ( | const std::string & | robot_state_topic | ) | [inline] |
Set the ROS topic for publishing a robot state.
topic |
Definition at line 103 of file moveit_visual_tools.h.
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 163 of file moveit_visual_tools.cpp.
std::map<rviz_visual_tools::colors, moveit_msgs::DisplayRobotState> moveit_visual_tools::MoveItVisualTools::display_robot_msgs_ [protected] |
Definition at line 573 of file moveit_visual_tools.h.
std::map<const robot_model::JointModelGroup *, visualization_msgs::MarkerArray> moveit_visual_tools::MoveItVisualTools::ee_markers_map_ [protected] |
Definition at line 567 of file moveit_visual_tools.h.
std::map<const robot_model::JointModelGroup *, EigenSTL::vector_Affine3d> moveit_visual_tools::MoveItVisualTools::ee_poses_map_ [protected] |
Definition at line 568 of file moveit_visual_tools.h.
robot_state::RobotStatePtr moveit_visual_tools::MoveItVisualTools::hidden_robot_state_ [protected] |
Definition at line 582 of file moveit_visual_tools.h.
bool moveit_visual_tools::MoveItVisualTools::mannual_trigger_update_ [protected] |
Definition at line 585 of file moveit_visual_tools.h.
std::string moveit_visual_tools::MoveItVisualTools::name_ [protected] |
Reimplemented from rviz_visual_tools::RvizVisualTools.
Definition at line 556 of file moveit_visual_tools.h.
planning_scene_monitor::PlanningSceneMonitorPtr moveit_visual_tools::MoveItVisualTools::planning_scene_monitor_ [protected] |
Definition at line 563 of file moveit_visual_tools.h.
std::string moveit_visual_tools::MoveItVisualTools::planning_scene_topic_ [protected] |
Definition at line 589 of file moveit_visual_tools.h.
Definition at line 559 of file moveit_visual_tools.h.
Definition at line 560 of file moveit_visual_tools.h.
robot_model_loader::RobotModelLoaderPtr moveit_visual_tools::MoveItVisualTools::rm_loader_ [protected] |
Definition at line 564 of file moveit_visual_tools.h.
robot_state::RobotModelConstPtr moveit_visual_tools::MoveItVisualTools::robot_model_ [protected] |
Definition at line 576 of file moveit_visual_tools.h.
std::string moveit_visual_tools::MoveItVisualTools::robot_state_topic_ [protected] |
Definition at line 588 of file moveit_visual_tools.h.
robot_state::RobotStatePtr moveit_visual_tools::MoveItVisualTools::shared_robot_state_ [protected] |
Definition at line 579 of file moveit_visual_tools.h.