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


moveit_visual_tools
Author(s): Dave Coleman
autogenerated on Fri Jun 17 2016 04:11:05