collision_distance_field_ros_helpers.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
37 #ifndef COLLISION_DISTANCE_FIELD_HELPERS_H_
38 #define COLLISION_DISTANCE_FIELD_HELPERS_H_
39 
40 #include <ros/ros.h>
41 #include <planning_models/robot_model.h>
42 #include <collision_distance_field/collision_distance_field_types.h>
43 
45 {
47  ros::NodeHandle& nh, const planning_models::RobotModelConstPtr& kmodel,
48  std::map<std::string, std::vector<collision_detection::CollisionSphere> >& link_body_spheres)
49 {
50  if (!nh.hasParam("link_spheres"))
51  {
52  ROS_INFO_STREAM("No parameter for link spheres");
53  return false;
54  }
55  XmlRpc::XmlRpcValue link_spheres;
56  nh.getParam("link_spheres", link_spheres);
57 
58  if (link_spheres.getType() != XmlRpc::XmlRpcValue::TypeArray)
59  {
60  ROS_WARN_STREAM("Link spheres not an array");
61  return false;
62  }
63 
64  if (link_spheres.size() == 0)
65  {
66  ROS_WARN_STREAM("Link spheres has no entries");
67  return false;
68  }
69  for (int i = 0; i < link_spheres.size(); i++)
70  {
71  if (!link_spheres[i].hasMember("link"))
72  {
73  ROS_WARN_STREAM("All link spheres must have link");
74  continue;
75  }
76  if (!link_spheres[i].hasMember("spheres"))
77  {
78  ROS_WARN_STREAM("All link spheres must have spheres");
79  continue;
80  }
81  std::string link = link_spheres[i]["link"];
82  XmlRpc::XmlRpcValue spheres = link_spheres[i]["spheres"];
83  if (spheres.getType() != XmlRpc::XmlRpcValue::TypeArray)
84  {
85  if (std::string(spheres) == "none")
86  {
87  ROS_DEBUG_STREAM("No spheres for " << link);
88  std::vector<collision_detection::CollisionSphere> coll_spheres;
89  link_body_spheres[link_spheres[i]["link"]] = coll_spheres;
90  continue;
91  }
92  }
93  std::vector<collision_detection::CollisionSphere> coll_spheres;
94  for (int j = 0; j < spheres.size(); j++)
95  {
96  if (!spheres[j].hasMember("x"))
97  {
98  ROS_WARN_STREAM("All spheres must specify a value for x");
99  continue;
100  }
101  if (!spheres[j].hasMember("y"))
102  {
103  ROS_WARN_STREAM("All spheres must specify a value for y");
104  continue;
105  }
106  if (!spheres[j].hasMember("z"))
107  {
108  ROS_WARN_STREAM("All spheres must specify a value for z");
109  continue;
110  }
111  if (!spheres[j].hasMember("radius"))
112  {
113  ROS_WARN_STREAM("All spheres must specify a value for radius");
114  continue;
115  }
116  Eigen::Vector3d rel(spheres[j]["x"], spheres[j]["y"], spheres[j]["z"]);
117  ROS_DEBUG_STREAM("Link " << link_spheres[i]["link"] << " sphere " << coll_spheres.size() << " " << rel.x() << " "
118  << rel.y() << " " << rel.z());
119  collision_detection::CollisionSphere cs(rel, spheres[j]["radius"]);
120  coll_spheres.push_back(cs);
121  }
122  link_body_spheres[link_spheres[i]["link"]] = coll_spheres;
123  // std::cerr << "For link " << link_spheres[i]["link"] << " adding " << coll_spheres.size() << " spheres " <<
124  // std::endl;
125  }
126  return true;
127 }
128 }
129 #endif
static bool loadLinkBodySphereDecompositions(ros::NodeHandle &nh, const planning_models::RobotModelConstPtr &kmodel, std::map< std::string, std::vector< collision_detection::CollisionSphere > > &link_body_spheres)


moveit_experimental
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley , Jorge Nicho
autogenerated on Wed Jul 10 2019 04:03:02