40 #ifndef MOVEIT_VISUAL_TOOLS_MOVEIT_VISUAL_TOOLS_H 41 #define MOVEIT_VISUAL_TOOLS_MOVEIT_VISUAL_TOOLS_H 52 #include <moveit_msgs/Grasp.h> 53 #include <moveit_msgs/DisplayRobotState.h> 54 #include <moveit_msgs/WorkspaceParameters.h> 57 #include <trajectory_msgs/JointTrajectory.h> 69 "/move_group/display_planned_path";
71 "display_robot_state";
85 planning_scene_monitor::PlanningSceneMonitorPtr psm);
95 robot_model::RobotModelConstPtr robot_model = robot_model::RobotModelConstPtr());
187 bool loadEEMarker(
const robot_model::JointModelGroup* ee_jmg,
const std::vector<double>& ee_joint_pos = {});
192 void loadTrajectoryPub(
const std::string& display_planned_path_topic = DISPLAY_PLANNED_PATH_TOPIC,
193 bool blocking =
true);
194 void loadRobotStatePub(
const std::string& robot_state_topic =
"",
bool blocking =
true);
222 bool publishEEMarkers(
const Eigen::Affine3d& pose,
const robot_model::JointModelGroup* ee_jmg,
223 const std::vector<double>& ee_joint_pos,
225 const std::string& ns =
"end_effector")
229 bool publishEEMarkers(
const Eigen::Affine3d& pose,
const robot_model::JointModelGroup* ee_jmg,
231 const std::string& ns =
"end_effector")
235 bool publishEEMarkers(
const geometry_msgs::Pose& pose,
const robot_model::JointModelGroup* ee_jmg,
237 const std::string& ns =
"end_effector")
241 bool publishEEMarkers(
const geometry_msgs::Pose& pose,
const robot_model::JointModelGroup* ee_jmg,
242 const std::vector<double>& ee_joint_pos,
244 const std::string& ns =
"end_effector");
252 bool publishGrasps(
const std::vector<moveit_msgs::Grasp>& possible_grasps,
const robot_model::JointModelGroup* ee_jmg,
253 double animate_speed = 0.1);
262 const robot_model::JointModelGroup* ee_jmg,
double animate_speed = 0.01);
271 bool publishAnimatedGrasp(
const moveit_msgs::Grasp& grasp,
const robot_model::JointModelGroup* ee_jmg,
272 double animate_speed);
281 bool publishIKSolutions(
const std::vector<trajectory_msgs::JointTrajectoryPoint>& ik_solutions,
282 const robot_model::JointModelGroup* arm_jmg,
double display_time = 0.4);
312 bool attachCO(
const std::string& name,
const std::string& ee_parent_link);
332 bool publishCollisionBlock(
const geometry_msgs::Pose& block_pose,
const std::string& block_name =
"block",
333 double block_size = 0.1,
344 bool publishCollisionCuboid(
const Eigen::Vector3d& point1,
const Eigen::Vector3d& point2,
const std::string& name,
347 const std::string& name,
376 const std::string& object_name,
double radius,
392 bool publishCollisionCylinder(
const geometry_msgs::Pose& object_pose,
const std::string& object_name,
double radius,
403 bool publishCollisionMesh(
const geometry_msgs::Pose& object_pose,
const std::string& object_name,
404 const std::string& mesh_path,
407 const std::string& mesh_path,
410 const shape_msgs::Mesh& mesh_msg,
412 bool publishCollisionMesh(
const geometry_msgs::Pose& object_pose,
const std::string& object_name,
413 const shape_msgs::Mesh& mesh_msg,
423 bool publishCollisionGraph(
const graph_msgs::GeometryGraph& graph,
const std::string& object_name,
double radius,
430 const std::string name, moveit_msgs::CollisionObject& collision_obj);
443 bool publishCollisionWall(
double x,
double y,
double angle = 0.0,
double width = 2.0,
double height = 1.5,
444 const std::string name =
"wall",
446 bool publishCollisionWall(
double x,
double y,
double z,
double angle = 0.0,
double width = 2.0,
double height = 1.5,
447 const std::string name =
"wall",
469 bool publishCollisionTable(
double x,
double y,
double z,
double angle,
double width,
double height,
double depth,
511 const std::string& planning_group,
double display_time = 0.1);
523 bool publishTrajectoryPath(
const robot_trajectory::RobotTrajectoryPtr& trajectory,
bool blocking =
false);
526 const moveit::core::RobotStateConstPtr robot_state,
bool blocking =
false);
530 const moveit_msgs::RobotState& robot_state,
bool blocking =
false);
559 const robot_model::JointModelGroup* arm_jmg,
562 const robot_model::JointModelGroup* arm_jmg,
565 const robot_model::JointModelGroup* arm_jmg,
591 bool publishRobotState(
const trajectory_msgs::JointTrajectoryPoint& trajectory_pt,
592 const robot_model::JointModelGroup* jmg,
602 bool publishRobotState(
const std::vector<double> joint_positions,
const robot_model::JointModelGroup* jmg,
646 planning_scene_monitor::PlanningSceneMonitorPtr
psm_;
662 std::map<const robot_model::JointModelGroup*, visualization_msgs::MarkerArray>
ee_markers_map_;
663 std::map<const robot_model::JointModelGroup*, EigenSTL::vector_Affine3d>
ee_poses_map_;
697 #endif // MOVEIT_VISUAL_TOOLS_MOVEIT_VISUAL_TOOLS_H
#define RVIZ_VISUAL_TOOLS_DEPRECATED
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")