visualize_robot_collision_volume.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage 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: Ioan Sucan */
00036 
00037 #include <moveit/planning_scene_monitor/planning_scene_monitor.h>
00038 #include <cstdlib>
00039 
00040 static const std::string ROBOT_DESCRIPTION = "robot_description";
00041 
00042 int main(int argc, char** argv)
00043 {
00044   ros::init(argc, argv, "visualize_robot_collision_volume");
00045 
00046   ros::AsyncSpinner spinner(1);
00047   spinner.start();
00048 
00049   double radius = 0.02;
00050   double lifetime = 600.0;
00051 
00052   boost::shared_ptr<tf::TransformListener> tr(new tf::TransformListener());
00053   planning_scene_monitor::PlanningSceneMonitor psm(ROBOT_DESCRIPTION, tr);
00054   if (psm.getPlanningScene())
00055   {
00056     psm.startWorldGeometryMonitor();
00057     psm.startSceneMonitor();
00058     psm.startStateMonitor();
00059     ros::NodeHandle nh;
00060     ros::Publisher pub_markers = nh.advertise<visualization_msgs::MarkerArray>("visualization_marker_array", 10);
00061     std::cout << "\nListening for planning scene...\nType the number of spheres to generate and press Enter: "
00062               << std::endl;
00063     int N;
00064     std::cin >> N;
00065 
00066     planning_scene::PlanningScenePtr scene = psm.getPlanningScene();
00067     std::vector<double> aabb;
00068     scene->getCurrentState().computeAABB(aabb);
00069 
00070     // publish the bounding box
00071     visualization_msgs::Marker mk;
00072     mk.header.stamp = ros::Time::now();
00073     mk.header.frame_id = scene->getPlanningFrame();
00074     mk.ns = "bounding_box";
00075     mk.id = 0;
00076     mk.type = visualization_msgs::Marker::CUBE;
00077     mk.action = visualization_msgs::Marker::ADD;
00078     mk.pose.position.x = (aabb[0] + aabb[1]) / 2.0;
00079     mk.pose.position.y = (aabb[2] + aabb[3]) / 2.0;
00080     mk.pose.position.z = (aabb[4] + aabb[5]) / 2.0;
00081     mk.pose.orientation.w = 1.0;
00082     mk.scale.x = aabb[1] - aabb[0];
00083     mk.scale.y = aabb[3] - aabb[2];
00084     mk.scale.z = aabb[5] - aabb[4];
00085     mk.color.r = 0.0f;
00086     mk.color.g = 0.5f;
00087     mk.color.b = 1.0f;
00088     mk.color.a = 0.3f;
00089     mk.lifetime = ros::Duration(lifetime);
00090     visualization_msgs::MarkerArray arr;
00091     arr.markers.push_back(mk);
00092     pub_markers.publish(arr);
00093 
00094     Eigen::Affine3d t;
00095     t.setIdentity();
00096     std::vector<Eigen::Vector3d> points;
00097     std::size_t published = 0;
00098     random_numbers::RandomNumberGenerator rng;
00099     collision_detection::CollisionRequest req;
00100 
00101     std_msgs::ColorRGBA color;
00102     color.r = 1.0f;
00103     color.g = 0.0f;
00104     color.b = 0.0f;
00105     color.a = 1.0f;
00106 
00107     for (int i = 0; i < N; ++i)
00108     {
00109       t.translation() = Eigen::Vector3d(rng.uniformReal(aabb[0], aabb[1]), rng.uniformReal(aabb[2], aabb[3]),
00110                                         rng.uniformReal(aabb[4], aabb[5]));
00111       scene->getWorldNonConst()->clearObjects();
00112       scene->getWorldNonConst()->addToObject("test", shapes::ShapeConstPtr(new shapes::Sphere(radius)), t);
00113       collision_detection::CollisionResult res;
00114       scene->checkCollision(req, res);
00115       if (res.collision)
00116       {
00117         points.push_back(t.translation());
00118         if (points.size() - published >= 100 || (points.size() > published && i + 1 >= N))
00119         {
00120           arr.markers.clear();
00121           for (std::size_t k = published; k < points.size(); ++k)
00122           {
00123             visualization_msgs::Marker mk;
00124             mk.header.stamp = ros::Time::now();
00125             mk.header.frame_id = scene->getPlanningFrame();
00126             mk.ns = "colliding";
00127             mk.id = k;
00128             mk.type = visualization_msgs::Marker::SPHERE;
00129             mk.action = visualization_msgs::Marker::ADD;
00130             mk.pose.position.x = points[k].x();
00131             mk.pose.position.y = points[k].y();
00132             mk.pose.position.z = points[k].z();
00133             mk.pose.orientation.w = 1.0;
00134             mk.scale.x = mk.scale.y = mk.scale.z = radius;
00135             mk.color = color;
00136             mk.lifetime = ros::Duration(lifetime);
00137             arr.markers.push_back(mk);
00138             pub_markers.publish(arr);
00139           }
00140           pub_markers.publish(arr);
00141           published = points.size();
00142         }
00143       }
00144     }
00145   }
00146 
00147   return 0;
00148 }


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Jul 24 2017 02:21:19