moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 #pragma once
38 
39 #include <ros/ros.h>
40 #include <planning_models/robot_model.h>
42 
43 namespace collision_detection
44 {
45 static inline bool loadLinkBodySphereDecompositions(
46  ros::NodeHandle& nh, const planning_models::RobotModelConstPtr& robot_model,
47  std::map<std::string, std::vector<collision_detection::CollisionSphere> >& link_body_spheres)
48 {
49  if (!nh.hasParam("link_spheres"))
50  {
51  ROS_INFO_STREAM("No parameter for link spheres");
52  return false;
53  }
54  XmlRpc::XmlRpcValue link_spheres;
55  nh.getParam("link_spheres", link_spheres);
56 
57  if (link_spheres.getType() != XmlRpc::XmlRpcValue::TypeArray)
58  {
59  ROS_WARN_STREAM("Link spheres not an array");
60  return false;
61  }
62 
63  if (link_spheres.size() == 0)
64  {
65  ROS_WARN_STREAM("Link spheres has no entries");
66  return false;
67  }
68  for (int i = 0; i < link_spheres.size(); ++i)
69  {
70  if (!link_spheres[i].hasMember("link"))
71  {
72  ROS_WARN_STREAM("All link spheres must have link");
73  continue;
74  }
75  if (!link_spheres[i].hasMember("spheres"))
76  {
77  ROS_WARN_STREAM("All link spheres must have spheres");
78  continue;
79  }
80  std::string link = link_spheres[i]["link"];
81  XmlRpc::XmlRpcValue spheres = link_spheres[i]["spheres"];
82  if (spheres.getType() != XmlRpc::XmlRpcValue::TypeArray)
83  {
84  if (std::string(spheres) == "none")
85  {
86  ROS_DEBUG_STREAM("No spheres for " << link);
87  std::vector<collision_detection::CollisionSphere> coll_spheres;
88  link_body_spheres[link_spheres[i]["link"]] = coll_spheres;
89  continue;
90  }
91  }
92  std::vector<collision_detection::CollisionSphere> coll_spheres;
93  for (int j = 0; j < spheres.size(); ++j)
94  {
95  if (!spheres[j].hasMember("x"))
96  {
97  ROS_WARN_STREAM("All spheres must specify a value for x");
98  continue;
99  }
100  if (!spheres[j].hasMember("y"))
101  {
102  ROS_WARN_STREAM("All spheres must specify a value for y");
103  continue;
104  }
105  if (!spheres[j].hasMember("z"))
106  {
107  ROS_WARN_STREAM("All spheres must specify a value for z");
108  continue;
109  }
110  if (!spheres[j].hasMember("radius"))
111  {
112  ROS_WARN_STREAM("All spheres must specify a value for radius");
113  continue;
114  }
115  Eigen::Vector3d rel(spheres[j]["x"], spheres[j]["y"], spheres[j]["z"]);
116  ROS_DEBUG_STREAM("Link " << link_spheres[i]["link"] << " sphere " << coll_spheres.size() << " " << rel.x() << " "
117  << rel.y() << " " << rel.z());
118  collision_detection::CollisionSphere cs(rel, spheres[j]["radius"]);
119  coll_spheres.push_back(cs);
120  }
121  link_body_spheres[link_spheres[i]["link"]] = coll_spheres;
122  // std::cerr << "For link " << link_spheres[i]["link"] << " adding " << coll_spheres.size() << " spheres " <<
123  // std::endl;
124  }
125  return true;
126 }
127 } // namespace collision_detection
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89