00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042 #ifndef MOVEIT_VISUAL_TOOLS__MOVEIT_VISUAL_TOOLS_H_
00043 #define MOVEIT_VISUAL_TOOLS__MOVEIT_VISUAL_TOOLS_H_
00044
00045
00046 #include <rviz_visual_tools/rviz_visual_tools.h>
00047
00048
00049 #include <moveit/planning_scene_monitor/planning_scene_monitor.h>
00050
00051 #include <rviz_visual_tools/deprecation.h>
00052
00053
00054 #include <moveit_msgs/Grasp.h>
00055 #include <moveit_msgs/DisplayRobotState.h>
00056 #include <moveit_msgs/WorkspaceParameters.h>
00057
00058
00059 #include <trajectory_msgs/JointTrajectory.h>
00060
00061 namespace moveit_visual_tools
00062 {
00063
00064 static const std::string ROBOT_DESCRIPTION = "robot_description";
00065 static const std::string DISPLAY_PLANNED_PATH_TOPIC =
00066 "/move_group/display_planned_path";
00067 static const std::string DISPLAY_ROBOT_STATE_TOPIC =
00068 "display_robot_state";
00069 static const std::string PLANNING_SCENE_TOPIC = "planning_scene";
00070
00071 class MoveItVisualTools : public rviz_visual_tools::RvizVisualTools
00072 {
00073 public:
00081 MoveItVisualTools(const std::string &base_frame, const std::string &marker_topic,
00082 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor);
00083
00090 MoveItVisualTools(const std::string &base_frame,
00091 const std::string &marker_topic = rviz_visual_tools::RVIZ_MARKER_TOPIC,
00092 robot_model::RobotModelConstPtr robot_model = robot_model::RobotModelConstPtr());
00093
00097 ~MoveItVisualTools(){};
00098
00103 void setRobotStateTopic(const std::string &robot_state_topic)
00104 {
00105 robot_state_topic_ = robot_state_topic;
00106 }
00107
00112 void setPlanningSceneTopic(const std::string &planning_scene_topic)
00113 {
00114 planning_scene_topic_ = planning_scene_topic;
00115 }
00116
00121 bool loadPlanningSceneMonitor();
00122
00129 bool processCollisionObjectMsg(const moveit_msgs::CollisionObject &msg,
00130 const rviz_visual_tools::colors &color = rviz_visual_tools::GREEN);
00131
00137 bool processAttachedCollisionObjectMsg(const moveit_msgs::AttachedCollisionObject &msg);
00138
00143 bool triggerPlanningSceneUpdate();
00144
00149 bool loadSharedRobotState();
00150
00155 moveit::core::RobotStatePtr &getSharedRobotState();
00156
00161 moveit::core::RobotModelConstPtr getRobotModel();
00162
00168 RVIZ_VISUAL_TOOLS_DEPRECATED
00169 bool loadEEMarker(const std::string &ee_group_name)
00170 {
00171 return loadEEMarker(robot_model_->getJointModelGroup(ee_group_name));
00172 }
00178 bool loadEEMarker(const robot_model::JointModelGroup *ee_jmg);
00179
00183 void loadTrajectoryPub(const std::string &display_planned_path_topic = DISPLAY_PLANNED_PATH_TOPIC);
00184 void loadRobotStatePub(const std::string &robot_state_topic = "");
00185
00190 void setPlanningSceneMonitor(planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor)
00191 {
00192 planning_scene_monitor_ = planning_scene_monitor;
00193 }
00194
00199 void setManualSceneUpdating(bool enable_manual)
00200 {
00201 mannual_trigger_update_ = enable_manual;
00202 }
00203
00211 bool publishEEMarkers(const Eigen::Affine3d &pose, const robot_model::JointModelGroup *ee_jmg,
00212 const rviz_visual_tools::colors &color = rviz_visual_tools::CLEAR,
00213 const std::string &ns = "end_effector")
00214 {
00215 return publishEEMarkers(convertPose(pose), ee_jmg, color, ns);
00216 }
00217 bool publishEEMarkers(const geometry_msgs::Pose &pose, const robot_model::JointModelGroup *ee_jmg,
00218 const rviz_visual_tools::colors &color = rviz_visual_tools::CLEAR,
00219 const std::string &ns = "end_effector");
00220
00227 bool publishGrasps(const std::vector<moveit_msgs::Grasp> &possible_grasps, const robot_model::JointModelGroup *ee_jmg,
00228 double animate_speed = 0.1);
00229
00236 bool publishAnimatedGrasps(const std::vector<moveit_msgs::Grasp> &possible_grasps,
00237 const robot_model::JointModelGroup *ee_jmg, double animate_speed = 0.01);
00238
00246 bool publishAnimatedGrasp(const moveit_msgs::Grasp &grasp, const robot_model::JointModelGroup *ee_jmg,
00247 double animate_speed);
00248
00256 bool publishIKSolutions(const std::vector<trajectory_msgs::JointTrajectoryPoint> &ik_solutions,
00257 const robot_model::JointModelGroup *arm_jmg, double display_time = 0.4);
00258
00265 bool removeAllCollisionObjects();
00266
00272 bool cleanupCO(const std::string &name);
00273
00279 bool cleanupACO(const std::string &name);
00280
00287 bool attachCO(const std::string &name, const std::string &ee_parent_link);
00288
00296 bool publishCollisionFloor(double z = 0.0, const std::string &plane_name = "Floor",
00297 const rviz_visual_tools::colors &color = rviz_visual_tools::GREEN);
00298
00307 bool publishCollisionBlock(const geometry_msgs::Pose &block_pose, const std::string &block_name, double block_size,
00308 const rviz_visual_tools::colors &color = rviz_visual_tools::GREEN);
00309
00318 RVIZ_VISUAL_TOOLS_DEPRECATED
00319 bool publishCollisionRectangle(const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const std::string &name,
00320 const rviz_visual_tools::colors &color)
00321 {
00322 return publishCollisionCuboid(convertPoint(point1), convertPoint(point2), name, color);
00323 }
00324 RVIZ_VISUAL_TOOLS_DEPRECATED
00325 bool publishCollisionRectangle(const geometry_msgs::Point &point1, const geometry_msgs::Point &point2,
00326 const std::string &name, const rviz_visual_tools::colors &color)
00327 {
00328 return publishCollisionCuboid(convertPoint(point1), convertPoint(point2), name, color);
00329 }
00330 bool publishCollisionCuboid(const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const std::string &name,
00331 const rviz_visual_tools::colors &color = rviz_visual_tools::GREEN);
00332 bool publishCollisionCuboid(const geometry_msgs::Point &point1, const geometry_msgs::Point &point2,
00333 const std::string &name,
00334 const rviz_visual_tools::colors &color = rviz_visual_tools::GREEN);
00335
00345 bool publishCollisionCylinder(const geometry_msgs::Point &a, const geometry_msgs::Point &b,
00346 const std::string &object_name, double radius,
00347 const rviz_visual_tools::colors &color = rviz_visual_tools::GREEN);
00348 bool publishCollisionCylinder(const Eigen::Vector3d &a, const Eigen::Vector3d &b, const std::string &object_name,
00349 double radius, const rviz_visual_tools::colors &color = rviz_visual_tools::GREEN);
00350
00360 bool publishCollisionCylinder(const Eigen::Affine3d &object_pose, const std::string &object_name, double radius,
00361 double height, const rviz_visual_tools::colors &color = rviz_visual_tools::GREEN);
00362 bool publishCollisionCylinder(const geometry_msgs::Pose &object_pose, const std::string &object_name, double radius,
00363 double height, const rviz_visual_tools::colors &color = rviz_visual_tools::GREEN);
00364
00373 bool publishCollisionMesh(const geometry_msgs::Pose &object_pose, const std::string &object_name,
00374 const std::string &mesh_path,
00375 const rviz_visual_tools::colors &color = rviz_visual_tools::GREEN);
00376 bool publishCollisionMesh(const Eigen::Affine3d &object_pose, const std::string &object_name,
00377 const std::string &mesh_path,
00378 const rviz_visual_tools::colors &color = rviz_visual_tools::GREEN);
00379 bool publishCollisionMesh(const Eigen::Affine3d &object_pose, const std::string &object_name,
00380 const shape_msgs::Mesh &mesh_msg,
00381 const rviz_visual_tools::colors &color = rviz_visual_tools::GREEN);
00382 bool publishCollisionMesh(const geometry_msgs::Pose &object_pose, const std::string &object_name,
00383 const shape_msgs::Mesh &mesh_msg,
00384 const rviz_visual_tools::colors &color = rviz_visual_tools::GREEN);
00385
00393 bool publishCollisionGraph(const graph_msgs::GeometryGraph &graph, const std::string &object_name, double radius,
00394 const rviz_visual_tools::colors &color = rviz_visual_tools::GREEN);
00395
00399 void getCollisionWallMsg(double x, double y, double angle, double width, const std::string name,
00400 moveit_msgs::CollisionObject &collision_obj);
00401
00412 bool publishCollisionWall(double x, double y, double angle, double width, const std::string name,
00413 const rviz_visual_tools::colors &color = rviz_visual_tools::GREEN);
00414
00427 bool publishCollisionTable(double x, double y, double angle, double width, double height, double depth,
00428 const std::string name, const rviz_visual_tools::colors &color = rviz_visual_tools::GREEN);
00429
00436 bool loadCollisionSceneFromFile(const std::string &path);
00437 bool loadCollisionSceneFromFile(const std::string &path, const Eigen::Affine3d &offset);
00438
00443 RVIZ_VISUAL_TOOLS_DEPRECATED
00444 bool publishCollisionTests();
00445
00451 bool publishWorkspaceParameters(const moveit_msgs::WorkspaceParameters ¶ms);
00452
00460 bool publishContactPoints(const moveit::core::RobotState &robot_state,
00461 const planning_scene::PlanningScene *planning_scene,
00462 const rviz_visual_tools::colors &color = rviz_visual_tools::RED);
00463
00475 bool publishTrajectoryPoint(const trajectory_msgs::JointTrajectoryPoint &trajectory_pt,
00476 const std::string &planning_group, double display_time = 0.1);
00477
00486 bool publishTrajectoryPath(const std::vector<robot_state::RobotStatePtr> &trajectory,
00487 const moveit::core::JointModelGroup *jmg, double speed = 0.01, bool blocking = false);
00488 bool publishTrajectoryPath(const robot_trajectory::RobotTrajectory &trajectory, bool blocking = false);
00489 bool publishTrajectoryPath(const moveit_msgs::RobotTrajectory &trajectory_msg,
00490 const robot_state::RobotStateConstPtr robot_state, bool blocking);
00491
00501 bool publishTrajectoryLine(const moveit_msgs::RobotTrajectory &trajectory_msg,
00502 const moveit::core::LinkModel *ee_parent_link, const robot_model::JointModelGroup *arm_jmg,
00503 const rviz_visual_tools::colors &color, bool clear_all_markers = false);
00504 bool publishTrajectoryLine(const robot_trajectory::RobotTrajectoryPtr robot_trajectory,
00505 const moveit::core::LinkModel* ee_parent_link,
00506 const rviz_visual_tools::colors& color,
00507 bool clear_all_markers);
00508
00515 bool publishTrajectoryPoints(const std::vector<robot_state::RobotStatePtr> &robot_state_trajectory,
00516 const moveit::core::LinkModel *ee_parent_link,
00517 const rviz_visual_tools::colors &color = rviz_visual_tools::YELLOW);
00518
00525 bool publishRobotState(const robot_state::RobotState &robot_state,
00526 const rviz_visual_tools::colors &color = rviz_visual_tools::DEFAULT);
00527 bool publishRobotState(const robot_state::RobotStatePtr &robot_state,
00528 const rviz_visual_tools::colors &color = rviz_visual_tools::DEFAULT);
00529
00537 bool publishRobotState(const trajectory_msgs::JointTrajectoryPoint &trajectory_pt,
00538 const robot_model::JointModelGroup *jmg,
00539 const rviz_visual_tools::colors &color = rviz_visual_tools::DEFAULT);
00540
00545 bool hideRobot();
00546
00547 private:
00552 planning_scene_monitor::PlanningSceneMonitorPtr getPlanningSceneMonitor();
00553
00554 protected:
00555
00556 std::string name_;
00557
00558
00559 ros::Publisher pub_display_path_;
00560 ros::Publisher pub_robot_state_;
00561
00562
00563 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
00564 robot_model_loader::RobotModelLoaderPtr rm_loader_;
00565
00566
00567 std::map<const robot_model::JointModelGroup *, visualization_msgs::MarkerArray> ee_markers_map_;
00568 std::map<const robot_model::JointModelGroup *, EigenSTL::vector_Affine3d> ee_poses_map_;
00569
00570
00571
00572
00573 std::map<rviz_visual_tools::colors, moveit_msgs::DisplayRobotState> display_robot_msgs_;
00574
00575
00576 robot_state::RobotModelConstPtr robot_model_;
00577
00578
00579 robot_state::RobotStatePtr shared_robot_state_;
00580
00581
00582 robot_state::RobotStatePtr hidden_robot_state_;
00583
00584
00585 bool mannual_trigger_update_;
00586
00587
00588 std::string robot_state_topic_;
00589 std::string planning_scene_topic_;
00590
00591 };
00592
00593 typedef boost::shared_ptr<MoveItVisualTools> MoveItVisualToolsPtr;
00594 typedef boost::shared_ptr<const MoveItVisualTools> MoveItVisualToolsConstPtr;
00595
00596 }
00597
00598 #endif