collision_distance_field_ros_helpers.h
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 the 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 
00037 #ifndef COLLISION_DISTANCE_FIELD_HELPERS_H_
00038 #define COLLISION_DISTANCE_FIELD_HELPERS_H_
00039 
00040 #include <ros/ros.h>
00041 #include <planning_models/robot_model.h>
00042 #include <collision_distance_field/collision_distance_field_types.h>
00043 
00044 namespace collision_detection
00045 {
00046 static inline bool loadLinkBodySphereDecompositions(
00047     ros::NodeHandle& nh, const planning_models::RobotModelConstPtr& kmodel,
00048     std::map<std::string, std::vector<collision_detection::CollisionSphere> >& link_body_spheres)
00049 {
00050   if (!nh.hasParam("link_spheres"))
00051   {
00052     ROS_INFO_STREAM("No parameter for link spheres");
00053     return false;
00054   }
00055   XmlRpc::XmlRpcValue link_spheres;
00056   nh.getParam("link_spheres", link_spheres);
00057 
00058   if (link_spheres.getType() != XmlRpc::XmlRpcValue::TypeArray)
00059   {
00060     ROS_WARN_STREAM("Link spheres not an array");
00061     return false;
00062   }
00063 
00064   if (link_spheres.size() == 0)
00065   {
00066     ROS_WARN_STREAM("Link spheres has no entries");
00067     return false;
00068   }
00069   for (int i = 0; i < link_spheres.size(); i++)
00070   {
00071     if (!link_spheres[i].hasMember("link"))
00072     {
00073       ROS_WARN_STREAM("All link spheres must have link");
00074       continue;
00075     }
00076     if (!link_spheres[i].hasMember("spheres"))
00077     {
00078       ROS_WARN_STREAM("All link spheres must have spheres");
00079       continue;
00080     }
00081     std::string link = link_spheres[i]["link"];
00082     XmlRpc::XmlRpcValue spheres = link_spheres[i]["spheres"];
00083     if (spheres.getType() != XmlRpc::XmlRpcValue::TypeArray)
00084     {
00085       if (std::string(spheres) == "none")
00086       {
00087         ROS_DEBUG_STREAM("No spheres for " << link);
00088         std::vector<collision_detection::CollisionSphere> coll_spheres;
00089         link_body_spheres[link_spheres[i]["link"]] = coll_spheres;
00090         continue;
00091       }
00092     }
00093     std::vector<collision_detection::CollisionSphere> coll_spheres;
00094     for (int j = 0; j < spheres.size(); j++)
00095     {
00096       if (!spheres[j].hasMember("x"))
00097       {
00098         ROS_WARN_STREAM("All spheres must specify a value for x");
00099         continue;
00100       }
00101       if (!spheres[j].hasMember("y"))
00102       {
00103         ROS_WARN_STREAM("All spheres must specify a value for y");
00104         continue;
00105       }
00106       if (!spheres[j].hasMember("z"))
00107       {
00108         ROS_WARN_STREAM("All spheres must specify a value for z");
00109         continue;
00110       }
00111       if (!spheres[j].hasMember("radius"))
00112       {
00113         ROS_WARN_STREAM("All spheres must specify a value for radius");
00114         continue;
00115       }
00116       Eigen::Vector3d rel(spheres[j]["x"], spheres[j]["y"], spheres[j]["z"]);
00117       ROS_DEBUG_STREAM("Link " << link_spheres[i]["link"] << " sphere " << coll_spheres.size() << " " << rel.x() << " "
00118                                << rel.y() << " " << rel.z());
00119       collision_detection::CollisionSphere cs(rel, spheres[j]["radius"]);
00120       coll_spheres.push_back(cs);
00121     }
00122     link_body_spheres[link_spheres[i]["link"]] = coll_spheres;
00123     // std::cerr << "For link " << link_spheres[i]["link"] << " adding " << coll_spheres.size() << " spheres " <<
00124     // std::endl;
00125   }
00126   return true;
00127 }
00128 }
00129 #endif


moveit_experimental
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley , Jorge Nicho
autogenerated on Wed Jun 19 2019 19:24:03