moveit_visual_tools.cpp
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: Simple tools for showing parts of a robot in Rviz, such as the gripper or arm
37 
39 
40 // MoveIt Messages
41 #include <moveit_msgs/CollisionObject.h>
42 
43 // MoveIt
47 
48 // Conversions
49 #include <tf2_eigen/tf2_eigen.h>
50 
51 // Transforms
53 
54 // Shape tools
57 
58 // C++
59 #include <string>
60 #include <algorithm>
61 #include <utility>
62 #include <vector>
63 #include <set>
64 #include <limits>
65 
66 namespace moveit_visual_tools
67 {
68 const std::string LOGNAME = "visual_tools";
69 
71  : RvizVisualTools("", rviz_visual_tools::RVIZ_MARKER_TOPIC)
72  , robot_state_topic_(DISPLAY_ROBOT_STATE_TOPIC)
73  , planning_scene_topic_(PLANNING_SCENE_TOPIC)
74 {
75  loadSharedRobotState();
76  setBaseFrame(robot_model_->getModelFrame());
77 }
78 
79 MoveItVisualTools::MoveItVisualTools(const std::string& base_frame, const std::string& marker_topic,
80  planning_scene_monitor::PlanningSceneMonitorPtr psm)
81  : RvizVisualTools::RvizVisualTools(base_frame, marker_topic)
82  , psm_(std::move(psm))
83  , robot_state_topic_(DISPLAY_ROBOT_STATE_TOPIC)
84  , planning_scene_topic_(PLANNING_SCENE_TOPIC)
85 {
86 }
87 
88 MoveItVisualTools::MoveItVisualTools(const std::string& base_frame, const std::string& marker_topic,
89  moveit::core::RobotModelConstPtr robot_model)
90  : RvizVisualTools::RvizVisualTools(base_frame, marker_topic), robot_model_(std::move(robot_model))
91 {
92 }
93 
95 {
96  // Check if we already have one
97  if (psm_)
98  {
99  ROS_WARN_STREAM_NAMED(LOGNAME, "Will not load a new planning scene monitor when one has "
100  "already been set for Visual Tools");
101  return false;
102  }
103  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Loading planning scene monitor");
104 
105  // Create tf transform buffer and listener
106  std::shared_ptr<tf2_ros::Buffer> tf_buffer = std::make_shared<tf2_ros::Buffer>();
107  std::shared_ptr<tf2_ros::TransformListener> tf_listener = std::make_shared<tf2_ros::TransformListener>(*tf_buffer);
108 
109  // Regular version b/c the other one causes problems with recognizing end effectors
110  psm_.reset(new planning_scene_monitor::PlanningSceneMonitor(ROBOT_DESCRIPTION, tf_buffer, "visual_tools_scene"));
111 
112  ros::spinOnce();
113  ros::Duration(0.1).sleep();
114  ros::spinOnce();
115 
116  if (psm_->getPlanningScene())
117  {
118  // Optional monitors to start:
119  // psm_->startWorldGeometryMonitor();
120  // psm_->startSceneMonitor("/move_group/monitored_planning_scene");
121  // psm_->startStateMonitor("/joint_states", "/attached_collision_object");
122 
125  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Publishing planning scene on " << planning_scene_topic_);
126 
128  planning_scene->setName("visual_tools_scene");
129  }
130  else
131  {
132  ROS_ERROR_STREAM_NAMED(LOGNAME, "Planning scene not configured");
133  return false;
134  }
135 
136  return true;
137 }
138 
139 bool MoveItVisualTools::processCollisionObjectMsg(const moveit_msgs::CollisionObject& msg,
140  const rviz_visual_tools::colors& color)
141 {
142  // Apply command directly to planning scene to avoid a ROS msg call
143  {
145  scene->getCurrentStateNonConst().update(); // TODO: remove hack to prevent bad transforms
146  scene->processCollisionObjectMsg(msg);
147  scene->setObjectColor(msg.id, getColor(color));
148  }
149  // Trigger an update
151  {
153  }
154 
155  return true;
156 }
157 
158 bool MoveItVisualTools::processAttachedCollisionObjectMsg(const moveit_msgs::AttachedCollisionObject& msg)
159 {
160  // Apply command directly to planning scene to avoid a ROS msg call
161  {
163  // scene->getCurrentStateNonConst().update(); // hack to prevent bad transforms
164  scene->processAttachedCollisionObjectMsg(msg);
165  }
166 
167  // Trigger an update
169  {
171  }
172 
173  return true;
174 }
175 
176 bool MoveItVisualTools::moveCollisionObject(const Eigen::Isometry3d& pose, const std::string& name,
177  const rviz_visual_tools::colors& color)
178 {
179  return moveCollisionObject(convertPose(pose), name, color);
180 }
181 
182 bool MoveItVisualTools::moveCollisionObject(const geometry_msgs::Pose& pose, const std::string& name,
183  const rviz_visual_tools::colors& color)
184 {
185  moveit_msgs::CollisionObject collision_obj;
186  collision_obj.header.stamp = ros::Time::now();
187  collision_obj.header.frame_id = base_frame_;
188  collision_obj.id = name;
189  collision_obj.operation = moveit_msgs::CollisionObject::MOVE;
190 
191  collision_obj.primitive_poses.resize(1);
192  collision_obj.primitive_poses[0] = pose;
193 
194  // ROS_INFO_STREAM_NAMED(LOGNAME,"CollisionObject: \n " << collision_obj);
195  // ROS_DEBUG_STREAM_NAMED(LOGNAME,"Published collision object " << name);
196  return processCollisionObjectMsg(collision_obj, color);
197 }
198 
200 {
201  // TODO(davetcoleman): perhaps switch to using the service call?
203 
204  return true;
205 }
206 
208 {
209  // Get robot state
210  if (!shared_robot_state_)
211  {
212  // Check if a robot model was passed in
213  if (!robot_model_)
214  {
215  // Fall back on using planning scene monitor.
216  robot_model_ = getPlanningSceneMonitor()->getRobotModel();
217  }
219 
220  // TODO(davetcoleman): this seems to be a work around for a weird NaN bug
221  shared_robot_state_->setToDefaultValues();
222  shared_robot_state_->update(true);
223 
224  // hidden_robot_state_.reset(new moveit::core::RobotState(robot_model_));
225  // hidden_robot_state_->setToDefaultValues();
226  // hidden_robot_state_->update(true);
227 
230  }
231 
232  return !(shared_robot_state_ == nullptr);
233 }
234 
235 moveit::core::RobotStatePtr& MoveItVisualTools::getSharedRobotState()
236 {
237  // Always load the robot state before using
240 }
241 
242 moveit::core::RobotModelConstPtr MoveItVisualTools::getRobotModel()
243 {
244  // Always load the robot state before using
246  return shared_robot_state_->getRobotModel();
247 }
248 
250  const std::vector<double>& ee_joint_pos)
251 {
252  // Get joint state group
253  if (ee_jmg == nullptr) // make sure EE_GROUP exists
254  {
255  ROS_ERROR_STREAM_NAMED(LOGNAME, "Unable to find joint model group with address" << ee_jmg);
256  return false;
257  }
258 
259  // Always load the robot state before using
261  shared_robot_state_->setToDefaultValues();
262  shared_robot_state_->update();
263 
264  if (!ee_joint_pos.empty())
265  {
266  if (ee_joint_pos.size() != ee_jmg->getActiveJointModels().size())
267  {
268  ROS_ERROR_STREAM_NAMED(LOGNAME, "The number of joint positions given ("
269  << ee_joint_pos.size() << ") does not match the number of active joints in "
270  << ee_jmg->getName() << "(" << ee_jmg->getActiveJointModels().size() << ")");
271  return false;
272  }
273  shared_robot_state_->setJointGroupActivePositions(ee_jmg, ee_joint_pos);
274  shared_robot_state_->update(true);
275  }
276 
277  // Clear old EE markers and EE poses
278  ee_markers_map_[ee_jmg].markers.clear();
279  ee_poses_map_[ee_jmg].clear();
280 
281  // Remember joint state
282  ee_joint_pos_map_[ee_jmg] = ee_joint_pos;
283 
284  // Keep track of how many unique markers we have between different EEs
285  static std::size_t marker_id_offset = 0;
286 
287  // Get end effector group
288 
289  // Create color to use for EE markers
290  std_msgs::ColorRGBA marker_color = getColor(rviz_visual_tools::GREY);
291 
292  // Get link names that are in end effector
293  const std::vector<std::string>& ee_link_names = ee_jmg->getLinkModelNames();
294 
295  // Get EE link markers for Rviz
296  shared_robot_state_->getRobotMarkers(ee_markers_map_[ee_jmg], ee_link_names, marker_color, ee_jmg->getName(),
297  ros::Duration());
298  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Number of rviz markers in end effector: " << ee_markers_map_[ee_jmg].markers.size());
299 
300  // Error check
301  if (ee_markers_map_[ee_jmg].markers.empty())
302  {
304  "No links found to visualize in end effector for joint model group: " << ee_jmg->getName());
305  return false;
306  }
307 
308  const std::string& ee_parent_link_name = ee_jmg->getEndEffectorParentGroup().second;
309  // ROS_DEBUG_STREAM_NAMED(LOGNAME,"EE Parent link: " << ee_parent_link_name);
310  const moveit::core::LinkModel* ee_parent_link = robot_model_->getLinkModel(ee_parent_link_name);
311 
312  Eigen::Isometry3d ee_marker_global_transform = shared_robot_state_->getGlobalLinkTransform(ee_parent_link);
313  Eigen::Isometry3d ee_marker_pose;
314 
315  // Process each link of the end effector
316  for (std::size_t i = 0; i < ee_markers_map_[ee_jmg].markers.size(); ++i)
317  {
318  // Header
319  ee_markers_map_[ee_jmg].markers[i].header.frame_id = base_frame_;
320 
321  // Options for meshes
322  if (ee_markers_map_[ee_jmg].markers[i].type == visualization_msgs::Marker::MESH_RESOURCE)
323  {
324  ee_markers_map_[ee_jmg].markers[i].mesh_use_embedded_materials = true;
325  }
326 
327  // Unique id
328  ee_markers_map_[ee_jmg].markers[i].id += marker_id_offset;
329 
330  // Copy original marker poses to a vector
331  ee_marker_pose = ee_marker_global_transform.inverse() * convertPose(ee_markers_map_[ee_jmg].markers[i].pose);
332  ee_poses_map_[ee_jmg].push_back(ee_marker_pose);
333  }
334 
335  marker_id_offset += ee_markers_map_[ee_jmg].markers.size();
336 
337  return true;
338 }
339 
340 void MoveItVisualTools::loadTrajectoryPub(const std::string& display_planned_path_topic, bool blocking)
341 {
342  if (pub_display_path_)
343  return;
344 
345  // Trajectory paths
346  pub_display_path_ = nh_.advertise<moveit_msgs::DisplayTrajectory>(display_planned_path_topic, 10, false);
347  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Publishing MoveIt trajectory on topic " << pub_display_path_.getTopic());
348 
349  // Wait for topic to be ready
350  if (blocking)
352 }
353 
354 void MoveItVisualTools::loadRobotStatePub(const std::string& robot_state_topic, bool blocking)
355 {
356  if (pub_robot_state_)
357  return;
358 
359  // Update global var if new topic was passed in
360  if (!robot_state_topic.empty())
361  robot_state_topic_ = robot_state_topic;
362 
363  // RobotState Message
364  pub_robot_state_ = nh_.advertise<moveit_msgs::DisplayRobotState>(robot_state_topic_, 1);
365  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Publishing MoveIt robot state on topic " << pub_robot_state_.getTopic());
366 
367  // Wait for topic to be ready
368  if (blocking)
370 }
371 
372 bool MoveItVisualTools::publishEEMarkers(const geometry_msgs::Pose& pose, const moveit::core::JointModelGroup* ee_jmg,
373  const std::vector<double>& ee_joint_pos,
374  const rviz_visual_tools::colors& color, const std::string& ns)
375 {
376  // Check if we have not loaded the EE markers
377  if (ee_markers_map_[ee_jmg].markers.empty() || ee_poses_map_[ee_jmg].empty() ||
378  ee_joint_pos_map_[ee_jmg] != ee_joint_pos)
379  {
380  if (!loadEEMarker(ee_jmg, ee_joint_pos))
381  {
382  ROS_ERROR_STREAM_NAMED(LOGNAME, "Unable to publish EE marker, unable to load EE markers");
383  return false;
384  }
385  }
386 
387  Eigen::Isometry3d eigen_goal_ee_pose = convertPose(pose);
388  Eigen::Isometry3d eigen_this_marker;
389 
390  // Process each link of the end effector
391  for (std::size_t i = 0; i < ee_markers_map_[ee_jmg].markers.size(); ++i)
392  {
393  // Make sure ROS is still spinning
394  if (!ros::ok())
395  break;
396 
397  // Header
398  ee_markers_map_[ee_jmg].markers[i].header.stamp = ros::Time::now();
399 
400  // Namespace
401  ee_markers_map_[ee_jmg].markers[i].ns = ns;
402 
403  // Lifetime
404  ee_markers_map_[ee_jmg].markers[i].lifetime = marker_lifetime_;
405 
406  // Color
407  if (color != rviz_visual_tools::DEFAULT)
408  ee_markers_map_[ee_jmg].markers[i].color = getColor(color);
409 
410  // Convert pose
411  eigen_this_marker = eigen_goal_ee_pose * ee_poses_map_[ee_jmg][i];
412  ee_markers_map_[ee_jmg].markers[i].pose = convertPose(eigen_this_marker);
413  }
414 
415  // Helper for publishing rviz markers
416  // Does not require trigger() because publishing array auto-triggers
417  if (!publishMarkers(ee_markers_map_[ee_jmg]))
418  {
419  ROS_WARN_STREAM_NAMED(LOGNAME, "Unable to publish EE markers");
420  return false;
421  }
422 
423  return true;
424 }
425 
426 bool MoveItVisualTools::publishGrasps(const std::vector<moveit_msgs::Grasp>& possible_grasps,
427  const moveit::core::JointModelGroup* ee_jmg, double animate_speed)
428 {
429  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Visualizing " << possible_grasps.size() << " grasps with EE joint model group "
430  << ee_jmg->getName());
431 
432  // Loop through all grasps
433  for (std::size_t i = 0; i < possible_grasps.size(); ++i)
434  {
435  if (!ros::ok()) // Check that ROS is still ok and that user isn't trying to quit
436  break;
437 
438  publishEEMarkers(possible_grasps[i].grasp_pose.pose, ee_jmg);
439 
440  ros::Duration(animate_speed).sleep();
441  }
442 
443  return true;
444 }
445 
446 bool MoveItVisualTools::publishAnimatedGrasps(const std::vector<moveit_msgs::Grasp>& possible_grasps,
447  const moveit::core::JointModelGroup* ee_jmg, double animate_speed)
448 {
449  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Visualizing " << possible_grasps.size() << " grasps with joint model group "
450  << ee_jmg->getName() << " at speed " << animate_speed);
451 
452  // Loop through all grasps
453  for (std::size_t i = 0; i < possible_grasps.size(); ++i)
454  {
455  if (!ros::ok()) // Check that ROS is still ok and that user isn't trying to quit
456  break;
457 
458  publishAnimatedGrasp(possible_grasps[i], ee_jmg, animate_speed);
459  ros::Duration(animate_speed).sleep();
460  }
461 
462  return true;
463 }
464 
465 bool MoveItVisualTools::publishAnimatedGrasp(const moveit_msgs::Grasp& grasp,
466  const moveit::core::JointModelGroup* ee_jmg, double animate_speed)
467 {
468  // Grasp Pose Variables
469  geometry_msgs::Pose grasp_pose = grasp.grasp_pose.pose;
470 
471 #if 0 // Debug
473  publishEEMarkers(grasp_pose, ee_jmg);
474  ros::Duration(0.5).sleep();
475 #endif
476 
477  Eigen::Isometry3d grasp_pose_eigen;
478  tf2::fromMsg(grasp_pose, grasp_pose_eigen);
479 
480  // Pre-grasp pose variables
481  geometry_msgs::Pose pre_grasp_pose;
482  Eigen::Isometry3d pre_grasp_pose_eigen;
483 
484  // Approach direction variables
485  Eigen::Vector3d pre_grasp_approach_direction_local;
486 
487  // Display Grasp Score
488  // std::string text = "Grasp Quality: " +
489  // boost::lexical_cast<std::string>(int(grasp.grasp_quality*100)) + "%";
490  // publishText(grasp_pose, text);
491 
492  // Convert the grasp pose into the frame of reference of the approach/retreat frame_id
493 
494  // Animate the movement - for ee approach direction
495  double animation_resulution = 0.1; // the lower the better the resolution
496  for (double percent = 0; percent < 1; percent += animation_resulution)
497  {
498  if (!ros::ok()) // Check that ROS is still ok and that user isn't trying to quit
499  break;
500 
501  // Copy original grasp pose to pre-grasp pose
502  pre_grasp_pose_eigen = grasp_pose_eigen;
503 
504  // The direction of the pre-grasp
505  // Calculate the current animation position based on the percent
506  Eigen::Vector3d pre_grasp_approach_direction = Eigen::Vector3d(
507  -1 * grasp.pre_grasp_approach.direction.vector.x * grasp.pre_grasp_approach.min_distance * (1 - percent),
508  -1 * grasp.pre_grasp_approach.direction.vector.y * grasp.pre_grasp_approach.min_distance * (1 - percent),
509  -1 * grasp.pre_grasp_approach.direction.vector.z * grasp.pre_grasp_approach.min_distance * (1 - percent));
510 
511  // Decide if we need to change the approach_direction to the local frame of the end effector
512  // orientation
513  const std::string& ee_parent_link_name = ee_jmg->getEndEffectorParentGroup().second;
514 
515  if (grasp.pre_grasp_approach.direction.header.frame_id == ee_parent_link_name)
516  {
517  // Apply/compute the approach_direction vector in the local frame of the grasp_pose
518  // orientation
519  pre_grasp_approach_direction_local = grasp_pose_eigen.rotation() * pre_grasp_approach_direction;
520  }
521  else
522  {
523  pre_grasp_approach_direction_local = pre_grasp_approach_direction; // grasp_pose_eigen.rotation() *
524  // pre_grasp_approach_direction;
525  }
526 
527  // Update the grasp pose usign the new locally-framed approach_direction
528  pre_grasp_pose_eigen.translation() += pre_grasp_approach_direction_local;
529 
530  // Convert eigen pre-grasp position back to regular message
531  pre_grasp_pose = tf2::toMsg(pre_grasp_pose_eigen);
532 
533  publishEEMarkers(pre_grasp_pose, ee_jmg);
534 
535  ros::Duration(animate_speed).sleep();
536 
537  // Pause more at initial pose for debugging purposes
538  if (percent == 0)
539  ros::Duration(animate_speed * 2).sleep();
540  }
541  return true;
542 }
543 
544 bool MoveItVisualTools::publishIKSolutions(const std::vector<trajectory_msgs::JointTrajectoryPoint>& ik_solutions,
545  const moveit::core::JointModelGroup* arm_jmg, double display_time)
546 {
547  if (ik_solutions.empty())
548  {
549  ROS_WARN_STREAM_NAMED(LOGNAME, "Empty ik_solutions vector passed into publishIKSolutions()");
550  return false;
551  }
552 
554 
555  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Visualizing " << ik_solutions.size() << " inverse kinematic solutions");
556 
557  // Apply the time to the trajectory
558  trajectory_msgs::JointTrajectoryPoint trajectory_pt_timed;
559 
560  // Create a trajectory with one point
561  moveit_msgs::RobotTrajectory trajectory_msg;
562  trajectory_msg.joint_trajectory.header.frame_id = base_frame_;
563  trajectory_msg.joint_trajectory.joint_names = arm_jmg->getActiveJointModelNames();
564 
565  // Overall length of trajectory
566  double running_time = 0;
567 
568  // Loop through all inverse kinematic solutions
569  for (std::size_t i = 0; i < ik_solutions.size(); ++i)
570  {
571  trajectory_pt_timed = ik_solutions[i];
572  trajectory_pt_timed.time_from_start = ros::Duration(running_time);
573  trajectory_msg.joint_trajectory.points.push_back(trajectory_pt_timed);
574 
575  running_time += display_time;
576  }
577 
578  // Re-add final position so the last point is displayed fully
579  trajectory_pt_timed = trajectory_msg.joint_trajectory.points.back();
580  trajectory_pt_timed.time_from_start = ros::Duration(running_time);
581  trajectory_msg.joint_trajectory.points.push_back(trajectory_pt_timed);
582 
583  return publishTrajectoryPath(trajectory_msg, shared_robot_state_, true);
584 }
585 
587 {
588  // Apply command directly to planning scene to avoid a ROS msg call
589  {
591  scene->removeAllCollisionObjects();
592  }
593 
594  return true;
595 }
596 
597 bool MoveItVisualTools::cleanupCO(const std::string& name)
598 {
599  // Clean up old collision objects
600  moveit_msgs::CollisionObject co;
601  co.header.stamp = ros::Time::now();
602  co.header.frame_id = base_frame_;
603  co.id = name;
604  co.operation = moveit_msgs::CollisionObject::REMOVE;
605 
606  return processCollisionObjectMsg(co);
607 }
608 
609 bool MoveItVisualTools::cleanupACO(const std::string& /*name*/)
610 {
611  // Clean up old attached collision object
612  moveit_msgs::AttachedCollisionObject aco;
613  aco.object.header.stamp = ros::Time::now();
614  aco.object.header.frame_id = base_frame_;
615 
616  // aco.object.id = name;
617  aco.object.operation = moveit_msgs::CollisionObject::REMOVE;
618 
620 }
621 
622 bool MoveItVisualTools::attachCO(const std::string& name, const std::string& ee_parent_link)
623 {
624  // Attach a collision object
625  moveit_msgs::AttachedCollisionObject aco;
626  aco.object.header.stamp = ros::Time::now();
627  aco.object.header.frame_id = base_frame_;
628 
629  aco.object.id = name;
630  aco.object.operation = moveit_msgs::CollisionObject::ADD;
631 
632  // Link to attach the object to
633  aco.link_name = ee_parent_link;
634 
636 }
637 
638 bool MoveItVisualTools::publishCollisionBlock(const geometry_msgs::Pose& block_pose, const std::string& name,
639  double block_size, const rviz_visual_tools::colors& color)
640 {
641  moveit_msgs::CollisionObject collision_obj;
642  collision_obj.header.stamp = ros::Time::now();
643  collision_obj.header.frame_id = base_frame_;
644  collision_obj.id = name;
645  collision_obj.operation = moveit_msgs::CollisionObject::ADD;
646 
647  collision_obj.primitives.resize(1);
648  collision_obj.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
649  collision_obj.primitives[0].dimensions.resize(
650  geometric_shapes::solidPrimitiveDimCount<shape_msgs::SolidPrimitive::BOX>());
651  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = block_size;
652  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = block_size;
653  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = block_size;
654  collision_obj.primitive_poses.resize(1);
655  collision_obj.primitive_poses[0] = block_pose;
656 
657  // ROS_INFO_STREAM_NAMED(LOGNAME,"CollisionObject: \n " << collision_obj);
658  // ROS_DEBUG_STREAM_NAMED(LOGNAME,"Published collision object " << name);
659  return processCollisionObjectMsg(collision_obj, color);
660 }
661 
662 bool MoveItVisualTools::publishCollisionCuboid(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2,
663  const std::string& name, const rviz_visual_tools::colors& color)
664 {
665  return publishCollisionCuboid(convertPoint(point1), convertPoint(point2), name, color);
666 }
667 
668 bool MoveItVisualTools::publishCollisionCuboid(const geometry_msgs::Point& point1, const geometry_msgs::Point& point2,
669  const std::string& name, const rviz_visual_tools::colors& color)
670 {
671  moveit_msgs::CollisionObject collision_obj;
672  collision_obj.header.stamp = ros::Time::now();
673  collision_obj.header.frame_id = base_frame_;
674  collision_obj.id = name;
675  collision_obj.operation = moveit_msgs::CollisionObject::ADD;
676 
677  // Calculate center pose
678  collision_obj.primitive_poses.resize(1);
679  collision_obj.primitive_poses[0].position.x = (point1.x - point2.x) / 2.0 + point2.x;
680  collision_obj.primitive_poses[0].position.y = (point1.y - point2.y) / 2.0 + point2.y;
681  collision_obj.primitive_poses[0].position.z = (point1.z - point2.z) / 2.0 + point2.z;
682 
683  // Calculate scale
684  collision_obj.primitives.resize(1);
685  collision_obj.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
686  collision_obj.primitives[0].dimensions.resize(
687  geometric_shapes::solidPrimitiveDimCount<shape_msgs::SolidPrimitive::BOX>());
688  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = fabs(point1.x - point2.x);
689  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = fabs(point1.y - point2.y);
690  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = fabs(point1.z - point2.z);
691 
692  // Prevent scale from being zero
693  if (!collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X])
694  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = rviz_visual_tools::SMALL_SCALE;
695  if (!collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y])
696  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = rviz_visual_tools::SMALL_SCALE;
697  if (!collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z])
698  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = rviz_visual_tools::SMALL_SCALE;
699 
700  // ROS_INFO_STREAM_NAMED(LOGNAME,"CollisionObject: \n " << collision_obj);
701  return processCollisionObjectMsg(collision_obj, color);
702 }
703 
704 bool MoveItVisualTools::publishCollisionCuboid(const Eigen::Isometry3d& pose, double width, double depth, double height,
705  const std::string& name, const rviz_visual_tools::colors& color)
706 {
707  geometry_msgs::Pose pose_msg = tf2::toMsg(pose);
708  return publishCollisionCuboid(pose_msg, width, depth, height, name, color);
709 }
710 
711 bool MoveItVisualTools::publishCollisionCuboid(const geometry_msgs::Pose& pose, double width, double depth,
712  double height, const std::string& name,
713  const rviz_visual_tools::colors& color)
714 {
715  moveit_msgs::CollisionObject collision_obj;
716  collision_obj.header.stamp = ros::Time::now();
717  collision_obj.header.frame_id = base_frame_;
718  collision_obj.id = name;
719  collision_obj.operation = moveit_msgs::CollisionObject::ADD;
720 
721  // Calculate center pose
722  collision_obj.primitive_poses.resize(1);
723  collision_obj.primitive_poses[0] = pose;
724 
725  // Calculate scale
726  collision_obj.primitives.resize(1);
727  collision_obj.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
728  collision_obj.primitives[0].dimensions.resize(
729  geometric_shapes::solidPrimitiveDimCount<shape_msgs::SolidPrimitive::BOX>());
730  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = width;
731  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = depth;
732  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = height;
733 
734  // Prevent scale from being zero
735  if (!collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X])
736  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = rviz_visual_tools::SMALL_SCALE;
737  if (!collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y])
738  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = rviz_visual_tools::SMALL_SCALE;
739  if (!collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z])
740  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = rviz_visual_tools::SMALL_SCALE;
741 
742  return processCollisionObjectMsg(collision_obj, color);
743 }
744 
745 bool MoveItVisualTools::publishCollisionFloor(double z, const std::string& plane_name,
746  const rviz_visual_tools::colors& color)
747 {
748  // Instead just generate a rectangle
749  geometry_msgs::Point point1;
750  geometry_msgs::Point point2;
751 
754  point1.z = z;
755 
756  point2.x = -rviz_visual_tools::LARGE_SCALE;
757  point2.y = -rviz_visual_tools::LARGE_SCALE;
758  point2.z = z - rviz_visual_tools::SMALL_SCALE;
759 
760  return publishCollisionCuboid(point1, point2, plane_name, color);
761 }
762 
763 bool MoveItVisualTools::publishCollisionCylinder(const geometry_msgs::Point& a, const geometry_msgs::Point& b,
764  const std::string& object_name, double radius,
765  const rviz_visual_tools::colors& color)
766 {
767  return publishCollisionCylinder(convertPoint(a), convertPoint(b), object_name, radius, color);
768 }
769 
770 bool MoveItVisualTools::publishCollisionCylinder(const Eigen::Vector3d& a, const Eigen::Vector3d& b,
771  const std::string& object_name, double radius,
772  const rviz_visual_tools::colors& color)
773 {
774  // Distance between two points
775  double height = (a - b).lpNorm<2>();
776 
777  // Find center point
778  Eigen::Vector3d pt_center = getCenterPoint(a, b);
779 
780  // Create vector
781  Eigen::Isometry3d pose;
782  pose = getVectorBetweenPoints(pt_center, b);
783 
784  // Convert pose to be normal to cylindar axis
785  Eigen::Isometry3d rotation;
786  rotation = Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitY());
787  pose = pose * rotation;
788 
789  return publishCollisionCylinder(pose, object_name, radius, height, color);
790 }
791 
792 bool MoveItVisualTools::publishCollisionCylinder(const Eigen::Isometry3d& object_pose, const std::string& object_name,
793  double radius, double height, const rviz_visual_tools::colors& color)
794 {
795  return publishCollisionCylinder(convertPose(object_pose), object_name, radius, height, color);
796 }
797 
798 bool MoveItVisualTools::publishCollisionCylinder(const geometry_msgs::Pose& object_pose, const std::string& object_name,
799  double radius, double height, const rviz_visual_tools::colors& color)
800 {
801  moveit_msgs::CollisionObject collision_obj;
802  collision_obj.header.stamp = ros::Time::now();
803  collision_obj.header.frame_id = base_frame_;
804  collision_obj.id = object_name;
805  collision_obj.operation = moveit_msgs::CollisionObject::ADD;
806  collision_obj.primitives.resize(1);
807  collision_obj.primitives[0].type = shape_msgs::SolidPrimitive::CYLINDER;
808  collision_obj.primitives[0].dimensions.resize(
809  geometric_shapes::solidPrimitiveDimCount<shape_msgs::SolidPrimitive::CYLINDER>());
810  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::CYLINDER_HEIGHT] = height;
811  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::CYLINDER_RADIUS] = radius;
812  collision_obj.primitive_poses.resize(1);
813  collision_obj.primitive_poses[0] = object_pose;
814 
815  // ROS_INFO_STREAM_NAMED(LOGNAME,"CollisionObject: \n " << collision_obj);
816  return processCollisionObjectMsg(collision_obj, color);
817 }
818 
819 bool MoveItVisualTools::publishCollisionMesh(const Eigen::Isometry3d& object_pose, const std::string& object_name,
820  const std::string& mesh_path, const rviz_visual_tools::colors& color)
821 {
822  return publishCollisionMesh(convertPose(object_pose), object_name, mesh_path, color);
823 }
824 
825 bool MoveItVisualTools::publishCollisionMesh(const geometry_msgs::Pose& object_pose, const std::string& object_name,
826  const std::string& mesh_path, const rviz_visual_tools::colors& color)
827 {
828  shapes::Shape* mesh = shapes::createMeshFromResource(mesh_path); // make sure its prepended by file://
829  shapes::ShapeMsg shape_msg; // this is a boost::variant type from shape_messages.h
830  if (!mesh || !shapes::constructMsgFromShape(mesh, shape_msg))
831  {
832  ROS_ERROR_STREAM_NAMED(LOGNAME, "Unable to create mesh shape message from resource " << mesh_path);
833  return false;
834  }
835 
836  if (!publishCollisionMesh(object_pose, object_name, boost::get<shape_msgs::Mesh>(shape_msg), color))
837  return false;
838 
839  ROS_DEBUG_NAMED(LOGNAME, "Loaded mesh from '%s'", mesh_path.c_str());
840  return true;
841 }
842 
843 bool MoveItVisualTools::publishCollisionMesh(const Eigen::Isometry3d& object_pose, const std::string& object_name,
844  const shape_msgs::Mesh& mesh_msg, const rviz_visual_tools::colors& color)
845 {
846  return publishCollisionMesh(convertPose(object_pose), object_name, mesh_msg, color);
847 }
848 
849 bool MoveItVisualTools::publishCollisionMesh(const geometry_msgs::Pose& object_pose, const std::string& object_name,
850  const shape_msgs::Mesh& mesh_msg, const rviz_visual_tools::colors& color)
851 {
852  // Create collision message
853  moveit_msgs::CollisionObject collision_obj;
854  collision_obj.header.stamp = ros::Time::now();
855  collision_obj.header.frame_id = base_frame_;
856  collision_obj.id = object_name;
857  collision_obj.operation = moveit_msgs::CollisionObject::ADD;
858  collision_obj.mesh_poses.resize(1);
859  collision_obj.mesh_poses[0] = object_pose;
860  collision_obj.meshes.resize(1);
861  collision_obj.meshes[0] = mesh_msg;
862 
863  return processCollisionObjectMsg(collision_obj, color);
864 }
865 
866 bool MoveItVisualTools::publishCollisionGraph(const graph_msgs::GeometryGraph& graph, const std::string& object_name,
867  double radius, const rviz_visual_tools::colors& color)
868 {
869  ROS_INFO_STREAM_NAMED("publishCollisionGraph", "Preparing to create collision graph");
870 
871  // The graph is one collision object with many primitives
872  moveit_msgs::CollisionObject collision_obj;
873  collision_obj.header.stamp = ros::Time::now();
874  collision_obj.header.frame_id = base_frame_;
875  collision_obj.id = object_name;
876  collision_obj.operation = moveit_msgs::CollisionObject::ADD;
877 
878  // Track which pairs of nodes we've already connected since graph is bi-directional
879  typedef std::pair<std::size_t, std::size_t> node_ids;
880  std::set<node_ids> added_edges;
881  std::pair<std::set<node_ids>::iterator, bool> return_value;
882 
883  Eigen::Vector3d a, b;
884  for (std::size_t i = 0; i < graph.nodes.size(); ++i)
885  {
886  for (std::size_t j = 0; j < graph.edges[i].node_ids.size(); ++j)
887  {
888  // Check if we've already added this pair of nodes (edge)
889  return_value = added_edges.insert(node_ids(i, j));
890  if (!return_value.second)
891  {
892  // Element already existed in set, so don't add a new collision object
893  }
894  else
895  {
896  // Create a cylinder from two points
897  a = convertPoint(graph.nodes[i]);
898  b = convertPoint(graph.nodes[graph.edges[i].node_ids[j]]);
899 
900  // add other direction of edge
901  added_edges.insert(node_ids(j, i));
902 
903  // Distance between two points
904  double height = (a - b).lpNorm<2>();
905 
906  // Find center point
907  Eigen::Vector3d pt_center = getCenterPoint(a, b);
908 
909  // Create vector
910  Eigen::Isometry3d pose;
911  pose = getVectorBetweenPoints(pt_center, b);
912 
913  // Convert pose to be normal to cylindar axis
914  Eigen::Isometry3d rotation;
915  rotation = Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitY());
916  pose = pose * rotation;
917 
918  // Create the solid primitive
919  shape_msgs::SolidPrimitive cylinder;
920  cylinder.type = shape_msgs::SolidPrimitive::CYLINDER;
921  cylinder.dimensions.resize(geometric_shapes::solidPrimitiveDimCount<shape_msgs::SolidPrimitive::CYLINDER>());
922  cylinder.dimensions[shape_msgs::SolidPrimitive::CYLINDER_HEIGHT] = height;
923  cylinder.dimensions[shape_msgs::SolidPrimitive::CYLINDER_RADIUS] = radius;
924 
925  // Add to the collision object
926  collision_obj.primitives.push_back(cylinder);
927 
928  // Add the pose
929  collision_obj.primitive_poses.push_back(convertPose(pose));
930  }
931  }
932  }
933 
934  return processCollisionObjectMsg(collision_obj, color);
935 }
936 
937 void MoveItVisualTools::getCollisionWallMsg(double x, double y, double z, double angle, double width, double height,
938  const std::string& name, moveit_msgs::CollisionObject& collision_obj)
939 {
940  collision_obj.header.stamp = ros::Time::now();
941  collision_obj.header.frame_id = base_frame_;
942  collision_obj.operation = moveit_msgs::CollisionObject::ADD;
943  collision_obj.primitives.resize(1);
944  collision_obj.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
945  collision_obj.primitives[0].dimensions.resize(
946  geometric_shapes::solidPrimitiveDimCount<shape_msgs::SolidPrimitive::BOX>());
947 
948  geometry_msgs::Pose rec_pose;
949 
950  // ----------------------------------------------------------------------------------
951  // Name
952  collision_obj.id = name;
953 
954  double depth = 0.1;
955 
956  // Position
957  rec_pose.position.x = x;
958  rec_pose.position.y = y;
959  rec_pose.position.z = height / 2 + z;
960 
961  // Size
962  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = depth;
963  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = width;
964  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = height;
965  // ----------------------------------------------------------------------------------
966 
967  Eigen::Quaterniond quat(Eigen::AngleAxis<double>(static_cast<double>(angle), Eigen::Vector3d::UnitZ()));
968  rec_pose.orientation.x = quat.x();
969  rec_pose.orientation.y = quat.y();
970  rec_pose.orientation.z = quat.z();
971  rec_pose.orientation.w = quat.w();
972 
973  collision_obj.primitive_poses.resize(1);
974  collision_obj.primitive_poses[0] = rec_pose;
975 }
976 
977 bool MoveItVisualTools::publishCollisionWall(double x, double y, double angle, double width, double height,
978  const std::string& name, const rviz_visual_tools::colors& color)
979 {
980  return publishCollisionWall(x, y, 0.0, angle, width, height, name, color);
981 }
982 
983 bool MoveItVisualTools::publishCollisionWall(double x, double y, double z, double angle, double width, double height,
984  const std::string& name, const rviz_visual_tools::colors& color)
985 {
986  moveit_msgs::CollisionObject collision_obj;
987  getCollisionWallMsg(x, y, z, angle, width, height, name, collision_obj);
988 
989  return processCollisionObjectMsg(collision_obj, color);
990 }
991 
992 bool MoveItVisualTools::publishCollisionTable(double x, double y, double z, double angle, double width, double height,
993  double depth, const std::string& name,
994  const rviz_visual_tools::colors& color)
995 {
996  geometry_msgs::Pose table_pose;
997 
998  // Center of table
999  table_pose.position.x = x;
1000  table_pose.position.y = y;
1001  table_pose.position.z = z + height / 2.0;
1002 
1003  // Orientation
1004  Eigen::Quaterniond quat(Eigen::AngleAxis<double>(static_cast<double>(angle), Eigen::Vector3d::UnitZ()));
1005  table_pose.orientation.x = quat.x();
1006  table_pose.orientation.y = quat.y();
1007  table_pose.orientation.z = quat.z();
1008  table_pose.orientation.w = quat.w();
1010  moveit_msgs::CollisionObject collision_obj;
1011  collision_obj.header.stamp = ros::Time::now();
1012  collision_obj.header.frame_id = base_frame_;
1013  collision_obj.id = name;
1014  collision_obj.operation = moveit_msgs::CollisionObject::ADD;
1015  collision_obj.primitives.resize(1);
1016  collision_obj.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
1017  collision_obj.primitives[0].dimensions.resize(
1018  geometric_shapes::solidPrimitiveDimCount<shape_msgs::SolidPrimitive::BOX>());
1019 
1020  // Size
1021  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = depth;
1022  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = width;
1023  collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = height;
1025  collision_obj.primitive_poses.resize(1);
1026  collision_obj.primitive_poses[0] = table_pose;
1027  return processCollisionObjectMsg(collision_obj, color);
1028 }
1029 
1030 bool MoveItVisualTools::loadCollisionSceneFromFile(const std::string& path)
1031 {
1032  return loadCollisionSceneFromFile(path, Eigen::Isometry3d::Identity());
1033 }
1034 
1035 bool MoveItVisualTools::loadCollisionSceneFromFile(const std::string& path, const Eigen::Isometry3d& offset)
1036 {
1037  // Open file
1038  std::ifstream fin(path.c_str());
1039  if (fin.good())
1040  {
1041  // Load directly to the planning scene
1043  {
1044  if (scene)
1045  {
1046  scene->loadGeometryFromStream(fin, offset);
1047  }
1048  else
1049  {
1050  ROS_WARN_STREAM_NAMED(LOGNAME, "Unable to get locked planning scene RW");
1051  return false;
1052  }
1053  }
1054  ROS_INFO_NAMED(LOGNAME, "Loaded scene geometry from '%s'", path.c_str());
1055  }
1056  else
1057  ROS_WARN_NAMED(LOGNAME, "Unable to load scene geometry from '%s'", path.c_str());
1058 
1059  fin.close();
1060 
1061  return triggerPlanningSceneUpdate();
1063 
1064 bool MoveItVisualTools::publishWorkspaceParameters(const moveit_msgs::WorkspaceParameters& params)
1065 {
1066  return publishCuboid(convertPoint(params.min_corner), convertPoint(params.max_corner), rviz_visual_tools::TRANSLUCENT,
1067  "Planning_Workspace", 1);
1068 }
1069 
1072  const rviz_visual_tools::colors& highlight_link_color,
1073  const rviz_visual_tools::colors& contact_point_color)
1074 {
1075  // Compute the contacts if any
1078  c_req.contacts = true;
1079  c_req.max_contacts = 10;
1080  c_req.max_contacts_per_pair = 3;
1081  c_req.verbose = true;
1082 
1083  // Check for collisions
1084  planning_scene->checkCollision(c_req, c_res, robot_state);
1085  std::vector<std::string> highlight_links;
1086  for (const auto& contact : c_res.contacts)
1087  {
1088  highlight_links.push_back(contact.first.first);
1089  highlight_links.push_back(contact.first.second);
1090  }
1091 
1092  publishRobotState(robot_state, highlight_link_color, highlight_links);
1093  publishContactPoints(c_res.contacts, planning_scene, contact_point_color);
1094  return c_res.collision;
1095 }
1099  const rviz_visual_tools::colors& color)
1100 {
1101  // Compute the contacts if any
1104  c_req.contacts = true;
1105  c_req.max_contacts = 10;
1106  c_req.max_contacts_per_pair = 3;
1107  c_req.verbose = true;
1108 
1109  // Check for collisions
1110  planning_scene->checkCollision(c_req, c_res, robot_state);
1111  return publishContactPoints(c_res.contacts, planning_scene, color);
1112 }
1113 
1116  const rviz_visual_tools::colors& color)
1117 {
1118  // Display
1119  if (!contacts.empty())
1120  {
1121  visualization_msgs::MarkerArray arr;
1122  collision_detection::getCollisionMarkersFromContacts(arr, planning_scene->getPlanningFrame(), contacts);
1123  ROS_INFO_STREAM_NAMED(LOGNAME, "Completed listing of explanations for invalid states.");
1124 
1125  // Check for markers
1126  if (arr.markers.empty())
1127  return true;
1128 
1129  // Convert markers to same namespace and other custom stuff
1130  for (std::size_t i = 0; i < arr.markers.size(); ++i)
1131  {
1132  arr.markers[i].ns = "Collision";
1133  arr.markers[i].id = i;
1134  arr.markers[i].scale.x = 0.04;
1135  arr.markers[i].scale.y = 0.04;
1136  arr.markers[i].scale.z = 0.04;
1137  arr.markers[i].color = getColor(color);
1138  }
1139 
1140  return publishMarkers(arr);
1141  }
1142  return true;
1143 }
1144 
1145 bool MoveItVisualTools::publishTrajectoryPoint(const trajectory_msgs::JointTrajectoryPoint& trajectory_pt,
1146  const std::string& planning_group, double display_time)
1147 {
1148  // Ensure robot_model_ is available
1150 
1151  // Get joint state group
1152  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(planning_group);
1153 
1154  if (jmg == nullptr) // not found
1155  {
1156  ROS_ERROR_STREAM_NAMED("publishTrajectoryPoint", "Could not find joint model group " << planning_group);
1157  return false;
1158  }
1159 
1160  // Apply the time to the trajectory
1161  trajectory_msgs::JointTrajectoryPoint trajectory_pt_timed = trajectory_pt;
1162  trajectory_pt_timed.time_from_start = ros::Duration(display_time);
1163 
1164  // Create a trajectory with one point
1165  moveit_msgs::RobotTrajectory trajectory_msg;
1166  trajectory_msg.joint_trajectory.header.frame_id = base_frame_;
1167  trajectory_msg.joint_trajectory.joint_names = jmg->getJointModelNames();
1168  trajectory_msg.joint_trajectory.points.push_back(trajectory_pt);
1169  trajectory_msg.joint_trajectory.points.push_back(trajectory_pt_timed);
1170 
1171  return publishTrajectoryPath(trajectory_msg, shared_robot_state_, true);
1172 }
1173 
1174 bool MoveItVisualTools::publishTrajectoryPath(const std::vector<moveit::core::RobotStatePtr>& trajectory,
1175  const moveit::core::JointModelGroup* jmg, double speed, bool blocking)
1176 {
1177  // Ensure robot_model_ is available
1179 
1180  // Copy the vector of RobotStates to a RobotTrajectory
1181  robot_trajectory::RobotTrajectoryPtr robot_trajectory(
1183 
1184  double duration_from_previous = 0;
1185  for (std::size_t k = 0; k < trajectory.size(); ++k)
1186  {
1187  duration_from_previous += speed;
1188  robot_trajectory->addSuffixWayPoint(trajectory[k], duration_from_previous);
1189  }
1190 
1191  // Convert trajectory to a message
1192  moveit_msgs::RobotTrajectory trajectory_msg;
1193  robot_trajectory->getRobotTrajectoryMsg(trajectory_msg);
1194 
1195  // Use first trajectory point as reference state
1196  moveit_msgs::RobotState robot_state_msg;
1197  if (!trajectory.empty())
1198  moveit::core::robotStateToRobotStateMsg(*trajectory[0], robot_state_msg);
1199 
1200  return publishTrajectoryPath(trajectory_msg, robot_state_msg, blocking);
1201 }
1202 
1203 bool MoveItVisualTools::publishTrajectoryPath(const robot_trajectory::RobotTrajectoryPtr& trajectory, bool blocking)
1204 {
1205  return publishTrajectoryPath(*trajectory, blocking);
1207 
1209 {
1210  moveit_msgs::RobotTrajectory trajectory_msg;
1211  trajectory.getRobotTrajectoryMsg(trajectory_msg);
1212 
1213  // Add time from start if none specified
1214  if (trajectory_msg.joint_trajectory.points.size() > 1)
1215  {
1216  if (trajectory_msg.joint_trajectory.points[1].time_from_start == ros::Duration(0)) // assume no timestamps exist
1217  {
1218  for (std::size_t i = 0; i < trajectory_msg.joint_trajectory.points.size(); ++i)
1219  {
1220  trajectory_msg.joint_trajectory.points[i].time_from_start = ros::Duration(i * 2); // 1 hz
1221  }
1222  }
1223  }
1224 
1225  // Use first trajectory point as reference state
1226  moveit_msgs::RobotState robot_state_msg;
1227  if (!trajectory.empty())
1228  moveit::core::robotStateToRobotStateMsg(trajectory.getFirstWayPoint(), robot_state_msg);
1229 
1230  return publishTrajectoryPath(trajectory_msg, robot_state_msg, blocking);
1231 }
1232 
1233 bool MoveItVisualTools::publishTrajectoryPath(const moveit_msgs::RobotTrajectory& trajectory_msg,
1234  const moveit::core::RobotStateConstPtr& robot_state, bool blocking)
1236  return publishTrajectoryPath(trajectory_msg, *robot_state, blocking);
1237 }
1238 
1239 bool MoveItVisualTools::publishTrajectoryPath(const moveit_msgs::RobotTrajectory& trajectory_msg,
1240  const moveit::core::RobotState& robot_state, bool blocking)
1241 {
1242  // Convert the robot state to a ROS message
1243  moveit_msgs::RobotState robot_state_msg;
1244  moveit::core::robotStateToRobotStateMsg(robot_state, robot_state_msg);
1245  return publishTrajectoryPath(trajectory_msg, robot_state_msg, blocking);
1246 }
1247 
1248 bool MoveItVisualTools::publishTrajectoryPath(const moveit_msgs::RobotTrajectory& trajectory_msg,
1249  const moveit_msgs::RobotState& robot_state, bool blocking)
1250 {
1251  // Check if we have enough points
1252  if (trajectory_msg.joint_trajectory.points.empty())
1253  {
1254  ROS_WARN_STREAM_NAMED(LOGNAME, "Unable to publish trajectory path because trajectory has zero points");
1255  return false;
1256  }
1257 
1258  // Ensure that the robot name is available.
1260 
1261  // Create the message
1262  moveit_msgs::DisplayTrajectory display_trajectory_msg;
1263  display_trajectory_msg.model_id = robot_model_->getName();
1264  display_trajectory_msg.trajectory.resize(1);
1265  display_trajectory_msg.trajectory[0] = trajectory_msg;
1266  display_trajectory_msg.trajectory_start = robot_state;
1267 
1268  publishTrajectoryPath(display_trajectory_msg);
1269 
1270  // Wait the duration of the trajectory
1271  if (blocking)
1272  {
1273  double duration = trajectory_msg.joint_trajectory.points.back().time_from_start.toSec();
1274 
1275  // If trajectory has not been parameterized, assume each waypoint takes 0.05 seconds (based on Rviz)
1276  if (duration < std::numeric_limits<double>::epsilon())
1277  {
1278  duration = 0.05 * trajectory_msg.joint_trajectory.points.size();
1279  }
1280  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Waiting for trajectory animation " << duration << " seconds");
1281 
1282  // Check if ROS is ok in intervals
1283  double counter = 0;
1284  static const double CHECK_TIME_INTERVAL = 0.25; // check every fourth second
1285  while (ros::ok() && counter <= duration)
1286  {
1287  counter += CHECK_TIME_INTERVAL;
1288  ros::Duration(CHECK_TIME_INTERVAL).sleep();
1289  }
1290  }
1291 
1292  return true;
1293 }
1294 
1295 void MoveItVisualTools::publishTrajectoryPath(const moveit_msgs::DisplayTrajectory& display_trajectory_msg)
1296 {
1297  // Publish message
1298  loadTrajectoryPub(); // always call this before publishing
1299  pub_display_path_.publish(display_trajectory_msg);
1300  ros::spinOnce();
1301 }
1302 
1303 bool MoveItVisualTools::publishTrajectoryLine(const moveit_msgs::RobotTrajectory& trajectory_msg,
1304  const moveit::core::LinkModel* ee_parent_link,
1305  const moveit::core::JointModelGroup* arm_jmg,
1306  const rviz_visual_tools::colors& color)
1307 {
1308  // Error check
1309  if (!arm_jmg)
1310  {
1311  ROS_FATAL_STREAM_NAMED(LOGNAME, "arm_jmg is NULL");
1312  return false;
1313  }
1314 
1315  // Always load the robot state before using
1317 
1318  // Convert trajectory into a series of RobotStates
1319  robot_trajectory::RobotTrajectoryPtr robot_trajectory(
1321  robot_trajectory->setRobotTrajectoryMsg(*shared_robot_state_, trajectory_msg);
1322 
1323  return publishTrajectoryLine(robot_trajectory, ee_parent_link, color);
1324 }
1325 
1326 bool MoveItVisualTools::publishTrajectoryLine(const robot_trajectory::RobotTrajectoryPtr& robot_trajectory,
1327  const moveit::core::LinkModel* ee_parent_link,
1328  const rviz_visual_tools::colors& color)
1329 {
1330  return publishTrajectoryLine(*robot_trajectory, ee_parent_link, color);
1331 }
1332 
1334  const moveit::core::LinkModel* ee_parent_link,
1336 {
1337  // Error check
1338  if (!ee_parent_link)
1339  {
1340  ROS_FATAL_STREAM_NAMED(LOGNAME, "ee_parent_link is NULL");
1341  return false;
1342  }
1343 
1344  // Point location datastructure
1346 
1347  // Visualize end effector position of cartesian path
1348  for (std::size_t i = 0; i < robot_trajectory.getWayPointCount(); ++i)
1349  {
1350  const Eigen::Isometry3d& tip_pose = robot_trajectory.getWayPoint(i).getGlobalLinkTransform(ee_parent_link);
1351 
1352  // Error Check
1353  if (tip_pose.translation().x() != tip_pose.translation().x())
1354  {
1355  ROS_ERROR_STREAM_NAMED(LOGNAME, "NAN DETECTED AT TRAJECTORY POINT i=" << i);
1356  return false;
1357  }
1359  path.push_back(tip_pose.translation());
1360  publishSphere(tip_pose, color, rviz_visual_tools::MEDIUM);
1361  }
1362 
1363  const double radius = 0.005;
1364  publishPath(path, color, radius);
1366  return true;
1367 }
1368 
1369 bool MoveItVisualTools::publishTrajectoryLine(const moveit_msgs::RobotTrajectory& trajectory_msg,
1370  const moveit::core::JointModelGroup* arm_jmg,
1371  const rviz_visual_tools::colors& color)
1372 {
1373  if (!arm_jmg)
1374  {
1375  ROS_FATAL_STREAM_NAMED(LOGNAME, "arm_jmg is NULL");
1376  return false;
1377  }
1378 
1379  std::vector<const moveit::core::LinkModel*> tips;
1380  if (!arm_jmg->getEndEffectorTips(tips) || tips.empty())
1381  {
1382  ROS_ERROR_STREAM_NAMED(LOGNAME, "Unable to get end effector tips from jmg");
1383  return false;
1384  }
1385 
1386  // For each end effector
1387  for (const moveit::core::LinkModel* ee_parent_link : tips)
1388  {
1389  if (!publishTrajectoryLine(trajectory_msg, ee_parent_link, arm_jmg, color))
1390  return false;
1391  }
1392 
1393  return true;
1394 }
1395 
1396 bool MoveItVisualTools::publishTrajectoryLine(const robot_trajectory::RobotTrajectoryPtr& robot_trajectory,
1397  const moveit::core::JointModelGroup* arm_jmg,
1398  const rviz_visual_tools::colors& color)
1399 {
1400  return publishTrajectoryLine(*robot_trajectory, arm_jmg, color);
1402 
1404  const moveit::core::JointModelGroup* arm_jmg,
1405  const rviz_visual_tools::colors& color)
1406 {
1407  if (!arm_jmg)
1408  {
1409  ROS_FATAL_STREAM_NAMED(LOGNAME, "arm_jmg is NULL");
1410  return false;
1411  }
1412 
1413  std::vector<const moveit::core::LinkModel*> tips;
1414  if (!arm_jmg->getEndEffectorTips(tips) || tips.empty())
1415  {
1416  ROS_ERROR_STREAM_NAMED(LOGNAME, "Unable to get end effector tips from jmg");
1417  return false;
1418  }
1419 
1420  // For each end effector
1421  for (const moveit::core::LinkModel* ee_parent_link : tips)
1422  {
1423  if (!publishTrajectoryLine(robot_trajectory, ee_parent_link, color))
1424  return false;
1425  }
1426 
1427  return true;
1429 
1430 bool MoveItVisualTools::publishTrajectoryPoints(const std::vector<moveit::core::RobotStatePtr>& robot_state_trajectory,
1431  const moveit::core::LinkModel* ee_parent_link,
1432  const rviz_visual_tools::colors& color)
1433 {
1434  // Visualize end effector position of cartesian path
1435  for (std::size_t i = 0; i < robot_state_trajectory.size(); ++i)
1436  {
1437  const Eigen::Isometry3d& tip_pose = robot_state_trajectory[i]->getGlobalLinkTransform(ee_parent_link);
1438 
1439  publishSphere(tip_pose, color);
1440  }
1441  return true;
1442 }
1443 
1444 void MoveItVisualTools::enableRobotStateRootOffet(const Eigen::Isometry3d& offset)
1445 {
1447  robot_state_root_offset_ = offset;
1448 }
1449 
1451 {
1453 }
1454 
1455 bool MoveItVisualTools::publishRobotState(const trajectory_msgs::JointTrajectoryPoint& trajectory_pt,
1456  const moveit::core::JointModelGroup* jmg,
1457  const rviz_visual_tools::colors& color)
1458 {
1459  return publishRobotState(trajectory_pt.positions, jmg, color);
1460 }
1461 
1462 bool MoveItVisualTools::publishRobotState(const std::vector<double>& joint_positions,
1463  const moveit::core::JointModelGroup* jmg,
1464  const rviz_visual_tools::colors& color)
1465 {
1466  // Always load the robot state before using
1468 
1469  // Set robot state
1470  shared_robot_state_->setToDefaultValues(); // reset the state just in case
1471  shared_robot_state_->setJointGroupPositions(jmg, joint_positions);
1472 
1473  // Publish robot state
1474  return publishRobotState(*shared_robot_state_, color);
1475 }
1477 bool MoveItVisualTools::publishRobotState(const moveit::core::RobotStatePtr& robot_state,
1478  const rviz_visual_tools::colors& color,
1479  const std::vector<std::string>& highlight_links)
1480 {
1481  return publishRobotState(*robot_state.get(), color, highlight_links);
1483 
1485  const rviz_visual_tools::colors& color,
1486  const std::vector<std::string>& highlight_links)
1488  // when only a subset of links should be colored, the default message is used rather than the cached solid robot
1489  // messages
1490  rviz_visual_tools::colors base_color = color;
1491  if (!highlight_links.empty())
1492  base_color = rviz_visual_tools::DEFAULT;
1493 
1494  // Reference to the correctly colored version of message (they are cached)
1495  // May not exist yet but this will create it
1496  moveit_msgs::DisplayRobotState& display_robot_msg = display_robot_msgs_[base_color];
1497 
1498  // Check if a robot state message already exists for this color
1499  if (display_robot_msg.highlight_links.empty()) // has not been colored yet, lets create that
1500  {
1501  if (color != rviz_visual_tools::DEFAULT) // ignore color highlights when set to default
1502  {
1503  // Get links names
1504  const std::vector<std::string>& link_names =
1505  highlight_links.empty() ? robot_state.getRobotModel()->getLinkModelNamesWithCollisionGeometry() :
1506  highlight_links;
1507  display_robot_msg.highlight_links.resize(link_names.size());
1508 
1509  // Get color
1510  const std_msgs::ColorRGBA& color_rgba = getColor(color);
1511 
1512  // Color every link
1513  for (std::size_t i = 0; i < link_names.size(); ++i)
1514  {
1515  display_robot_msg.highlight_links[i].id = link_names[i];
1516  display_robot_msg.highlight_links[i].color = color_rgba;
1517  }
1518  }
1519  }
1520 
1521  // Apply the offset
1523  {
1525 
1526  // Copy robot state
1527  *shared_robot_state_ = robot_state;
1528 
1530 
1531  // Convert state to message
1533  }
1534  else
1535  {
1536  // Convert state to message
1537  moveit::core::robotStateToRobotStateMsg(robot_state, display_robot_msg.state);
1538  }
1539 
1540  // Publish
1541  publishRobotState(display_robot_msg);
1542 
1543  // remove highlight links from default message
1544  if (!highlight_links.empty())
1545  display_robot_msg.highlight_links.clear();
1546 
1547  return true;
1548 }
1549 
1550 void MoveItVisualTools::publishRobotState(const moveit_msgs::DisplayRobotState& robot_state_msg)
1551 {
1553  pub_robot_state_.publish(robot_state_msg);
1554  ros::spinOnce();
1555 }
1556 
1558 {
1559  moveit_msgs::DisplayRobotState display_robot_state_msg;
1560  // Hide the robot state
1561  display_robot_state_msg.hide = true;
1562 
1563  // Publish
1564  publishRobotState(display_robot_state_msg);
1565  return true;
1566 }
1567 
1568 void MoveItVisualTools::showJointLimits(const moveit::core::RobotStatePtr& robot_state)
1569 {
1570  const std::vector<const moveit::core::JointModel*>& joints = robot_state->getRobotModel()->getActiveJointModels();
1571 
1572  // Loop through joints
1573  for (std::size_t i = 0; i < joints.size(); ++i)
1574  {
1575  // Assume all joints have only one variable
1576  if (joints[i]->getVariableCount() > 1)
1577  {
1578  // ROS_WARN_STREAM_NAMED(LOGNAME, "Unable to handle joints with more than one var, skipping '"
1579  //<< joints[i]->getName() << "'");
1580  continue;
1581  }
1583  double current_value = robot_state->getVariablePosition(joints[i]->getName());
1584 
1585  // check if bad position
1586  bool out_of_bounds = !robot_state->satisfiesBounds(joints[i]);
1587 
1588  const moveit::core::VariableBounds& bound = joints[i]->getVariableBounds()[0];
1590  if (out_of_bounds)
1591  std::cout << MOVEIT_CONSOLE_COLOR_RED;
1592 
1593  std::cout << " " << std::fixed << std::setprecision(5) << bound.min_position_ << "\t";
1594  double delta = bound.max_position_ - bound.min_position_;
1595  // std::cout << "delta: " << delta << " ";
1596  double step = delta / 20.0;
1597 
1598  bool marker_shown = false;
1599  for (double value = bound.min_position_; value < bound.max_position_; value += step)
1600  {
1601  // show marker of current value
1602  if (!marker_shown && current_value < value)
1603  {
1604  std::cout << "|";
1605  marker_shown = true;
1606  }
1607  else
1608  std::cout << "-";
1609  }
1610  // show max position
1611  std::cout << " \t" << std::fixed << std::setprecision(5) << bound.max_position_ << " \t" << joints[i]->getName()
1612  << " current: " << std::fixed << std::setprecision(5) << current_value << std::endl;
1613 
1614  if (out_of_bounds)
1615  std::cout << MOVEIT_CONSOLE_COLOR_RESET;
1616  }
1617 }
1618 
1625 planning_scene_monitor::PlanningSceneMonitorPtr MoveItVisualTools::getPlanningSceneMonitor()
1626 {
1627  if (!psm_)
1628  {
1629  ROS_INFO_STREAM_NAMED(LOGNAME, "No planning scene passed into moveit_visual_tools, creating one.");
1631  ros::spinOnce();
1632  ros::Duration(1).sleep(); // TODO: is this necessary?
1633  }
1634  return psm_;
1635 }
1636 
1638 {
1639  static const std::string VJOINT_NAME = "virtual_joint";
1640 
1641  // Check if joint exists
1642  if (!robot_state.getRobotModel()->hasJointModel(VJOINT_NAME))
1643  {
1644  ROS_WARN_STREAM_NAMED("moveit_visual_tools", "Joint '" << VJOINT_NAME << "' does not exist.");
1645  return false;
1646  }
1647 
1648  // Check if variables exist
1649  if (!robot_state.getRobotModel()->getJointModel(VJOINT_NAME)->hasVariable(VJOINT_NAME + "/trans_x"))
1650  {
1651  // Debug
1652  ROS_WARN_STREAM_NAMED("moveit_visual_tools", "Variables for joint '" << VJOINT_NAME
1653  << "' do not exist. Try making this vjoint "
1654  "floating");
1655  ROS_WARN_STREAM_NAMED("moveit_visual_tools", "The only available joint variables are:");
1656  const std::vector<std::string>& var_names =
1657  robot_state.getRobotModel()->getJointModel(VJOINT_NAME)->getVariableNames();
1658  std::copy(var_names.begin(), var_names.end(), std::ostream_iterator<std::string>(std::cout, "\n"));
1659  return false;
1660  }
1661 
1662  return true;
1663 }
1664 
1666  const Eigen::Isometry3d& offset)
1667 {
1668  static const std::string VJOINT_NAME = "virtual_joint";
1670  // Error check
1671  if (!checkForVirtualJoint(robot_state))
1672  {
1673  ROS_WARN_STREAM_NAMED("moveit_visual_tools", "Unable to apply virtual joint transform, hideRobot() functionality "
1674  "is disabled");
1675  return false;
1676  }
1677 
1678  // Apply translation
1679  robot_state.setVariablePosition(VJOINT_NAME + "/trans_x", offset.translation().x());
1680  robot_state.setVariablePosition(VJOINT_NAME + "/trans_y", offset.translation().y());
1681  robot_state.setVariablePosition(VJOINT_NAME + "/trans_z", offset.translation().z());
1682 
1683  // Apply rotation
1684  Eigen::Quaterniond q(offset.rotation());
1685  robot_state.setVariablePosition(VJOINT_NAME + "/rot_x", q.x());
1686  robot_state.setVariablePosition(VJOINT_NAME + "/rot_y", q.y());
1687  robot_state.setVariablePosition(VJOINT_NAME + "/rot_z", q.z());
1688  robot_state.setVariablePosition(VJOINT_NAME + "/rot_w", q.w());
1689 
1690  return true;
1691 }
1692 
1693 } // namespace moveit_visual_tools
moveit_visual_tools::MoveItVisualTools::robot_model_
moveit::core::RobotModelConstPtr robot_model_
Definition: moveit_visual_tools.h:762
moveit::core::LinkModel
shapes::ShapeMsg
boost::variant< shape_msgs::SolidPrimitive, shape_msgs::Mesh, shape_msgs::Plane > ShapeMsg
moveit::core::JointModelGroup::getActiveJointModels
const std::vector< const JointModel * > & getActiveJointModels() const
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
rviz_visual_tools::RvizVisualTools::getColor
std_msgs::ColorRGBA getColor(colors color) const
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
duration
std::chrono::system_clock::duration duration
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
angle
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
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::core::JointModelGroup::getActiveJointModelNames
const std::vector< std::string > & getActiveJointModelNames() const
moveit::core::VariableBounds
collision_tools.h
moveit_visual_tools::MoveItVisualTools::loadSharedRobotState
bool loadSharedRobotState()
Load robot state only as needed.
Definition: moveit_visual_tools.cpp:239
tf2_eigen.h
tf2::fromMsg
void fromMsg(const A &, B &b)
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
rviz_visual_tools::RvizVisualTools::getCenterPoint
Eigen::Vector3d getCenterPoint(const Eigen::Vector3d &a, const Eigen::Vector3d &b) const
moveit_visual_tools::MoveItVisualTools::planning_scene_topic_
std::string planning_scene_topic_
Definition: moveit_visual_tools.h:743
rviz_visual_tools::RvizVisualTools::getVectorBetweenPoints
Eigen::Isometry3d getVectorBetweenPoints(const Eigen::Vector3d &a, const Eigen::Vector3d &b) const
planning_scene::PlanningScene
getName
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
rviz_visual_tools::RvizVisualTools::publishPath
bool publishPath(const EigenSTL::vector_Isometry3d &path, colors color, scales scale, const std::string &ns="Path")
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
collision_detection::getCollisionMarkersFromContacts
void getCollisionMarkersFromContacts(visualization_msgs::MarkerArray &arr, const std::string &frame_id, const CollisionResult::ContactMap &con)
ros::spinOnce
ROSCPP_DECL void spinOnce()
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
shape_operations.h
rviz_visual_tools
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
step
unsigned int step
shapes::Shape
moveit_visual_tools::DISPLAY_ROBOT_STATE_TOPIC
static const std::string DISPLAY_ROBOT_STATE_TOPIC
Definition: moveit_visual_tools.h:104
MOVEIT_CONSOLE_COLOR_RESET
#define MOVEIT_CONSOLE_COLOR_RESET
robot_trajectory::RobotTrajectory
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
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
planning_scene_monitor::PlanningSceneMonitor
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
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
collision_detection::CollisionRequest
ros::ok
ROSCPP_DECL bool ok()
rviz_visual_tools::RvizVisualTools::waitForSubscriber
bool waitForSubscriber(const ros::Publisher &pub, double wait_time=0.5, bool blocking=false)
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
rviz_visual_tools::SMALL_SCALE
static const double SMALL_SCALE
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::core::JointModelGroup::getEndEffectorTips
bool getEndEffectorTips(std::vector< const LinkModel * > &tips) const
planning_scene_monitor::LockedPlanningSceneRW
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::core::JointModelGroup::getName
const std::string & getName() const
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::MoveItVisualTools::root_robot_state_
moveit::core::RobotStatePtr root_robot_state_
Definition: moveit_visual_tools.h:772
robot_trajectory
robot_trajectory::RobotTrajectory::getRobotTrajectoryMsg
void getRobotTrajectoryMsg(moveit_msgs::RobotTrajectory &trajectory, const std::vector< std::string > &joint_filter=std::vector< std::string >()) const
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
name
std::string name
moveit::core::RobotState::setVariablePosition
void setVariablePosition(const std::string &variable, double value)
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
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
collision_detection::CollisionResult
rviz_visual_tools::RvizVisualTools::publishCuboid
bool publishCuboid(const Eigen::Isometry3d &pose, const Eigen::Vector3d &size, colors color=BLUE)
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
bound
template Interval< double > bound(const Interval< double > &i, const Interval< double > &other)
rviz_visual_tools::RvizVisualTools::marker_lifetime_
ros::Duration marker_lifetime_
y
double y
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
EigenSTL::vector_Vector3d
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
collision_detection::CollisionRequest::max_contacts
std::size_t max_contacts
moveit::core::JointModelGroup::getJointModelNames
const std::vector< std::string > & getJointModelNames() const
moveit::core::RobotState::getRobotModel
const RobotModelConstPtr & getRobotModel() const
MOVEIT_CONSOLE_COLOR_RED
#define MOVEIT_CONSOLE_COLOR_RED
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
collision_detection::CollisionRequest::verbose
bool verbose
robot_trajectory::RobotTrajectory::empty
bool empty() const
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::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
shapes::createMeshFromResource
Mesh * createMeshFromResource(const std::string &resource)
rviz_visual_tools::TRANSLUCENT
TRANSLUCENT
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
rviz_visual_tools::RvizVisualTools::publishArrow
bool publishArrow(const Eigen::Isometry3d &pose, colors color=BLUE, scales scale=MEDIUM, double length=0.0, std::size_t id=0)
rviz_visual_tools::LARGE_SCALE
static const double LARGE_SCALE
rviz_visual_tools::RvizVisualTools::publishSphere
bool publishSphere(const Eigen::Isometry3d &pose, colors color=BLUE, scales scale=MEDIUM, const std::string &ns="Sphere", std::size_t id=0)
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
rviz_visual_tools::RvizVisualTools::convertPoint
static geometry_msgs::Point convertPoint(const Eigen::Vector3d &point)
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
robot_trajectory::RobotTrajectory::getFirstWayPoint
const moveit::core::RobotState & getFirstWayPoint() const
ROS_WARN_STREAM_NAMED
#define ROS_WARN_STREAM_NAMED(name, args)
shapes::constructMsgFromShape
bool constructMsgFromShape(const Shape *shape, ShapeMsg &shape_msg)
rviz_visual_tools::RvizVisualTools::nh_
ros::NodeHandle nh_
collision_detection::CollisionResult::contacts
ContactMap contacts
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::core::JointModelGroup::getLinkModelNames
const std::vector< std::string > & getLinkModelNames() const
solid_primitive_dims.h
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
transform_listener.h
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
ros::Publisher::getTopic
std::string getTopic() const
moveit_visual_tools::MoveItVisualTools::pub_robot_state_
ros::Publisher pub_robot_state_
Definition: moveit_visual_tools.h:747
rviz_visual_tools::RvizVisualTools::publishMarkers
bool publishMarkers(visualization_msgs::MarkerArray &markers)
moveit_visual_tools::MoveItVisualTools::MoveItVisualTools
MoveItVisualTools()
Constructor.
Definition: moveit_visual_tools.cpp:102
tf_buffer
tf2_ros::Buffer * tf_buffer
std
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_visual_tools::LOGNAME
const std::string LOGNAME
Definition: moveit_visual_tools.cpp:100
collision_detection::CollisionRequest::contacts
bool contacts
rviz_visual_tools::MEDIUM
MEDIUM
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
moveit::core::JointModelGroup
rviz_visual_tools::RvizVisualTools::base_frame_
std::string base_frame_
moveit_visual_tools::MoveItVisualTools::robot_state_root_offset_
Eigen::Isometry3d robot_state_root_offset_
Definition: moveit_visual_tools.h:776
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
planning_scene_monitor::PlanningSceneMonitor::UPDATE_GEOMETRY
UPDATE_GEOMETRY
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
tf2::toMsg
B toMsg(const A &a)
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
collision_detection::CollisionResult::collision
bool collision
conversions.h
x
double x
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
ros::Duration::sleep
bool sleep() const
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
planning_scene_monitor::PlanningSceneMonitor::UPDATE_SCENE
UPDATE_SCENE
moveit_visual_tools::MoveItVisualTools::getSharedRobotState
moveit::core::RobotStatePtr & getSharedRobotState()
Allow robot state to be altered.
Definition: moveit_visual_tools.cpp:267
collision_detection::CollisionRequest::max_contacts_per_pair
std::size_t max_contacts_per_pair
moveit_visual_tools::MoveItVisualTools::shared_robot_state_
moveit::core::RobotStatePtr shared_robot_state_
Definition: moveit_visual_tools.h:765
console_colors.h
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::core::JointModelGroup::getEndEffectorParentGroup
const std::pair< std::string, std::string > & getEndEffectorParentGroup() const
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.h
moveit_visual_tools
Definition: imarker_end_effector.h:62
ros::Duration
z
double z
moveit::core::robotStateToRobotStateMsg
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
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::GREY
GREY
rviz_visual_tools::DEFAULT
DEFAULT
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
ros::Time::now
static Time now()


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