moveit_visual_tools.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015, University of Colorado, Boulder
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Univ of CO, Boulder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 // Author: Dave Coleman
00036 // Desc:   Simple tools for showing parts of a robot in Rviz, such as the gripper or arm
00037 
00038 #include <moveit_visual_tools/moveit_visual_tools.h>
00039 
00040 // MoveIt Messages
00041 #include <moveit_msgs/DisplayTrajectory.h>
00042 #include <moveit_msgs/CollisionObject.h>
00043 
00044 // MoveIt
00045 #include <moveit/robot_state/conversions.h>
00046 #include <moveit/collision_detection/collision_tools.h>
00047 
00048 // Conversions
00049 #include <tf_conversions/tf_eigen.h>
00050 #include <eigen_conversions/eigen_msg.h>
00051 
00052 // Shape tools
00053 #include <geometric_shapes/solid_primitive_dims.h>
00054 #include <geometric_shapes/shape_operations.h>
00055 
00056 namespace moveit_visual_tools
00057 {
00058 MoveItVisualTools::MoveItVisualTools(
00059     const std::string& base_frame, const std::string& marker_topic,
00060     planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor)
00061   : RvizVisualTools::RvizVisualTools(base_frame, marker_topic)
00062   , planning_scene_monitor_(planning_scene_monitor)
00063   , mannual_trigger_update_(false)
00064   , robot_state_topic_(DISPLAY_ROBOT_STATE_TOPIC)
00065   , planning_scene_topic_(PLANNING_SCENE_TOPIC)
00066   , name_("visual_tools")
00067 {
00068 }
00069 
00070 MoveItVisualTools::MoveItVisualTools(const std::string& base_frame, const std::string& marker_topic,
00071                                      robot_model::RobotModelConstPtr robot_model)
00072   : RvizVisualTools::RvizVisualTools(base_frame, marker_topic)
00073   , robot_model_(robot_model)
00074   , mannual_trigger_update_(false)
00075 {
00076 }
00077 
00078 bool MoveItVisualTools::loadPlanningSceneMonitor()
00079 {
00080   // Check if we already have one
00081   if (planning_scene_monitor_)
00082   {
00083     ROS_WARN_STREAM_NAMED(name_, "Will not load a new planning scene monitor when one has "
00084                                           "already been set for Visual Tools");
00085     return false;
00086   }
00087   ROS_DEBUG_STREAM_NAMED(name_, "Loading planning scene monitor");
00088 
00089   // Create tf transformer
00090   boost::shared_ptr<tf::TransformListener> tf;
00091   // tf.reset(new tf::TransformListener(nh_));
00092   // ros::spinOnce();
00093 
00094   // Regular version b/c the other one causes problems with recognizing end effectors
00095   planning_scene_monitor_.reset(new planning_scene_monitor::PlanningSceneMonitor(
00096                                                                                  //ROBOT_DESCRIPTION, boost::shared_ptr<tf::Transformer>(), "visual_tools_scene"));
00097                                                                                  ROBOT_DESCRIPTION, tf, "visual_tools_scene"));
00098   ros::spinOnce();
00099   ros::Duration(0.1).sleep();
00100   ros::spinOnce();
00101 
00102   if (planning_scene_monitor_->getPlanningScene())
00103   {
00104     // Optional monitors to start:
00105     // planning_scene_monitor_->startWorldGeometryMonitor();
00106     // planning_scene_monitor_->startSceneMonitor("/move_group/monitored_planning_scene");
00107     // planning_scene_monitor_->startStateMonitor("/joint_states", "/attached_collision_object");
00108 
00109     planning_scene_monitor_->startPublishingPlanningScene(
00110         planning_scene_monitor::PlanningSceneMonitor::UPDATE_SCENE, planning_scene_topic_);
00111     ROS_DEBUG_STREAM_NAMED(name_, "Publishing planning scene on "
00112                                                << planning_scene_topic_);
00113 
00114     planning_scene_monitor_->getPlanningScene()->setName("visual_tools_scene");
00115   }
00116   else
00117   {
00118     ROS_ERROR_STREAM_NAMED(name_, "Planning scene not configured");
00119     return false;
00120   }
00121 
00122   return true;
00123 }
00124 
00125 bool MoveItVisualTools::processCollisionObjectMsg(const moveit_msgs::CollisionObject& msg,
00126                                                   const rviz_visual_tools::colors& color)
00127 {
00128   // Apply command directly to planning scene to avoid a ROS msg call
00129   {
00130     planning_scene_monitor::LockedPlanningSceneRW scene(getPlanningSceneMonitor());
00131     scene->getCurrentStateNonConst().update();  // hack to prevent bad transforms
00132     scene->processCollisionObjectMsg(msg);
00133     scene->setObjectColor(msg.id, getColor(color));
00134   }
00135   // Trigger an update
00136   if (!mannual_trigger_update_)
00137   {
00138     triggerPlanningSceneUpdate();
00139   }
00140 
00141   return true;
00142 }
00143 
00144 bool MoveItVisualTools::processAttachedCollisionObjectMsg(
00145     const moveit_msgs::AttachedCollisionObject& msg)
00146 {
00147   // Apply command directly to planning scene to avoid a ROS msg call
00148   {
00149     planning_scene_monitor::LockedPlanningSceneRW scene(getPlanningSceneMonitor());
00150     // scene->getCurrentStateNonConst().update(); // hack to prevent bad transforms
00151     scene->processAttachedCollisionObjectMsg(msg);
00152   }
00153 
00154   // Trigger an update
00155   if (!mannual_trigger_update_)
00156   {
00157     triggerPlanningSceneUpdate();
00158   }
00159 
00160   return true;
00161 }
00162 
00163 bool MoveItVisualTools::triggerPlanningSceneUpdate()
00164 {
00165   getPlanningSceneMonitor()->triggerSceneUpdateEvent(
00166       planning_scene_monitor::PlanningSceneMonitor::UPDATE_SCENE);
00167   ros::spinOnce();
00168   return true;
00169 }
00170 
00171 bool MoveItVisualTools::loadSharedRobotState()
00172 {
00173   // Get robot state
00174   if (!shared_robot_state_)
00175   {
00176     // Check if a robot model was passed in
00177     if (!robot_model_)
00178     {
00179       // Fall back on using planning scene monitor.
00180       planning_scene_monitor::PlanningSceneMonitorPtr psm = getPlanningSceneMonitor();
00181       robot_model_ = psm->getRobotModel();
00182     }
00183     shared_robot_state_.reset(new robot_state::RobotState(robot_model_));
00184     hidden_robot_state_.reset(new robot_state::RobotState(robot_model_));
00185 
00186     // TODO: this seems to be a work around for a weird NaN number bug
00187     shared_robot_state_->setToDefaultValues();
00188     shared_robot_state_->update(true);
00189     hidden_robot_state_->setToDefaultValues();
00190     hidden_robot_state_->update(true);
00191   }
00192 
00193   return shared_robot_state_;
00194 }
00195 
00196 moveit::core::RobotStatePtr& MoveItVisualTools::getSharedRobotState()
00197 {
00198   // Always load the robot state before using
00199   loadSharedRobotState();
00200   return shared_robot_state_;
00201 }
00202 
00203 moveit::core::RobotModelConstPtr MoveItVisualTools::getRobotModel()
00204 {
00205   // Always load the robot state before using
00206   loadSharedRobotState();
00207   return shared_robot_state_->getRobotModel();
00208 }
00209 
00210 bool MoveItVisualTools::loadEEMarker(const robot_model::JointModelGroup* ee_jmg)
00211 {
00212   // Get joint state group
00213   if (ee_jmg == NULL)  // make sure EE_GROUP exists
00214   {
00215     ROS_ERROR_STREAM_NAMED(name_, "Unable to find joint model group with address"
00216                                                << ee_jmg);
00217     return false;
00218   }
00219 
00220   // Always load the robot state before using
00221   loadSharedRobotState();
00222   shared_robot_state_->setToDefaultValues();
00223   shared_robot_state_->update();
00224 
00225   // Clear old EE markers and EE poses
00226   ee_markers_map_[ee_jmg].markers.clear();
00227   ee_poses_map_[ee_jmg].clear();
00228 
00229   // Keep track of how many unique markers we have between different EEs
00230   static std::size_t marker_id_offset = 0;
00231 
00232   // -----------------------------------------------------------------------------------------------
00233   // Get end effector group
00234 
00235   // Create color to use for EE markers
00236   std_msgs::ColorRGBA marker_color = getColor(rviz_visual_tools::GREY);
00237 
00238   // Get link names that are in end effector
00239   const std::vector<std::string>& ee_link_names = ee_jmg->getLinkModelNames();
00240 
00241   // -----------------------------------------------------------------------------------------------
00242   // Get EE link markers for Rviz
00243 
00244   shared_robot_state_->getRobotMarkers(ee_markers_map_[ee_jmg], ee_link_names, marker_color,
00245                                        ee_jmg->getName(), ros::Duration());
00246   ROS_DEBUG_STREAM_NAMED(name_, "Number of rviz markers in end effector: "
00247                                              << ee_markers_map_[ee_jmg].markers.size());
00248 
00249   const std::string& ee_parent_link_name = ee_jmg->getEndEffectorParentGroup().second;
00250   // ROS_DEBUG_STREAM_NAMED(name_,"EE Parent link: " << ee_parent_link_name);
00251   const moveit::core::LinkModel* ee_parent_link = robot_model_->getLinkModel(ee_parent_link_name);
00252 
00253   Eigen::Affine3d ee_marker_global_transform =
00254       shared_robot_state_->getGlobalLinkTransform(ee_parent_link);
00255   Eigen::Affine3d ee_marker_pose;
00256 
00257   // Process each link of the end effector
00258   for (std::size_t i = 0; i < ee_markers_map_[ee_jmg].markers.size(); ++i)
00259   {
00260     // Header
00261     ee_markers_map_[ee_jmg].markers[i].header.frame_id = base_frame_;
00262 
00263     // Options for meshes
00264     if (ee_markers_map_[ee_jmg].markers[i].type == visualization_msgs::Marker::MESH_RESOURCE)
00265     {
00266       ee_markers_map_[ee_jmg].markers[i].mesh_use_embedded_materials = true;
00267     }
00268 
00269     // Unique id
00270     ee_markers_map_[ee_jmg].markers[i].id += marker_id_offset;
00271 
00272     // Copy original marker poses to a vector
00273     ee_marker_pose =
00274         ee_marker_global_transform.inverse() * convertPose(ee_markers_map_[ee_jmg].markers[i].pose);
00275     ee_poses_map_[ee_jmg].push_back(ee_marker_pose);
00276   }
00277 
00278   marker_id_offset += ee_markers_map_[ee_jmg].markers.size();
00279 
00280   return true;
00281 }
00282 
00283 void MoveItVisualTools::loadTrajectoryPub(const std::string& display_planned_path_topic)
00284 {
00285   if (pub_display_path_)
00286     return;
00287 
00288   // Trajectory paths
00289   pub_display_path_ =
00290       nh_.advertise<moveit_msgs::DisplayTrajectory>(display_planned_path_topic, 10, false);
00291   ROS_DEBUG_STREAM_NAMED(name_, "Publishing MoveIt trajectory on topic "
00292                                              << pub_display_path_.getTopic());
00293 
00294   // Wait for topic to be ready
00295   waitForSubscriber(pub_display_path_);
00296 }
00297 
00298 void MoveItVisualTools::loadRobotStatePub(const std::string& robot_state_topic)
00299 {
00300   if (pub_robot_state_)
00301     return;
00302 
00303   // Update global var if new topic was passed in
00304   if (!robot_state_topic.empty())
00305     robot_state_topic_ = robot_state_topic;
00306 
00307   // RobotState Message
00308   pub_robot_state_ = nh_.advertise<moveit_msgs::DisplayRobotState>(robot_state_topic_, 1);
00309   ROS_DEBUG_STREAM_NAMED(name_, "Publishing MoveIt robot state on topic "
00310                                              << pub_robot_state_.getTopic());
00311 
00312   // Wait for topic to be ready
00313   waitForSubscriber(pub_robot_state_);
00314 }
00315 
00316 planning_scene_monitor::PlanningSceneMonitorPtr MoveItVisualTools::getPlanningSceneMonitor()
00317 {
00318   if (!planning_scene_monitor_)
00319   {
00320     ROS_INFO_STREAM_NAMED(name_,
00321                           "No planning scene passed into moveit_visual_tools, creating one.");
00322     loadPlanningSceneMonitor();
00323     ros::spinOnce();
00324     ros::Duration(1).sleep();
00325   }
00326   return planning_scene_monitor_;
00327 }
00328 
00329 bool MoveItVisualTools::publishEEMarkers(const geometry_msgs::Pose& pose,
00330                                          const robot_model::JointModelGroup* ee_jmg,
00331                                          const rviz_visual_tools::colors& color,
00332                                          const std::string& ns)
00333 {
00334   // Check if we have not loaded the EE markers
00335   if (ee_markers_map_[ee_jmg].markers.empty() || ee_poses_map_[ee_jmg].empty())
00336   {
00337     if (!loadEEMarker(ee_jmg))
00338     {
00339       ROS_ERROR_STREAM_NAMED(name_,
00340                              "Unable to publish EE marker, unable to load EE markers");
00341       return false;
00342     }
00343   }
00344 
00345   Eigen::Affine3d eigen_goal_ee_pose = convertPose(pose);
00346   Eigen::Affine3d eigen_this_marker;
00347 
00348   // publishArrow( pose, rviz_visual_tools::RED, rviz_visual_tools::LARGE );
00349 
00350   // -----------------------------------------------------------------------------------------------
00351   // Process each link of the end effector
00352   for (std::size_t i = 0; i < ee_markers_map_[ee_jmg].markers.size(); ++i)
00353   {
00354     // Make sure ROS is still spinning
00355     if (!ros::ok())
00356       break;
00357 
00358     // Header
00359     ee_markers_map_[ee_jmg].markers[i].header.stamp = ros::Time::now();
00360 
00361     // Namespace
00362     ee_markers_map_[ee_jmg].markers[i].ns = ns;
00363 
00364     // Lifetime
00365     ee_markers_map_[ee_jmg].markers[i].lifetime = marker_lifetime_;
00366 
00367     // Color
00368     ee_markers_map_[ee_jmg].markers[i].color = getColor(color);
00369 
00370     // Convert pose
00371     eigen_this_marker = eigen_goal_ee_pose * ee_poses_map_[ee_jmg][i];
00372     ee_markers_map_[ee_jmg].markers[i].pose = convertPose(eigen_this_marker);
00373   }
00374 
00375   // Helper for publishing rviz markers
00376   if (!publishMarkers(ee_markers_map_[ee_jmg]))
00377     return false;
00378 
00379   return true;
00380 }
00381 
00382 bool MoveItVisualTools::publishGrasps(const std::vector<moveit_msgs::Grasp>& possible_grasps,
00383                                       const robot_model::JointModelGroup* ee_jmg,
00384                                       double animate_speed)
00385 {
00386   ROS_DEBUG_STREAM_NAMED(name_, "Visualizing " << possible_grasps.size()
00387                                                         << " grasps with EE joint model group "
00388                                                         << ee_jmg->getName());
00389 
00390   // Loop through all grasps
00391   for (std::size_t i = 0; i < possible_grasps.size(); ++i)
00392   {
00393     if (!ros::ok())  // Check that ROS is still ok and that user isn't trying to quit
00394       break;
00395 
00396     publishEEMarkers(possible_grasps[i].grasp_pose.pose, ee_jmg);
00397 
00398     ros::Duration(animate_speed).sleep();
00399   }
00400 
00401   return true;
00402 }
00403 
00404 bool MoveItVisualTools::publishAnimatedGrasps(
00405     const std::vector<moveit_msgs::Grasp>& possible_grasps,
00406     const robot_model::JointModelGroup* ee_jmg, double animate_speed)
00407 {
00408   ROS_DEBUG_STREAM_NAMED(
00409       name_, "Visualizing " << possible_grasps.size() << " grasps with joint model group "
00410                                      << ee_jmg->getName() << " at speed " << animate_speed);
00411 
00412   // Loop through all grasps
00413   for (std::size_t i = 0; i < possible_grasps.size(); ++i)
00414   {
00415     if (!ros::ok())  // Check that ROS is still ok and that user isn't trying to quit
00416       break;
00417 
00418     publishAnimatedGrasp(possible_grasps[i], ee_jmg, animate_speed);
00419 
00420     ros::Duration(0.1).sleep();
00421   }
00422 
00423   return true;
00424 }
00425 
00426 bool MoveItVisualTools::publishAnimatedGrasp(const moveit_msgs::Grasp& grasp,
00427                                              const robot_model::JointModelGroup* ee_jmg,
00428                                              double animate_speed)
00429 {
00430   // Grasp Pose Variables
00431   geometry_msgs::Pose grasp_pose = grasp.grasp_pose.pose;
00432 
00433   // Debug
00434   if (false)
00435   {
00436     publishArrow(grasp_pose, rviz_visual_tools::GREEN);
00437     publishEEMarkers(grasp_pose, ee_jmg);
00438     ros::Duration(0.5).sleep();
00439   }
00440 
00441   Eigen::Affine3d grasp_pose_eigen;
00442   tf::poseMsgToEigen(grasp_pose, grasp_pose_eigen);
00443 
00444   // Pre-grasp pose variables
00445   geometry_msgs::Pose pre_grasp_pose;
00446   Eigen::Affine3d pre_grasp_pose_eigen;
00447 
00448   // Approach direction variables
00449   Eigen::Vector3d pre_grasp_approach_direction_local;
00450 
00451   // Display Grasp Score
00452   // std::string text = "Grasp Quality: " +
00453   // boost::lexical_cast<std::string>(int(grasp.grasp_quality*100)) + "%";
00454   // publishText(grasp_pose, text);
00455 
00456   // Convert the grasp pose into the frame of reference of the approach/retreat frame_id
00457 
00458   // Animate the movement - for ee approach direction
00459   double animation_resulution = 0.1;  // the lower the better the resolution
00460   for (double percent = 0; percent < 1; percent += animation_resulution)
00461   {
00462     if (!ros::ok())  // Check that ROS is still ok and that user isn't trying to quit
00463       break;
00464 
00465     // Copy original grasp pose to pre-grasp pose
00466     pre_grasp_pose_eigen = grasp_pose_eigen;
00467 
00468     // The direction of the pre-grasp
00469     // Calculate the current animation position based on the percent
00470     Eigen::Vector3d pre_grasp_approach_direction =
00471         Eigen::Vector3d(-1 * grasp.pre_grasp_approach.direction.vector.x *
00472                             grasp.pre_grasp_approach.min_distance * (1 - percent),
00473                         -1 * grasp.pre_grasp_approach.direction.vector.y *
00474                             grasp.pre_grasp_approach.min_distance * (1 - percent),
00475                         -1 * grasp.pre_grasp_approach.direction.vector.z *
00476                             grasp.pre_grasp_approach.min_distance * (1 - percent));
00477 
00478     // Decide if we need to change the approach_direction to the local frame of the end effector
00479     // orientation
00480     const std::string& ee_parent_link_name = ee_jmg->getEndEffectorParentGroup().second;
00481 
00482     if (grasp.pre_grasp_approach.direction.header.frame_id == ee_parent_link_name)
00483     {
00484       // Apply/compute the approach_direction vector in the local frame of the grasp_pose
00485       // orientation
00486       pre_grasp_approach_direction_local =
00487           grasp_pose_eigen.rotation() * pre_grasp_approach_direction;
00488     }
00489     else
00490     {
00491       pre_grasp_approach_direction_local =
00492           pre_grasp_approach_direction;  // grasp_pose_eigen.rotation() *
00493                                          // pre_grasp_approach_direction;
00494     }
00495 
00496     // Update the grasp pose usign the new locally-framed approach_direction
00497     pre_grasp_pose_eigen.translation() += pre_grasp_approach_direction_local;
00498 
00499     // Convert eigen pre-grasp position back to regular message
00500     tf::poseEigenToMsg(pre_grasp_pose_eigen, pre_grasp_pose);
00501 
00502     // publishArrow(pre_grasp_pose, moveit_visual_tools::BLUE);
00503     publishEEMarkers(pre_grasp_pose, ee_jmg);
00504 
00505     ros::Duration(animate_speed).sleep();
00506 
00507     // Pause more at initial pose for debugging purposes
00508     if (percent == 0)
00509       ros::Duration(animate_speed * 2).sleep();
00510   }
00511   return true;
00512 }
00513 
00514 bool MoveItVisualTools::publishIKSolutions(
00515     const std::vector<trajectory_msgs::JointTrajectoryPoint>& ik_solutions,
00516     const robot_model::JointModelGroup* arm_jmg, double display_time)
00517 {
00518   if (ik_solutions.empty())
00519   {
00520     ROS_WARN_STREAM_NAMED(name_,
00521                           "Empty ik_solutions vector passed into publishIKSolutions()");
00522     return false;
00523   }
00524 
00525   loadSharedRobotState();
00526 
00527   ROS_DEBUG_STREAM_NAMED(name_, "Visualizing " << ik_solutions.size()
00528                                                         << " inverse kinematic solutions");
00529 
00530   // Apply the time to the trajectory
00531   trajectory_msgs::JointTrajectoryPoint trajectory_pt_timed;
00532 
00533   // Create a trajectory with one point
00534   moveit_msgs::RobotTrajectory trajectory_msg;
00535   trajectory_msg.joint_trajectory.header.frame_id = base_frame_;
00536   trajectory_msg.joint_trajectory.joint_names = arm_jmg->getActiveJointModelNames();
00537 
00538   // Overall length of trajectory
00539   double running_time = 0;
00540 
00541   // Loop through all inverse kinematic solutions
00542   for (std::size_t i = 0; i < ik_solutions.size(); ++i)
00543   {
00544     trajectory_pt_timed = ik_solutions[i];
00545     trajectory_pt_timed.time_from_start = ros::Duration(running_time);
00546     trajectory_msg.joint_trajectory.points.push_back(trajectory_pt_timed);
00547 
00548     running_time += display_time;
00549   }
00550 
00551   // Re-add final position so the last point is displayed fully
00552   trajectory_pt_timed = trajectory_msg.joint_trajectory.points.back();
00553   trajectory_pt_timed.time_from_start = ros::Duration(running_time);
00554   trajectory_msg.joint_trajectory.points.push_back(trajectory_pt_timed);
00555 
00556   return publishTrajectoryPath(trajectory_msg, shared_robot_state_, true);
00557 }
00558 
00559 bool MoveItVisualTools::removeAllCollisionObjects()
00560 {
00561   // Apply command directly to planning scene to avoid a ROS msg call
00562   {
00563     planning_scene_monitor::LockedPlanningSceneRW scene(getPlanningSceneMonitor());
00564     scene->removeAllCollisionObjects();
00565   }
00566 
00567   return true;
00568 }
00569 
00570 bool MoveItVisualTools::cleanupCO(const std::string& name)
00571 {
00572   // Clean up old collision objects
00573   moveit_msgs::CollisionObject co;
00574   co.header.stamp = ros::Time::now();
00575   co.header.frame_id = base_frame_;
00576   co.id = name;
00577   co.operation = moveit_msgs::CollisionObject::REMOVE;
00578 
00579   return processCollisionObjectMsg(co);
00580 }
00581 
00582 bool MoveItVisualTools::cleanupACO(const std::string& name)
00583 {
00584   // Clean up old attached collision object
00585   moveit_msgs::AttachedCollisionObject aco;
00586   aco.object.header.stamp = ros::Time::now();
00587   aco.object.header.frame_id = base_frame_;
00588 
00589   // aco.object.id = name;
00590   aco.object.operation = moveit_msgs::CollisionObject::REMOVE;
00591 
00592   return processAttachedCollisionObjectMsg(aco);
00593 }
00594 
00595 bool MoveItVisualTools::attachCO(const std::string& name, const std::string& ee_parent_link)
00596 {
00597   // Attach a collision object
00598   moveit_msgs::AttachedCollisionObject aco;
00599   aco.object.header.stamp = ros::Time::now();
00600   aco.object.header.frame_id = base_frame_;
00601 
00602   aco.object.id = name;
00603   aco.object.operation = moveit_msgs::CollisionObject::ADD;
00604 
00605   // Link to attach the object to
00606   aco.link_name = ee_parent_link;
00607 
00608   return processAttachedCollisionObjectMsg(aco);
00609 }
00610 
00611 bool MoveItVisualTools::publishCollisionBlock(const geometry_msgs::Pose& block_pose,
00612                                               const std::string& name, double block_size,
00613                                               const rviz_visual_tools::colors& color)
00614 {
00615   moveit_msgs::CollisionObject collision_obj;
00616   collision_obj.header.stamp = ros::Time::now();
00617   collision_obj.header.frame_id = base_frame_;
00618   collision_obj.id = name;
00619   collision_obj.operation = moveit_msgs::CollisionObject::ADD;
00620 
00621   collision_obj.primitives.resize(1);
00622   collision_obj.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
00623   collision_obj.primitives[0].dimensions.resize(
00624       geometric_shapes::SolidPrimitiveDimCount<shape_msgs::SolidPrimitive::BOX>::value);
00625   collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = block_size;
00626   collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = block_size;
00627   collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = block_size;
00628   collision_obj.primitive_poses.resize(1);
00629   collision_obj.primitive_poses[0] = block_pose;
00630 
00631   // ROS_INFO_STREAM_NAMED(name_,"CollisionObject: \n " << collision_obj);
00632   // ROS_DEBUG_STREAM_NAMED(name_,"Published collision object " << name);
00633   return processCollisionObjectMsg(collision_obj, color);
00634 }
00635 
00636 bool MoveItVisualTools::publishCollisionCuboid(const Eigen::Vector3d& point1,
00637                                                const Eigen::Vector3d& point2,
00638                                                const std::string& name,
00639                                                const rviz_visual_tools::colors& color)
00640 {
00641   return publishCollisionCuboid(convertPoint(point1), convertPoint(point2), name, color);
00642 }
00643 
00644 bool MoveItVisualTools::publishCollisionCuboid(const geometry_msgs::Point& point1,
00645                                                const geometry_msgs::Point& point2,
00646                                                const std::string& name,
00647                                                const rviz_visual_tools::colors& color)
00648 {
00649   moveit_msgs::CollisionObject collision_obj;
00650   collision_obj.header.stamp = ros::Time::now();
00651   collision_obj.header.frame_id = base_frame_;
00652   collision_obj.id = name;
00653   collision_obj.operation = moveit_msgs::CollisionObject::ADD;
00654 
00655   // Calculate center pose
00656   collision_obj.primitive_poses.resize(1);
00657   collision_obj.primitive_poses[0].position.x = (point1.x - point2.x) / 2.0 + point2.x;
00658   collision_obj.primitive_poses[0].position.y = (point1.y - point2.y) / 2.0 + point2.y;
00659   collision_obj.primitive_poses[0].position.z = (point1.z - point2.z) / 2.0 + point2.z;
00660 
00661   // Calculate scale
00662   collision_obj.primitives.resize(1);
00663   collision_obj.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
00664   collision_obj.primitives[0].dimensions.resize(
00665       geometric_shapes::SolidPrimitiveDimCount<shape_msgs::SolidPrimitive::BOX>::value);
00666   collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] =
00667       fabs(point1.x - point2.x);
00668   collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] =
00669       fabs(point1.y - point2.y);
00670   collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] =
00671       fabs(point1.z - point2.z);
00672 
00673   // Prevent scale from being zero
00674   if (!collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X])
00675     collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] =
00676         rviz_visual_tools::SMALL_SCALE;
00677   if (!collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y])
00678     collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] =
00679         rviz_visual_tools::SMALL_SCALE;
00680   if (!collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z])
00681     collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] =
00682         rviz_visual_tools::SMALL_SCALE;
00683 
00684   // ROS_INFO_STREAM_NAMED(name_,"CollisionObject: \n " << collision_obj);
00685   return processCollisionObjectMsg(collision_obj, color);
00686 }
00687 
00688 bool MoveItVisualTools::publishCollisionFloor(double z, const std::string& plane_name,
00689                                               const rviz_visual_tools::colors& color)
00690 {
00691   // Instead just generate a rectangle
00692   geometry_msgs::Point point1;
00693   geometry_msgs::Point point2;
00694 
00695   point1.x = rviz_visual_tools::LARGE_SCALE;
00696   point1.y = rviz_visual_tools::LARGE_SCALE;
00697   point1.z = z;
00698 
00699   point2.x = -rviz_visual_tools::LARGE_SCALE;
00700   point2.y = -rviz_visual_tools::LARGE_SCALE;
00701   point2.z = z - rviz_visual_tools::SMALL_SCALE;
00702   ;
00703 
00704   return publishCollisionCuboid(point1, point2, plane_name, color);
00705 }
00706 
00707 bool MoveItVisualTools::publishCollisionCylinder(const geometry_msgs::Point& a,
00708                                                  const geometry_msgs::Point& b,
00709                                                  const std::string& object_name, double radius,
00710                                                  const rviz_visual_tools::colors& color)
00711 {
00712   return publishCollisionCylinder(convertPoint(a), convertPoint(b), object_name, radius, color);
00713 }
00714 
00715 bool MoveItVisualTools::publishCollisionCylinder(const Eigen::Vector3d& a, const Eigen::Vector3d& b,
00716                                                  const std::string& object_name, double radius,
00717                                                  const rviz_visual_tools::colors& color)
00718 {
00719   // Distance between two points
00720   double height = (a - b).lpNorm<2>();
00721 
00722   // Find center point
00723   Eigen::Vector3d pt_center = getCenterPoint(a, b);
00724 
00725   // Create vector
00726   Eigen::Affine3d pose;
00727   pose = getVectorBetweenPoints(pt_center, b);
00728 
00729   // Convert pose to be normal to cylindar axis
00730   Eigen::Affine3d rotation;
00731   rotation = Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitY());
00732   pose = pose * rotation;
00733 
00734   return publishCollisionCylinder(pose, object_name, radius, height, color);
00735 }
00736 
00737 bool MoveItVisualTools::publishCollisionCylinder(const Eigen::Affine3d& object_pose,
00738                                                  const std::string& object_name, double radius,
00739                                                  double height,
00740                                                  const rviz_visual_tools::colors& color)
00741 {
00742   return publishCollisionCylinder(convertPose(object_pose), object_name, radius, height, color);
00743 }
00744 
00745 bool MoveItVisualTools::publishCollisionCylinder(const geometry_msgs::Pose& object_pose,
00746                                                  const std::string& object_name, double radius,
00747                                                  double height,
00748                                                  const rviz_visual_tools::colors& color)
00749 {
00750   moveit_msgs::CollisionObject collision_obj;
00751   collision_obj.header.stamp = ros::Time::now();
00752   collision_obj.header.frame_id = base_frame_;
00753   collision_obj.id = object_name;
00754   collision_obj.operation = moveit_msgs::CollisionObject::ADD;
00755   collision_obj.primitives.resize(1);
00756   collision_obj.primitives[0].type = shape_msgs::SolidPrimitive::CYLINDER;
00757   collision_obj.primitives[0].dimensions.resize(
00758       geometric_shapes::SolidPrimitiveDimCount<shape_msgs::SolidPrimitive::CYLINDER>::value);
00759   collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::CYLINDER_HEIGHT] = height;
00760   collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::CYLINDER_RADIUS] = radius;
00761   collision_obj.primitive_poses.resize(1);
00762   collision_obj.primitive_poses[0] = object_pose;
00763 
00764   // ROS_INFO_STREAM_NAMED(name_,"CollisionObject: \n " << collision_obj);
00765   return processCollisionObjectMsg(collision_obj, color);
00766 }
00767 
00768 bool MoveItVisualTools::publishCollisionMesh(const Eigen::Affine3d& object_pose,
00769                                              const std::string& object_name,
00770                                              const std::string& mesh_path,
00771                                              const rviz_visual_tools::colors& color)
00772 {
00773   return publishCollisionMesh(convertPose(object_pose), object_name, mesh_path, color);
00774 }
00775 
00776 bool MoveItVisualTools::publishCollisionMesh(const geometry_msgs::Pose& object_pose,
00777                                              const std::string& object_name,
00778                                              const std::string& mesh_path,
00779                                              const rviz_visual_tools::colors& color)
00780 {
00781   shapes::Shape* mesh =
00782       shapes::createMeshFromResource(mesh_path);  // make sure its prepended by file://
00783   shapes::ShapeMsg shape_msg;  // this is a boost::variant type from shape_messages.h
00784   if (!mesh || !shapes::constructMsgFromShape(mesh, shape_msg))
00785   {
00786     ROS_ERROR_STREAM_NAMED(name_, "Unable to create mesh shape message from resource "
00787                                                << mesh_path);
00788     return false;
00789   }
00790 
00791   if (!publishCollisionMesh(object_pose, object_name, boost::get<shape_msgs::Mesh>(shape_msg),
00792                             color))
00793     return false;
00794 
00795   ROS_DEBUG_NAMED(name_, "Loaded mesh from '%s'", mesh_path.c_str());
00796   return true;
00797 }
00798 
00799 bool MoveItVisualTools::publishCollisionMesh(const Eigen::Affine3d& object_pose,
00800                                              const std::string& object_name,
00801                                              const shape_msgs::Mesh& mesh_msg,
00802                                              const rviz_visual_tools::colors& color)
00803 {
00804   return publishCollisionMesh(convertPose(object_pose), object_name, mesh_msg, color);
00805 }
00806 
00807 bool MoveItVisualTools::publishCollisionMesh(const geometry_msgs::Pose& object_pose,
00808                                              const std::string& object_name,
00809                                              const shape_msgs::Mesh& mesh_msg,
00810                                              const rviz_visual_tools::colors& color)
00811 {
00812   // Create collision message
00813   moveit_msgs::CollisionObject collision_obj;
00814   collision_obj.header.stamp = ros::Time::now();
00815   collision_obj.header.frame_id = base_frame_;
00816   collision_obj.id = object_name;
00817   collision_obj.operation = moveit_msgs::CollisionObject::ADD;
00818   collision_obj.mesh_poses.resize(1);
00819   collision_obj.mesh_poses[0] = object_pose;
00820   collision_obj.meshes.resize(1);
00821   collision_obj.meshes[0] = mesh_msg;
00822 
00823   return processCollisionObjectMsg(collision_obj, color);
00824 }
00825 
00826 bool MoveItVisualTools::publishCollisionGraph(const graph_msgs::GeometryGraph& graph,
00827                                               const std::string& object_name, double radius,
00828                                               const rviz_visual_tools::colors& color)
00829 {
00830   ROS_INFO_STREAM_NAMED("publishCollisionGraph", "Preparing to create collision graph");
00831 
00832   // The graph is one collision object with many primitives
00833   moveit_msgs::CollisionObject collision_obj;
00834   collision_obj.header.stamp = ros::Time::now();
00835   collision_obj.header.frame_id = base_frame_;
00836   collision_obj.id = object_name;
00837   collision_obj.operation = moveit_msgs::CollisionObject::ADD;
00838 
00839   // Track which pairs of nodes we've already connected since graph is bi-directional
00840   typedef std::pair<std::size_t, std::size_t> node_ids;
00841   std::set<node_ids> added_edges;
00842   std::pair<std::set<node_ids>::iterator, bool> return_value;
00843 
00844   Eigen::Vector3d a, b;
00845   for (std::size_t i = 0; i < graph.nodes.size(); ++i)
00846   {
00847     for (std::size_t j = 0; j < graph.edges[i].node_ids.size(); ++j)
00848     {
00849       // Check if we've already added this pair of nodes (edge)
00850       return_value = added_edges.insert(node_ids(i, j));
00851       if (return_value.second == false)
00852       {
00853         // Element already existed in set, so don't add a new collision object
00854       }
00855       else
00856       {
00857         // Create a cylinder from two points
00858         a = convertPoint(graph.nodes[i]);
00859         b = convertPoint(graph.nodes[graph.edges[i].node_ids[j]]);
00860 
00861         // add other direction of edge
00862         added_edges.insert(node_ids(j, i));
00863 
00864         // Distance between two points
00865         double height = (a - b).lpNorm<2>();
00866 
00867         // Find center point
00868         Eigen::Vector3d pt_center = getCenterPoint(a, b);
00869 
00870         // Create vector
00871         Eigen::Affine3d pose;
00872         pose = getVectorBetweenPoints(pt_center, b);
00873 
00874         // Convert pose to be normal to cylindar axis
00875         Eigen::Affine3d rotation;
00876         rotation = Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitY());
00877         pose = pose * rotation;
00878 
00879         // Create the solid primitive
00880         shape_msgs::SolidPrimitive cylinder;
00881         cylinder.type = shape_msgs::SolidPrimitive::CYLINDER;
00882         cylinder.dimensions.resize(
00883             geometric_shapes::SolidPrimitiveDimCount<shape_msgs::SolidPrimitive::CYLINDER>::value);
00884         cylinder.dimensions[shape_msgs::SolidPrimitive::CYLINDER_HEIGHT] = height;
00885         cylinder.dimensions[shape_msgs::SolidPrimitive::CYLINDER_RADIUS] = radius;
00886 
00887         // Add to the collision object
00888         collision_obj.primitives.push_back(cylinder);
00889 
00890         // Add the pose
00891         collision_obj.primitive_poses.push_back(convertPose(pose));
00892       }
00893     }
00894   }
00895 
00896   return processCollisionObjectMsg(collision_obj, color);
00897 }
00898 
00899 void MoveItVisualTools::getCollisionWallMsg(double x, double y, double angle, double width,
00900                                             const std::string name,
00901                                             moveit_msgs::CollisionObject& collision_obj)
00902 {
00903   double floor_to_base_height = 0; // TODO(davetcoleman): set this to a better value
00904 
00905   collision_obj.header.stamp = ros::Time::now();
00906   collision_obj.header.frame_id = base_frame_;
00907   collision_obj.operation = moveit_msgs::CollisionObject::ADD;
00908   collision_obj.primitives.resize(1);
00909   collision_obj.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
00910   collision_obj.primitives[0].dimensions.resize(
00911       geometric_shapes::SolidPrimitiveDimCount<shape_msgs::SolidPrimitive::BOX>::value);
00912 
00913   geometry_msgs::Pose rec_pose;
00914 
00915   // ----------------------------------------------------------------------------------
00916   // Name
00917   collision_obj.id = name;
00918 
00919   double depth = 0.1;
00920   double height = 2.5;
00921 
00922   // Position
00923   rec_pose.position.x = x;
00924   rec_pose.position.y = y;
00925   rec_pose.position.z = height / 2 + floor_to_base_height;
00926 
00927   // Size
00928   collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = depth;
00929   collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = width;
00930   collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = height;
00931   // ----------------------------------------------------------------------------------
00932 
00933   Eigen::Quaterniond quat(Eigen::AngleAxis<double>(double(angle), Eigen::Vector3d::UnitZ()));
00934   rec_pose.orientation.x = quat.x();
00935   rec_pose.orientation.y = quat.y();
00936   rec_pose.orientation.z = quat.z();
00937   rec_pose.orientation.w = quat.w();
00938 
00939   collision_obj.primitive_poses.resize(1);
00940   collision_obj.primitive_poses[0] = rec_pose;
00941 }
00942 
00943 bool MoveItVisualTools::publishCollisionWall(double x, double y, double angle, double width,
00944                                              const std::string name,
00945                                              const rviz_visual_tools::colors& color)
00946 {
00947   moveit_msgs::CollisionObject collision_obj;
00948   getCollisionWallMsg(x, y, angle, width, name, collision_obj);
00949 
00950   return processCollisionObjectMsg(collision_obj, color);
00951 }
00952 
00953 bool MoveItVisualTools::publishCollisionTable(double x, double y, double angle, double width,
00954                                               double height, double depth, const std::string name,
00955                                               const rviz_visual_tools::colors& color)
00956 {
00957   double floor_to_base_height = 0; // TODO(davetcoleman): set this to a better value
00958 
00959   geometry_msgs::Pose table_pose;
00960 
00961   // Position
00962   table_pose.position.x = x;
00963   table_pose.position.y = y;
00964   table_pose.position.z = height / 2 + floor_to_base_height;
00965 
00966   // Orientation
00967   Eigen::Quaterniond quat(Eigen::AngleAxis<double>(double(angle), Eigen::Vector3d::UnitZ()));
00968   table_pose.orientation.x = quat.x();
00969   table_pose.orientation.y = quat.y();
00970   table_pose.orientation.z = quat.z();
00971   table_pose.orientation.w = quat.w();
00972 
00973   moveit_msgs::CollisionObject collision_obj;
00974   collision_obj.header.stamp = ros::Time::now();
00975   collision_obj.header.frame_id = base_frame_;
00976   collision_obj.id = name;
00977   collision_obj.operation = moveit_msgs::CollisionObject::ADD;
00978   collision_obj.primitives.resize(1);
00979   collision_obj.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
00980   collision_obj.primitives[0].dimensions.resize(
00981       geometric_shapes::SolidPrimitiveDimCount<shape_msgs::SolidPrimitive::BOX>::value);
00982 
00983   // Size
00984   collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = depth;
00985   collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = width;
00986   collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = height;
00987 
00988   collision_obj.primitive_poses.resize(1);
00989   collision_obj.primitive_poses[0] = table_pose;
00990   return processCollisionObjectMsg(collision_obj, color);
00991 }
00992 
00993 bool MoveItVisualTools::loadCollisionSceneFromFile(const std::string& path)
00994 {
00995   return loadCollisionSceneFromFile(path, Eigen::Affine3d::Identity());
00996 }
00997 
00998 bool MoveItVisualTools::loadCollisionSceneFromFile(const std::string& path,
00999                                                    const Eigen::Affine3d& offset)
01000 {
01001   // Open file
01002   std::ifstream fin(path.c_str());
01003   if (fin.good())
01004   {
01005     // Load directly to the planning scene
01006     planning_scene_monitor::LockedPlanningSceneRW scene(getPlanningSceneMonitor());
01007     {
01008       if (scene)
01009       {
01010         scene->loadGeometryFromStream(fin, offset);
01011       }
01012       else
01013       {
01014         ROS_WARN_STREAM_NAMED(name_, "Unable to get locked planning scene RW");
01015         return false;
01016       }
01017     }
01018     ROS_INFO_NAMED(name_, "Loaded scene geometry from '%s'", path.c_str());
01019   }
01020   else
01021     ROS_WARN_NAMED(name_, "Unable to load scene geometry from '%s'", path.c_str());
01022 
01023   fin.close();
01024 
01025   return triggerPlanningSceneUpdate();
01026 }
01027 
01028 bool MoveItVisualTools::publishCollisionTests() { ROS_ERROR_STREAM_NAMED("temp", "Depricated"); }
01029 
01030 bool MoveItVisualTools::publishWorkspaceParameters(const moveit_msgs::WorkspaceParameters& params)
01031 {
01032   return publishCollisionCuboid(convertPoint(params.min_corner), convertPoint(params.max_corner),
01033                                 "workspace", rviz_visual_tools::TRANSLUCENT);
01034 }
01035 
01036 bool MoveItVisualTools::publishContactPoints(const moveit::core::RobotState& robot_state,
01037                                              const planning_scene::PlanningScene* planning_scene,
01038                                              const rviz_visual_tools::colors& color)
01039 {
01040   // Compute the contacts if any
01041   collision_detection::CollisionRequest c_req;
01042   collision_detection::CollisionResult c_res;
01043   c_req.contacts = true;
01044   c_req.max_contacts = 10;
01045   c_req.max_contacts_per_pair = 3;
01046   c_req.verbose = true;
01047 
01048   // Check for collisions
01049   planning_scene->checkCollision(c_req, c_res, robot_state);
01050 
01051   // Display
01052   if (c_res.contact_count > 0)
01053   {
01054     visualization_msgs::MarkerArray arr;
01055     collision_detection::getCollisionMarkersFromContacts(arr, planning_scene->getPlanningFrame(),
01056                                                          c_res.contacts);
01057     ROS_INFO_STREAM_NAMED(name_, "Completed listing of explanations for invalid states.");
01058 
01059     // Check for markers
01060     if (arr.markers.empty())
01061       return true;
01062 
01063     // Convert markers to same namespace and other custom stuff
01064     for (std::size_t i = 0; i < arr.markers.size(); ++i)
01065     {
01066       arr.markers[i].ns = "Collision";
01067       arr.markers[i].scale.x = 0.04;
01068       arr.markers[i].scale.y = 0.04;
01069       arr.markers[i].scale.z = 0.04;
01070       arr.markers[i].color = getColor(color);
01071     }
01072 
01073     return publishMarkers(arr);
01074   }
01075   return true;
01076 }
01077 
01078 bool MoveItVisualTools::publishTrajectoryPoint(
01079     const trajectory_msgs::JointTrajectoryPoint& trajectory_pt, const std::string& planning_group,
01080     double display_time)
01081 {
01082   // Get joint state group
01083   const robot_model::JointModelGroup* jmg = robot_model_->getJointModelGroup(planning_group);
01084 
01085   if (jmg == NULL)  // not found
01086   {
01087     ROS_ERROR_STREAM_NAMED("publishTrajectoryPoint", "Could not find joint model group "
01088                                                          << planning_group);
01089     return false;
01090   }
01091 
01092   // Apply the time to the trajectory
01093   trajectory_msgs::JointTrajectoryPoint trajectory_pt_timed = trajectory_pt;
01094   trajectory_pt_timed.time_from_start = ros::Duration(display_time);
01095 
01096   // Create a trajectory with one point
01097   moveit_msgs::RobotTrajectory trajectory_msg;
01098   trajectory_msg.joint_trajectory.header.frame_id = base_frame_;
01099   trajectory_msg.joint_trajectory.joint_names = jmg->getJointModelNames();
01100   trajectory_msg.joint_trajectory.points.push_back(trajectory_pt);
01101   trajectory_msg.joint_trajectory.points.push_back(trajectory_pt_timed);
01102 
01103   return publishTrajectoryPath(trajectory_msg, shared_robot_state_, true);
01104 }
01105 
01106 bool MoveItVisualTools::publishTrajectoryPath(
01107     const std::vector<robot_state::RobotStatePtr>& trajectory,
01108     const moveit::core::JointModelGroup* jmg, double speed, bool blocking)
01109 {
01110   // Copy the vector of RobotStates to a RobotTrajectory
01111   robot_trajectory::RobotTrajectoryPtr robot_trajectory(
01112       new robot_trajectory::RobotTrajectory(robot_model_, jmg->getName()));
01113   ;
01114 
01115   double duration_from_previous = 0;
01116   for (std::size_t k = 0; k < trajectory.size(); ++k)
01117   {
01118     duration_from_previous += speed;
01119     robot_trajectory->addSuffixWayPoint(trajectory[k], duration_from_previous);
01120   }
01121 
01122   // Convert trajectory to a message
01123   moveit_msgs::RobotTrajectory trajectory_msg;
01124   robot_trajectory->getRobotTrajectoryMsg(trajectory_msg);
01125 
01126   return publishTrajectoryPath(trajectory_msg, shared_robot_state_, blocking);
01127 }
01128 
01129 bool MoveItVisualTools::publishTrajectoryPath(const robot_trajectory::RobotTrajectory& trajectory,
01130                                               bool blocking)
01131 {
01132   moveit_msgs::RobotTrajectory trajectory_msg;
01133   trajectory.getRobotTrajectoryMsg(trajectory_msg);
01134 
01135   // Add time from start if none specified
01136   if (trajectory_msg.joint_trajectory.points.size() > 1)
01137   {
01138     if (trajectory_msg.joint_trajectory.points[1].time_from_start ==
01139         ros::Duration(0))  // assume no timestamps exist
01140     {
01141       for (std::size_t i = 0; i < trajectory_msg.joint_trajectory.points.size(); ++i)
01142       {
01143         trajectory_msg.joint_trajectory.points[i].time_from_start = ros::Duration(i * 2);  // 1 hz
01144       }
01145     }
01146   }
01147 
01148   return publishTrajectoryPath(trajectory_msg, shared_robot_state_, blocking);
01149 }
01150 
01151 bool MoveItVisualTools::publishTrajectoryPath(const moveit_msgs::RobotTrajectory& trajectory_msg,
01152                                               const robot_state::RobotStateConstPtr robot_state,
01153                                               bool blocking)
01154 {
01155   // Check if we have enough points
01156   if (!trajectory_msg.joint_trajectory.points.size())
01157   {
01158     ROS_WARN_STREAM_NAMED(name_,
01159                           "Unable to publish trajectory path because trajectory has zero points");
01160     return false;
01161   }
01162 
01163   // Create the message
01164   moveit_msgs::DisplayTrajectory display_trajectory_msg;
01165   display_trajectory_msg.model_id = robot_model_->getName();
01166   display_trajectory_msg.trajectory.resize(1);
01167   display_trajectory_msg.trajectory[0] = trajectory_msg;
01168 
01169   // Convert the current robot state to the trajectory start, so that we can e.g. provide vjoint
01170   // positions
01171   robot_state::robotStateToRobotStateMsg(*robot_state, display_trajectory_msg.trajectory_start);
01172 
01173   // Publish message
01174   loadTrajectoryPub();  // always call this before publishing
01175   pub_display_path_.publish(display_trajectory_msg);
01176   ros::spinOnce();
01177 
01178   // Wait the duration of the trajectory
01179   if (blocking)
01180   {
01181     ROS_INFO_STREAM_NAMED(name_,
01182                           "Waiting for trajectory animation "
01183                               << trajectory_msg.joint_trajectory.points.back().time_from_start
01184                               << " seconds");
01185 
01186     // Check if ROS is ok in intervals
01187     double counter = 0;
01188     while (ros::ok() &&
01189            counter < trajectory_msg.joint_trajectory.points.back().time_from_start.toSec())
01190     {
01191       counter += 0.25;  // check every fourth second
01192       ros::Duration(0.25).sleep();
01193     }
01194   }
01195 
01196   return true;
01197 }
01198 
01199 bool MoveItVisualTools::publishTrajectoryLine(const moveit_msgs::RobotTrajectory& trajectory_msg,
01200                                               const moveit::core::LinkModel* ee_parent_link,
01201                                               const robot_model::JointModelGroup* arm_jmg,
01202                                               const rviz_visual_tools::colors& color,
01203                                               bool clear_all_markers)
01204 {
01205   // Error check
01206   if (!arm_jmg)
01207   {
01208     ROS_FATAL_STREAM_NAMED(name_, "arm_jmg is NULL");
01209     return false;
01210   }
01211 
01212   // Always load the robot state before using
01213   loadSharedRobotState();
01214 
01215   // Convert trajectory into a series of RobotStates
01216   robot_trajectory::RobotTrajectoryPtr
01217     robot_trajectory(new robot_trajectory::RobotTrajectory(robot_model_, arm_jmg->getName()));
01218   robot_trajectory->setRobotTrajectoryMsg(*shared_robot_state_, trajectory_msg);
01219 
01220   return publishTrajectoryLine(robot_trajectory, ee_parent_link, color, clear_all_markers);
01221 }
01222 
01223 bool MoveItVisualTools::publishTrajectoryLine(const robot_trajectory::RobotTrajectoryPtr robot_trajectory,
01224                                               const moveit::core::LinkModel* ee_parent_link,
01225                                               const rviz_visual_tools::colors& color,
01226                                               bool clear_all_markers)
01227 {
01228   // Error check
01229   if (!ee_parent_link)
01230   {
01231     ROS_FATAL_STREAM_NAMED(name_, "ee_parent_link is NULL");
01232     return false;
01233   }
01234 
01235   // Point location datastructure
01236   std::vector<geometry_msgs::Point> path;
01237 
01238   // Group together messages
01239   enableInternalBatchPublishing(true);
01240 
01241   if (clear_all_markers)
01242     publishMarker(reset_marker_);
01243 
01244   // Visualize end effector position of cartesian path
01245   for (std::size_t i = 0; i < robot_trajectory->getWayPointCount(); ++i)
01246   {
01247     const Eigen::Affine3d& tip_pose =
01248         robot_trajectory->getWayPoint(i).getGlobalLinkTransform(ee_parent_link);
01249 
01250     // Error Check
01251     if (tip_pose.translation().x() != tip_pose.translation().x())
01252     {
01253       ROS_ERROR_STREAM_NAMED(name_, "NAN DETECTED AT TRAJECTORY POINT i=" << i);
01254       return false;
01255     }
01256 
01257     path.push_back(convertPose(tip_pose).position);
01258     publishSphere(tip_pose, color, rviz_visual_tools::LARGE);
01259   }
01260 
01261   publishPath(path, color, rviz_visual_tools::XSMALL);
01262 
01263   return triggerInternalBatchPublishAndDisable();
01264 }
01265 
01266 bool MoveItVisualTools::publishTrajectoryPoints(
01267     const std::vector<robot_state::RobotStatePtr>& robot_state_trajectory,
01268     const moveit::core::LinkModel* ee_parent_link, const rviz_visual_tools::colors& color)
01269 {
01270   // Visualize end effector position of cartesian path
01271   for (std::size_t i = 0; i < robot_state_trajectory.size(); ++i)
01272   {
01273     const Eigen::Affine3d& tip_pose =
01274         robot_state_trajectory[i]->getGlobalLinkTransform(ee_parent_link);
01275 
01276     publishSphere(tip_pose, color);
01277   }
01278   return true;
01279 }
01280 
01281 bool MoveItVisualTools::publishRobotState(const robot_state::RobotStatePtr& robot_state,
01282                                           const rviz_visual_tools::colors& color)
01283 {
01284   publishRobotState(*robot_state.get(), color);
01285 }
01286 
01287 bool MoveItVisualTools::publishRobotState(const robot_state::RobotState& robot_state,
01288                                           const rviz_visual_tools::colors& color)
01289 {
01290   // Reference to the correctly colored version of message (they are cached)
01291   // May not exist yet but this will create it
01292   moveit_msgs::DisplayRobotState& display_robot_msg = display_robot_msgs_[color];
01293 
01294   // Check if a robot state message already exists for this color
01295   if (display_robot_msg.highlight_links.size() == 0)  // has not been colored yet, lets create that
01296   {
01297     if (color != rviz_visual_tools::DEFAULT)  // ignore color highlights when set to default
01298     {
01299       // Get links names
01300       const std::vector<const moveit::core::LinkModel*>& link_names =
01301           robot_state.getRobotModel()->getLinkModelsWithCollisionGeometry();
01302       display_robot_msg.highlight_links.resize(link_names.size());
01303 
01304       // Get color
01305       const std_msgs::ColorRGBA& color_rgba = getColor(color);
01306 
01307       // Color every link
01308       for (std::size_t i = 0; i < link_names.size(); ++i)
01309       {
01310         display_robot_msg.highlight_links[i].id = link_names[i]->getName();
01311         display_robot_msg.highlight_links[i].color = color_rgba;
01312       }
01313     }
01314   }
01315 
01316   // Modify colors to also indicate which are fixed
01317   // TODO not compatibile with mainstream moveit
01318   /*
01319   if (robot_state.hasFixedLinks())
01320   {
01321     // Get links names
01322     const std::vector<const moveit::core::LinkModel*>& link_names =
01323   robot_state.getRobotModel()->getLinkModelsWithCollisionGeometry();
01324 
01325     for (std::size_t i = 0; i < robot_model_->getFixableLinks().size(); ++i)
01326     {
01327       if (robot_state.fixedLinkEnabled(i))
01328       {
01329         for (std::size_t j = 0; j < link_names.size(); ++j)
01330         {
01331           if (link_names[j] == robot_model_->getFixableLinks()[i])
01332             if ( robot_state.getPrimaryFixedLinkID() == i ) // is primary
01333               display_robot_msg.highlight_links[j].color = getColor(rviz_visual_tools::BLUE);
01334             else
01335               display_robot_msg.highlight_links[j].color = getColor(rviz_visual_tools::RED);
01336         }
01337       }
01338     }
01339   }
01340   */
01341 
01342   // Convert state to message
01343   robot_state::robotStateToRobotStateMsg(robot_state, display_robot_msg.state);
01344 
01345   // Publish
01346   loadRobotStatePub();
01347   pub_robot_state_.publish(display_robot_msg);
01348   ros::spinOnce();
01349 
01350   return true;
01351 }
01352 
01353 bool MoveItVisualTools::publishRobotState(
01354     const trajectory_msgs::JointTrajectoryPoint& trajectory_pt,
01355     const robot_model::JointModelGroup* jmg, const rviz_visual_tools::colors& color)
01356 {
01357   // Always load the robot state before using
01358   loadSharedRobotState();
01359 
01360   // Set robot state
01361   shared_robot_state_->setToDefaultValues();  // reset the state just in case
01362   shared_robot_state_->setJointGroupPositions(jmg, trajectory_pt.positions);
01363 
01364   // Publish robot state
01365   publishRobotState(*shared_robot_state_, color);
01366 
01367   return true;
01368 }
01369 
01370 bool MoveItVisualTools::hideRobot()
01371 {
01372   static const std::string VJOINT_NAME = "virtual_joint";
01373 
01374   // Always load the robot state before using
01375   loadSharedRobotState();
01376 
01377   // Check if joint
01378   if (!hidden_robot_state_->getRobotModel()->hasJointModel(VJOINT_NAME))
01379   {
01380     ROS_WARN_STREAM_NAMED(name_, "Unable to hide robot because joint '" << VJOINT_NAME
01381                           << "' does not exist.");
01382     const std::vector<std::string>& names = hidden_robot_state_->getRobotModel()->getJointModelNames();
01383     ROS_WARN_STREAM_NAMED(name_, "Available names:");
01384     std::copy(names.begin(), names.end(), std::ostream_iterator<std::string>(std::cout, "\n"));
01385 
01386     return false;
01387   }
01388 
01389   // Check if variables exist
01390   if (!hidden_robot_state_->getRobotModel()->getJointModel(VJOINT_NAME)
01391       ->hasVariable(VJOINT_NAME + "/trans_x"))
01392   {
01393     // Debug
01394     ROS_WARN_STREAM_NAMED(name_, "Unable to hide robot because variables for joint '" << VJOINT_NAME
01395                           << "' do not exist. Try making this vjoint floating");
01396     ROS_WARN_STREAM_NAMED(name_, "The only available joint variables are:");
01397     const std::vector<std::string>& var_names =
01398       hidden_robot_state_->getRobotModel()->getJointModel(VJOINT_NAME)->getVariableNames();
01399     std::copy(var_names.begin(), var_names.end(),
01400               std::ostream_iterator<std::string>(std::cout, "\n"));
01401     return false;
01402   }
01403 
01404   // Hide the robot
01405   hidden_robot_state_->setVariablePosition(VJOINT_NAME + "/trans_x",
01406                                            rviz_visual_tools::LARGE_SCALE);
01407   hidden_robot_state_->setVariablePosition(VJOINT_NAME + "/trans_y",
01408                                            rviz_visual_tools::LARGE_SCALE);
01409   hidden_robot_state_->setVariablePosition(VJOINT_NAME + "/trans_z",
01410                                            rviz_visual_tools::LARGE_SCALE);
01411   return publishRobotState(hidden_robot_state_);
01412 }
01413 
01414 }  // namespace


moveit_visual_tools
Author(s): Dave Coleman
autogenerated on Thu Jun 6 2019 17:34:03