moveit_visual_tools.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015, University of Colorado, Boulder
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Univ of CO, Boulder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* \author Dave Coleman
36  * \desc Helper functions for displaying and debugging MoveIt data in Rviz via published markers
37  * and MoveIt collision objects. Very useful for debugging complex software
38  */
39 
40 #ifndef MOVEIT_VISUAL_TOOLS_MOVEIT_VISUAL_TOOLS_H
41 #define MOVEIT_VISUAL_TOOLS_MOVEIT_VISUAL_TOOLS_H
42 
43 // Rviz Visualization Tool
45 
46 // MoveIt
48 // #include <moveit/macros/deprecation.h>
50 
51 // MoveIt Messages
52 #include <moveit_msgs/Grasp.h>
53 #include <moveit_msgs/DisplayRobotState.h>
54 #include <moveit_msgs/WorkspaceParameters.h>
55 #include <moveit_msgs/DisplayTrajectory.h>
56 
57 // ROS Messages
58 #include <trajectory_msgs/JointTrajectory.h>
59 
60 // C++
61 #include <map>
62 #include <string>
63 #include <utility>
64 #include <vector>
65 
66 namespace moveit_visual_tools
67 {
68 // Default constants
69 static const std::string ROBOT_DESCRIPTION = "robot_description"; // this is the default used in ROS
70 static const std::string DISPLAY_PLANNED_PATH_TOPIC =
71  "/move_group/display_planned_path"; // this is the default when adding the Rviz plugin
72 static const std::string DISPLAY_ROBOT_STATE_TOPIC =
73  "display_robot_state"; // this is the default when adding the Rviz plugin
74 static const std::string PLANNING_SCENE_TOPIC = "planning_scene"; // this is the default when adding the Rviz plugin
75 
76 class MoveItVisualTools : public rviz_visual_tools::RvizVisualTools
77 {
78 public:
86 
94  MoveItVisualTools(const std::string& base_frame, const std::string& marker_topic,
95  planning_scene_monitor::PlanningSceneMonitorPtr psm);
96 
103  MoveItVisualTools(const std::string& base_frame,
104  const std::string& marker_topic = rviz_visual_tools::RVIZ_MARKER_TOPIC,
105  moveit::core::RobotModelConstPtr robot_model = moveit::core::RobotModelConstPtr());
106 
111  void setRobotStateTopic(const std::string& robot_state_topic)
112  {
113  robot_state_topic_ = robot_state_topic;
114  }
115 
120  void setPlanningSceneTopic(const std::string& planning_scene_topic)
121  {
122  planning_scene_topic_ = planning_scene_topic;
123  }
124 
130 
137  bool processCollisionObjectMsg(const moveit_msgs::CollisionObject& msg,
139 
145  bool processAttachedCollisionObjectMsg(const moveit_msgs::AttachedCollisionObject& msg);
146 
153  bool moveCollisionObject(const Eigen::Isometry3d& pose, const std::string& name,
154  const rviz_visual_tools::colors& color);
155  bool moveCollisionObject(const geometry_msgs::Pose& pose, const std::string& name,
156  const rviz_visual_tools::colors& color);
157 
163 
168  bool loadSharedRobotState();
169 
174  moveit::core::RobotStatePtr& getSharedRobotState();
175 
180  moveit::core::RobotStatePtr& getRootRobotState()
181  {
182  return root_robot_state_;
183  }
184 
189  moveit::core::RobotModelConstPtr getRobotModel();
190 
197  bool loadEEMarker(const moveit::core::JointModelGroup* ee_jmg, const std::vector<double>& ee_joint_pos = {});
198 
202  void loadTrajectoryPub(const std::string& display_planned_path_topic = DISPLAY_PLANNED_PATH_TOPIC,
203  bool blocking = true);
204  void loadRobotStatePub(const std::string& robot_state_topic = "", bool blocking = true);
205 
210  void setPlanningSceneMonitor(planning_scene_monitor::PlanningSceneMonitorPtr psm)
211  {
212  psm_ = std::move(psm);
213  }
214 
219  void setManualSceneUpdating(bool enable_manual = true)
220  {
221  mannual_trigger_update_ = enable_manual;
222  }
223 
232  bool publishEEMarkers(const Eigen::Isometry3d& pose, const moveit::core::JointModelGroup* ee_jmg,
233  const std::vector<double>& ee_joint_pos,
235  const std::string& ns = "end_effector")
236  {
237  return publishEEMarkers(convertPose(pose), ee_jmg, ee_joint_pos, color, ns);
238  }
239  bool publishEEMarkers(const Eigen::Isometry3d& pose, const moveit::core::JointModelGroup* ee_jmg,
241  const std::string& ns = "end_effector")
242  {
243  return publishEEMarkers(convertPose(pose), ee_jmg, {}, color, ns);
244  }
245  bool publishEEMarkers(const geometry_msgs::Pose& pose, const moveit::core::JointModelGroup* ee_jmg,
247  const std::string& ns = "end_effector")
248  {
249  return publishEEMarkers(pose, ee_jmg, {}, color, ns);
250  }
251  bool publishEEMarkers(const geometry_msgs::Pose& pose, const moveit::core::JointModelGroup* ee_jmg,
252  const std::vector<double>& ee_joint_pos,
254  const std::string& ns = "end_effector");
255 
262  bool publishGrasps(const std::vector<moveit_msgs::Grasp>& possible_grasps,
263  const moveit::core::JointModelGroup* ee_jmg, double animate_speed = 0.1);
264 
272  bool publishAnimatedGrasps(const std::vector<moveit_msgs::Grasp>& possible_grasps,
273  const moveit::core::JointModelGroup* ee_jmg, double animate_speed = 0.01);
274 
283  bool publishAnimatedGrasp(const moveit_msgs::Grasp& grasp, const moveit::core::JointModelGroup* ee_jmg,
284  double animate_speed);
285 
293  bool publishIKSolutions(const std::vector<trajectory_msgs::JointTrajectoryPoint>& ik_solutions,
294  const moveit::core::JointModelGroup* arm_jmg, double display_time = 0.4);
295 
303 
309  bool cleanupCO(const std::string& name);
310 
316  bool cleanupACO(const std::string& name);
317 
324  bool attachCO(const std::string& name, const std::string& ee_parent_link);
325 
333  bool publishCollisionFloor(double z = 0.0, const std::string& plane_name = "Floor",
335 
344  bool publishCollisionBlock(const geometry_msgs::Pose& block_pose, const std::string& block_name = "block",
345  double block_size = 0.1,
347 
356  bool publishCollisionCuboid(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, const std::string& name,
358  bool publishCollisionCuboid(const geometry_msgs::Point& point1, const geometry_msgs::Point& point2,
359  const std::string& name,
361 
372  bool publishCollisionCuboid(const Eigen::Isometry3d& pose, double width, double depth, double height,
373  const std::string& name, const rviz_visual_tools::colors& color);
374 
375  bool publishCollisionCuboid(const geometry_msgs::Pose& pose, double width, double depth, double height,
376  const std::string& name, const rviz_visual_tools::colors& color);
377 
386  bool publishCollisionCuboid(const Eigen::Isometry3d& pose, const Eigen::Vector3d& size, const std::string& name,
387  const rviz_visual_tools::colors& color)
388  {
389  return publishCollisionCuboid(pose, size.x(), size.y(), size.z(), name, color);
390  }
391  bool publishCollisionCuboid(const geometry_msgs::Pose& pose, const geometry_msgs::Vector3& size,
392  const std::string& name, const rviz_visual_tools::colors& color)
393  {
394  return publishCollisionCuboid(pose, size.x, size.y, size.z, name, color);
395  }
396 
406  bool publishCollisionCylinder(const geometry_msgs::Point& a, const geometry_msgs::Point& b,
407  const std::string& object_name, double radius,
409  bool publishCollisionCylinder(const Eigen::Vector3d& a, const Eigen::Vector3d& b, const std::string& object_name,
410  double radius, const rviz_visual_tools::colors& color = rviz_visual_tools::GREEN);
411 
421  bool publishCollisionCylinder(const Eigen::Isometry3d& object_pose, const std::string& object_name, double radius,
422  double height, const rviz_visual_tools::colors& color = rviz_visual_tools::GREEN);
423  bool publishCollisionCylinder(const geometry_msgs::Pose& object_pose, const std::string& object_name, double radius,
424  double height, const rviz_visual_tools::colors& color = rviz_visual_tools::GREEN);
425 
434  bool publishCollisionMesh(const geometry_msgs::Pose& object_pose, const std::string& object_name,
435  const std::string& mesh_path,
437  bool publishCollisionMesh(const Eigen::Isometry3d& object_pose, const std::string& object_name,
438  const std::string& mesh_path,
440  bool publishCollisionMesh(const Eigen::Isometry3d& object_pose, const std::string& object_name,
441  const shape_msgs::Mesh& mesh_msg,
443  bool publishCollisionMesh(const geometry_msgs::Pose& object_pose, const std::string& object_name,
444  const shape_msgs::Mesh& mesh_msg,
446 
454  bool publishCollisionGraph(const graph_msgs::GeometryGraph& graph, const std::string& object_name, double radius,
456 
460  void getCollisionWallMsg(double x, double y, double z, double angle, double width, double height,
461  const std::string& name, moveit_msgs::CollisionObject& collision_obj);
462 
474  bool publishCollisionWall(double x, double y, double angle = 0.0, double width = 2.0, double height = 1.5,
475  const std::string& name = "wall",
477  bool publishCollisionWall(double x, double y, double z, double angle = 0.0, double width = 2.0, double height = 1.5,
478  const std::string& name = "wall",
480 
493  bool publishCollisionTable(double x, double y, double z, double angle, double width, double height, double depth,
494  const std::string& name,
496 
503  bool loadCollisionSceneFromFile(const std::string& path);
504  bool loadCollisionSceneFromFile(const std::string& path, const Eigen::Isometry3d& offset);
505 
511  bool publishWorkspaceParameters(const moveit_msgs::WorkspaceParameters& params);
512 
523  bool checkAndPublishCollision(const moveit::core::RobotState& robot_state,
525  const rviz_visual_tools::colors& highlight_link_color = rviz_visual_tools::RED,
526  const rviz_visual_tools::colors& contact_point_color = rviz_visual_tools::PURPLE);
527 
535  bool publishContactPoints(const moveit::core::RobotState& robot_state,
538 
549 
561  bool publishTrajectoryPoint(const trajectory_msgs::JointTrajectoryPoint& trajectory_pt,
562  const std::string& planning_group, double display_time = 0.1);
563 
572  bool publishTrajectoryPath(const std::vector<moveit::core::RobotStatePtr>& trajectory,
573  const moveit::core::JointModelGroup* jmg, double speed = 0.01, bool blocking = false);
574  bool publishTrajectoryPath(const robot_trajectory::RobotTrajectoryPtr& trajectory, bool blocking = false);
575  bool publishTrajectoryPath(const robot_trajectory::RobotTrajectory& trajectory, bool blocking = false);
576  bool publishTrajectoryPath(const moveit_msgs::RobotTrajectory& trajectory_msg,
577  const moveit::core::RobotStateConstPtr& robot_state, bool blocking = false);
578  bool publishTrajectoryPath(const moveit_msgs::RobotTrajectory& trajectory_msg,
579  const moveit::core::RobotState& robot_state, bool blocking = false);
580  bool publishTrajectoryPath(const moveit_msgs::RobotTrajectory& trajectory_msg,
581  const moveit_msgs::RobotState& robot_state, bool blocking = false);
582  void publishTrajectoryPath(const moveit_msgs::DisplayTrajectory& display_trajectory_msg);
583 
592  bool publishTrajectoryLine(const moveit_msgs::RobotTrajectory& trajectory_msg,
593  const moveit::core::LinkModel* ee_parent_link,
594  const moveit::core::JointModelGroup* arm_jmg,
596  bool publishTrajectoryLine(const robot_trajectory::RobotTrajectoryPtr& robot_trajectory,
597  const moveit::core::LinkModel* ee_parent_link,
600  const moveit::core::LinkModel* ee_parent_link,
602 
611  bool publishTrajectoryLine(const moveit_msgs::RobotTrajectory& trajectory_msg,
612  const moveit::core::JointModelGroup* arm_jmg,
614  bool publishTrajectoryLine(const robot_trajectory::RobotTrajectoryPtr& robot_trajectory,
615  const moveit::core::JointModelGroup* arm_jmg,
618  const moveit::core::JointModelGroup* arm_jmg,
620 
627  bool publishTrajectoryPoints(const std::vector<moveit::core::RobotStatePtr>& robot_state_trajectory,
628  const moveit::core::LinkModel* ee_parent_link,
630 
632  void enableRobotStateRootOffet(const Eigen::Isometry3d& offset);
633 
636 
644  bool publishRobotState(const trajectory_msgs::JointTrajectoryPoint& trajectory_pt,
647 
655  bool publishRobotState(const std::vector<double>& joint_positions, const moveit::core::JointModelGroup* jmg,
657 
666  bool publishRobotState(const moveit::core::RobotState& robot_state,
668  const std::vector<std::string>& highlight_links = {});
669  bool publishRobotState(const moveit::core::RobotStatePtr& robot_state,
671  const std::vector<std::string>& highlight_links = {});
672  void publishRobotState(const moveit_msgs::DisplayRobotState& display_robot_state_msg);
673 
678  bool hideRobot();
679 
681  static bool applyVirtualJointTransform(moveit::core::RobotState& robot_state, const Eigen::Isometry3d& offset);
682 
687  void showJointLimits(const moveit::core::RobotStatePtr& robot_state);
688 
693  planning_scene_monitor::PlanningSceneMonitorPtr getPlanningSceneMonitor();
694 
695 private:
700  static bool checkForVirtualJoint(const moveit::core::RobotState& robot_state);
701 
702 protected:
703  // Pointer to a Planning Scene Monitor
704  planning_scene_monitor::PlanningSceneMonitorPtr psm_;
705 
706  // Prevent the planning scene from always auto-pushing, but rather do it manually
707  bool mannual_trigger_update_ = false;
708 
709  // ROS topic names to use when starting publishers
710  std::string robot_state_topic_;
711  std::string planning_scene_topic_;
712 
713  // ROS publishers
714  ros::Publisher pub_display_path_; // for MoveIt trajectories
715  ros::Publisher pub_robot_state_; // publish a RobotState message
716 
717  robot_model_loader::RobotModelLoaderPtr rm_loader_; // so that we can specify our own options
718 
719  // End Effector Markers
720  std::map<const moveit::core::JointModelGroup*, visualization_msgs::MarkerArray> ee_markers_map_;
721  std::map<const moveit::core::JointModelGroup*, EigenSTL::vector_Isometry3d> ee_poses_map_;
722  std::map<const moveit::core::JointModelGroup*, std::vector<double> > ee_joint_pos_map_;
723 
724  // Cached robot state marker - cache the colored links.
725  // Note: Only allows colors provided in rviz_visual_tools to prevent too many robot state messages from being loaded
726  // and ensuring efficiency
727  std::map<rviz_visual_tools::colors, moveit_msgs::DisplayRobotState> display_robot_msgs_;
728 
729  // Pointer to the robot model
730  moveit::core::RobotModelConstPtr robot_model_;
731 
732  // Note: call loadSharedRobotState() before using this
733  moveit::core::RobotStatePtr shared_robot_state_;
734 
735  // Note: call loadSharedRobotState() before using this. Use only for hiding the robot
736  moveit::core::RobotStatePtr hidden_robot_state_;
737 
738  // A robot state whose virtual_joint remains at identity so that getGlobalLinkTransform() isn't tainted
739  // Note: call loadSharedRobotState() before using this
740  moveit::core::RobotStatePtr root_robot_state_;
741 
742  // Optional offset that can be applied to all outgoing/published robot states
744  Eigen::Isometry3d robot_state_root_offset_;
745 
746 public:
747  EIGEN_MAKE_ALIGNED_OPERATOR_NEW // http://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
748 }; // class
749 
750 typedef std::shared_ptr<MoveItVisualTools> MoveItVisualToolsPtr;
751 typedef std::shared_ptr<const MoveItVisualTools> MoveItVisualToolsConstPtr;
752 
753 } // namespace moveit_visual_tools
754 
755 #endif // MOVEIT_VISUAL_TOOLS_MOVEIT_VISUAL_TOOLS_H
moveit_visual_tools::MoveItVisualTools::robot_model_
moveit::core::RobotModelConstPtr robot_model_
Definition: moveit_visual_tools.h:762
moveit::core::LinkModel
moveit_visual_tools::MoveItVisualTools::getRootRobotState
moveit::core::RobotStatePtr & getRootRobotState()
Allow robot state to be altered.
Definition: moveit_visual_tools.h:212
moveit_visual_tools::MoveItVisualTools::publishCollisionCuboid
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.
Definition: moveit_visual_tools.cpp:694
collision_detection::CollisionResult::ContactMap
std::map< std::pair< std::string, std::string >, std::vector< Contact > > ContactMap
moveit_visual_tools::MoveItVisualTools::triggerPlanningSceneUpdate
bool triggerPlanningSceneUpdate()
When mannual_trigger_update_ is true, use this to tell the planning scene to send an update out....
Definition: moveit_visual_tools.cpp:231
moveit_visual_tools::MoveItVisualTools::cleanupCO
bool cleanupCO(const std::string &name)
Remove a collision object from the planning scene.
Definition: moveit_visual_tools.cpp:629
moveit_visual_tools::MoveItVisualTools::rm_loader_
robot_model_loader::RobotModelLoaderPtr rm_loader_
Definition: moveit_visual_tools.h:749
ros::Publisher
moveit_visual_tools::MoveItVisualTools::publishCollisionTable
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.
Definition: moveit_visual_tools.cpp:1024
moveit_visual_tools::MoveItVisualTools::publishTrajectoryPath
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 publ...
Definition: moveit_visual_tools.cpp:1206
moveit_visual_tools::MoveItVisualTools::processAttachedCollisionObjectMsg
bool processAttachedCollisionObjectMsg(const moveit_msgs::AttachedCollisionObject &msg)
Skip a ROS message call by sending directly to planning scene monitor.
Definition: moveit_visual_tools.cpp:190
moveit_visual_tools::MoveItVisualTools::moveCollisionObject
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.
Definition: moveit_visual_tools.cpp:208
moveit_visual_tools::MoveItVisualTools::loadSharedRobotState
bool loadSharedRobotState()
Load robot state only as needed.
Definition: moveit_visual_tools.cpp:239
moveit_visual_tools::MoveItVisualTools::planning_scene_topic_
std::string planning_scene_topic_
Definition: moveit_visual_tools.h:743
planning_scene::PlanningScene
moveit_visual_tools::MoveItVisualTools::enableRobotStateRootOffet
void enableRobotStateRootOffet(const Eigen::Isometry3d &offset)
All published robot states will have their virtual joint moved by offset.
Definition: moveit_visual_tools.cpp:1476
moveit_visual_tools::MoveItVisualTools::publishCollisionCylinder
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.
Definition: moveit_visual_tools.cpp:795
moveit_visual_tools::MoveItVisualTools::cleanupACO
bool cleanupACO(const std::string &name)
Remove an active collision object from the planning scene.
Definition: moveit_visual_tools.cpp:641
moveit_visual_tools::MoveItVisualTools::publishCollisionMesh
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.
Definition: moveit_visual_tools.cpp:857
moveit_visual_tools::MoveItVisualTools::hidden_robot_state_
moveit::core::RobotStatePtr hidden_robot_state_
Definition: moveit_visual_tools.h:768
moveit_visual_tools::MoveItVisualTools::publishEEMarkers
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.
Definition: moveit_visual_tools.h:264
rviz_visual_tools::RvizVisualTools::convertPose
static geometry_msgs::Pose convertPose(const Eigen::Isometry3d &pose)
moveit_visual_tools::MoveItVisualTools::robot_state_root_offset_enabled_
bool robot_state_root_offset_enabled_
Definition: moveit_visual_tools.h:775
moveit::core::RobotState
moveit_visual_tools::DISPLAY_ROBOT_STATE_TOPIC
static const std::string DISPLAY_ROBOT_STATE_TOPIC
Definition: moveit_visual_tools.h:104
rviz_visual_tools::RvizVisualTools
robot_trajectory::RobotTrajectory
rviz_visual_tools::PURPLE
PURPLE
moveit_visual_tools::MoveItVisualTools::ee_joint_pos_map_
std::map< const moveit::core::JointModelGroup *, std::vector< double > > ee_joint_pos_map_
Definition: moveit_visual_tools.h:754
moveit_visual_tools::MoveItVisualTools::checkAndPublishCollision
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....
Definition: moveit_visual_tools.cpp:1102
moveit_visual_tools::MoveItVisualTools::publishGrasps
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.
Definition: moveit_visual_tools.cpp:458
moveit_visual_tools::MoveItVisualTools::removeAllCollisionObjects
bool removeAllCollisionObjects()
Remove all collision objects that this class has added to the MoveIt planning scene Communicates dire...
Definition: moveit_visual_tools.cpp:618
moveit_visual_tools::MoveItVisualTools::mannual_trigger_update_
bool mannual_trigger_update_
Definition: moveit_visual_tools.h:739
moveit_visual_tools::MoveItVisualTools::publishAnimatedGrasp
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 ...
Definition: moveit_visual_tools.cpp:497
moveit_visual_tools::MoveItVisualTools::processCollisionObjectMsg
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.
Definition: moveit_visual_tools.cpp:171
moveit_visual_tools::MoveItVisualTools::publishCollisionGraph
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.
Definition: moveit_visual_tools.cpp:898
moveit_visual_tools::MoveItVisualToolsPtr
std::shared_ptr< MoveItVisualTools > MoveItVisualToolsPtr
Definition: moveit_visual_tools.h:782
moveit_visual_tools::MoveItVisualTools::root_robot_state_
moveit::core::RobotStatePtr root_robot_state_
Definition: moveit_visual_tools.h:772
robot_trajectory
moveit_visual_tools::MoveItVisualTools::psm_
planning_scene_monitor::PlanningSceneMonitorPtr psm_
Definition: moveit_visual_tools.h:736
moveit_visual_tools::MoveItVisualTools::display_robot_msgs_
std::map< rviz_visual_tools::colors, moveit_msgs::DisplayRobotState > display_robot_msgs_
Definition: moveit_visual_tools.h:759
moveit_visual_tools::MoveItVisualTools::loadCollisionSceneFromFile
bool loadCollisionSceneFromFile(const std::string &path)
Load a planning scene to a planning_scene_monitor from file.
Definition: moveit_visual_tools.cpp:1062
moveit_visual_tools::MoveItVisualTools::showJointLimits
void showJointLimits(const moveit::core::RobotStatePtr &robot_state)
Print to console the current robot state's joint values within its limits visually.
Definition: moveit_visual_tools.cpp:1600
moveit_visual_tools::MoveItVisualTools::setManualSceneUpdating
void setManualSceneUpdating(bool enable_manual=true)
Prevent the planning scene from always auto-pushing, but rather do it manually.
Definition: moveit_visual_tools.h:251
moveit_visual_tools::MoveItVisualTools::applyVirtualJointTransform
static bool applyVirtualJointTransform(moveit::core::RobotState &robot_state, const Eigen::Isometry3d &offset)
Before publishing a robot state, optionally change its root transform.
Definition: moveit_visual_tools.cpp:1697
planning_scene_monitor.h
moveit_visual_tools::DISPLAY_PLANNED_PATH_TOPIC
static const std::string DISPLAY_PLANNED_PATH_TOPIC
Definition: moveit_visual_tools.h:102
deprecation.h
moveit_visual_tools::MoveItVisualTools::publishCollisionWall
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.
Definition: moveit_visual_tools.cpp:1009
moveit_visual_tools::MoveItVisualTools::publishWorkspaceParameters
bool publishWorkspaceParameters(const moveit_msgs::WorkspaceParameters &params)
Display size of workspace used for planning with OMPL, etc. Important for virtual joints.
Definition: moveit_visual_tools.cpp:1096
moveit_visual_tools::MoveItVisualTools::ee_poses_map_
std::map< const moveit::core::JointModelGroup *, EigenSTL::vector_Isometry3d > ee_poses_map_
Definition: moveit_visual_tools.h:753
moveit_visual_tools::MoveItVisualTools::getRobotModel
moveit::core::RobotModelConstPtr getRobotModel()
Get a pointer to the robot model.
Definition: moveit_visual_tools.cpp:274
moveit_visual_tools::MoveItVisualTools::setRobotStateTopic
void setRobotStateTopic(const std::string &robot_state_topic)
Set the ROS topic for publishing a robot state.
Definition: moveit_visual_tools.h:143
moveit_visual_tools::MoveItVisualTools::hideRobot
bool hideRobot()
Hide robot in RobotState display in Rviz.
Definition: moveit_visual_tools.cpp:1589
moveit_visual_tools::MoveItVisualTools::publishCollisionFloor
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.
Definition: moveit_visual_tools.cpp:777
moveit_visual_tools::MoveItVisualTools::checkForVirtualJoint
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 wa...
Definition: moveit_visual_tools.cpp:1669
moveit_visual_tools::MoveItVisualToolsConstPtr
std::shared_ptr< const MoveItVisualTools > MoveItVisualToolsConstPtr
Definition: moveit_visual_tools.h:783
moveit_visual_tools::MoveItVisualTools::publishRobotState
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.
Definition: moveit_visual_tools.cpp:1487
moveit_visual_tools::ROBOT_DESCRIPTION
static const std::string ROBOT_DESCRIPTION
Definition: moveit_visual_tools.h:101
moveit_visual_tools::MoveItVisualTools::publishTrajectoryPoint
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...
Definition: moveit_visual_tools.cpp:1177
rviz_visual_tools::YELLOW
YELLOW
rviz_visual_tools::RED
RED
moveit_visual_tools::MoveItVisualTools::loadPlanningSceneMonitor
bool loadPlanningSceneMonitor()
Load a planning scene monitor if one was not passed into the constructor.
Definition: moveit_visual_tools.cpp:126
moveit_visual_tools::MoveItVisualTools::publishTrajectoryLine
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.
Definition: moveit_visual_tools.cpp:1335
rviz_visual_tools::colors
colors
moveit_visual_tools::MoveItVisualTools::ee_markers_map_
std::map< const moveit::core::JointModelGroup *, visualization_msgs::MarkerArray > ee_markers_map_
Definition: moveit_visual_tools.h:752
rviz_visual_tools::GREEN
GREEN
moveit_visual_tools::MoveItVisualTools::publishCollisionBlock
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.
Definition: moveit_visual_tools.cpp:670
moveit_visual_tools::MoveItVisualTools::pub_robot_state_
ros::Publisher pub_robot_state_
Definition: moveit_visual_tools.h:747
moveit_visual_tools::MoveItVisualTools::MoveItVisualTools
MoveItVisualTools()
Constructor.
Definition: moveit_visual_tools.cpp:102
moveit_visual_tools::MoveItVisualTools::getPlanningSceneMonitor
planning_scene_monitor::PlanningSceneMonitorPtr getPlanningSceneMonitor()
Get the planning scene monitor that this class is using.
Definition: moveit_visual_tools.cpp:1657
moveit_visual_tools::MoveItVisualTools::disableRobotStateRootOffet
void disableRobotStateRootOffet()
Turn off the root offset feature.
Definition: moveit_visual_tools.cpp:1482
moveit_visual_tools::MoveItVisualTools::publishContactPoints
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.
Definition: moveit_visual_tools.cpp:1129
moveit::core::JointModelGroup
rviz_visual_tools::RVIZ_MARKER_TOPIC
static const std::string RVIZ_MARKER_TOPIC
moveit_visual_tools::MoveItVisualTools::robot_state_root_offset_
Eigen::Isometry3d robot_state_root_offset_
Definition: moveit_visual_tools.h:776
moveit_visual_tools::PLANNING_SCENE_TOPIC
static const std::string PLANNING_SCENE_TOPIC
Definition: moveit_visual_tools.h:106
moveit_visual_tools::MoveItVisualTools::loadTrajectoryPub
void loadTrajectoryPub(const std::string &display_planned_path_topic=DISPLAY_PLANNED_PATH_TOPIC, bool blocking=true)
Load publishers as needed.
Definition: moveit_visual_tools.cpp:372
moveit_visual_tools::MoveItVisualTools::loadEEMarker
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.
Definition: moveit_visual_tools.cpp:281
moveit_visual_tools::MoveItVisualTools::robot_state_topic_
std::string robot_state_topic_
Definition: moveit_visual_tools.h:742
moveit_visual_tools::MoveItVisualTools::pub_display_path_
ros::Publisher pub_display_path_
Definition: moveit_visual_tools.h:746
moveit_visual_tools::MoveItVisualTools::attachCO
bool attachCO(const std::string &name, const std::string &ee_parent_link)
Attach a collision object from the planning scene.
Definition: moveit_visual_tools.cpp:654
moveit_visual_tools::MoveItVisualTools::getSharedRobotState
moveit::core::RobotStatePtr & getSharedRobotState()
Allow robot state to be altered.
Definition: moveit_visual_tools.cpp:267
moveit_visual_tools::MoveItVisualTools::setPlanningSceneTopic
void setPlanningSceneTopic(const std::string &planning_scene_topic)
Set the planning scene topic.
Definition: moveit_visual_tools.h:152
moveit_visual_tools::MoveItVisualTools::shared_robot_state_
moveit::core::RobotStatePtr shared_robot_state_
Definition: moveit_visual_tools.h:765
moveit_visual_tools::MoveItVisualTools::publishTrajectoryPoints
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.
Definition: moveit_visual_tools.cpp:1462
planning_scene
moveit_visual_tools::MoveItVisualTools::publishIKSolutions
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 t...
Definition: moveit_visual_tools.cpp:576
moveit_visual_tools
Definition: imarker_end_effector.h:62
moveit_visual_tools::MoveItVisualTools::getCollisionWallMsg
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.
Definition: moveit_visual_tools.cpp:969
rviz_visual_tools::DEFAULT
DEFAULT
rviz_visual_tools::LIME_GREEN
LIME_GREEN
moveit_visual_tools::MoveItVisualTools::loadRobotStatePub
void loadRobotStatePub(const std::string &robot_state_topic="", bool blocking=true)
Definition: moveit_visual_tools.cpp:386
moveit_visual_tools::MoveItVisualTools::publishAnimatedGrasps
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...
Definition: moveit_visual_tools.cpp:478
rviz_visual_tools.h
moveit_visual_tools::MoveItVisualTools::setPlanningSceneMonitor
void setPlanningSceneMonitor(planning_scene_monitor::PlanningSceneMonitorPtr psm)
Allow a pre-configured planning scene monitor to be set for publishing collision objects,...
Definition: moveit_visual_tools.h:242


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