moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
collision_tools.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2011, 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 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
35/* Author: Ioan Sucan */
36
38#include <rclcpp/clock.hpp>
39#include <rclcpp/time.hpp>
40#include <tf2_eigen/tf2_eigen.hpp>
41
42namespace collision_detection
43{
44void getCostMarkers(visualization_msgs::msg::MarkerArray& arr, const std::string& frame_id,
45 std::set<CostSource>& cost_sources)
46{
47 std_msgs::msg::ColorRGBA color;
48 color.r = 1.0f;
49 color.g = 0.5f;
50 color.b = 0.0f;
51 color.a = 0.4f;
52 getCostMarkers(arr, frame_id, cost_sources, color, rclcpp::Duration(60, 0));
53}
54
55void getCollisionMarkersFromContacts(visualization_msgs::msg::MarkerArray& arr, const std::string& frame_id,
57{
58 std_msgs::msg::ColorRGBA color;
59 color.r = 1.0f;
60 color.g = 0.0f;
61 color.b = 0.0f;
62 color.a = 0.8f;
63 getCollisionMarkersFromContacts(arr, frame_id, con, color, rclcpp::Duration(60, 0));
64}
65
66void getCostMarkers(visualization_msgs::msg::MarkerArray& arr, const std::string& frame_id,
67 std::set<CostSource>& cost_sources, const std_msgs::msg::ColorRGBA& color,
68 const rclcpp::Duration& lifetime)
69{
70 int id = 0;
71 for (const auto& cost_source : cost_sources)
72 {
73 visualization_msgs::msg::Marker mk;
74 mk.header.stamp = rclcpp::Clock(RCL_ROS_TIME).now();
75 mk.header.frame_id = frame_id;
76 mk.ns = "cost_source";
77 mk.id = id++;
78 mk.type = visualization_msgs::msg::Marker::CUBE;
79 mk.action = visualization_msgs::msg::Marker::ADD;
80 mk.pose.position.x = (cost_source.aabb_max[0] + cost_source.aabb_min[0]) / 2.0;
81 mk.pose.position.y = (cost_source.aabb_max[1] + cost_source.aabb_min[1]) / 2.0;
82 mk.pose.position.z = (cost_source.aabb_max[2] + cost_source.aabb_min[2]) / 2.0;
83 mk.pose.orientation.x = 0.0;
84 mk.pose.orientation.y = 0.0;
85 mk.pose.orientation.z = 0.0;
86 mk.pose.orientation.w = 1.0;
87 mk.scale.x = cost_source.aabb_max[0] - cost_source.aabb_min[0];
88 mk.scale.y = cost_source.aabb_max[1] - cost_source.aabb_min[1];
89 mk.scale.z = cost_source.aabb_max[2] - cost_source.aabb_min[2];
90 mk.color = color;
91 if (mk.color.a == 0.0)
92 mk.color.a = 1.0;
93 mk.lifetime = lifetime;
94 arr.markers.push_back(mk);
95 }
96}
97
98void getCollisionMarkersFromContacts(visualization_msgs::msg::MarkerArray& arr, const std::string& frame_id,
99 const CollisionResult::ContactMap& con, const std_msgs::msg::ColorRGBA& color,
100 const rclcpp::Duration& lifetime, double radius)
101
102{
103 std::map<std::string, unsigned> ns_counts;
104
105 for (const auto& collision : con)
106 {
107 for (const auto& contact : collision.second)
108 {
109 std::string ns_name = contact.body_name_1 + "=" + contact.body_name_2;
110 if (ns_counts.find(ns_name) == ns_counts.end())
111 {
112 ns_counts[ns_name] = 0;
113 }
114 else
115 {
116 ns_counts[ns_name]++;
117 }
118 visualization_msgs::msg::Marker mk;
119 mk.header.stamp = rclcpp::Clock(RCL_ROS_TIME).now();
120 mk.header.frame_id = frame_id;
121 mk.ns = ns_name;
122 mk.id = ns_counts[ns_name];
123 mk.type = visualization_msgs::msg::Marker::SPHERE;
124 mk.action = visualization_msgs::msg::Marker::ADD;
125 mk.pose.position.x = contact.pos.x();
126 mk.pose.position.y = contact.pos.y();
127 mk.pose.position.z = contact.pos.z();
128 mk.pose.orientation.x = 0.0;
129 mk.pose.orientation.y = 0.0;
130 mk.pose.orientation.z = 0.0;
131 mk.pose.orientation.w = 1.0;
132 mk.scale.x = mk.scale.y = mk.scale.z = radius * 2.0;
133 mk.color = color;
134 if (mk.color.a == 0.0)
135 mk.color.a = 1.0;
136 mk.lifetime = lifetime;
137 arr.markers.push_back(mk);
138 }
139 }
140}
141
142bool getSensorPositioning(geometry_msgs::msg::Point& point, const std::set<CostSource>& cost_sources)
143{
144 if (cost_sources.empty())
145 return false;
146 auto it = cost_sources.begin();
147 for (std::size_t i = 0; i < 4 * cost_sources.size() / 5; ++i)
148 ++it;
149 point.x = (it->aabb_max[0] + it->aabb_min[0]) / 2.0;
150 point.y = (it->aabb_max[1] + it->aabb_min[1]) / 2.0;
151 point.z = (it->aabb_max[2] + it->aabb_min[2]) / 2.0;
152 return true;
153}
154
155double getTotalCost(const std::set<CostSource>& cost_sources)
156{
157 double cost = 0.0;
158 for (const auto& cost_source : cost_sources)
159 cost += cost_source.getVolume() * cost_source.cost;
160 return cost;
161}
162
163void intersectCostSources(std::set<CostSource>& cost_sources, const std::set<CostSource>& a,
164 const std::set<CostSource>& b)
165{
166 cost_sources.clear();
167 CostSource tmp;
168 for (const auto& source_a : a)
169 {
170 for (const auto& source_b : b)
171 {
172 tmp.aabb_min[0] = std::max(source_a.aabb_min[0], source_b.aabb_min[0]);
173 tmp.aabb_min[1] = std::max(source_a.aabb_min[1], source_b.aabb_min[1]);
174 tmp.aabb_min[2] = std::max(source_a.aabb_min[2], source_b.aabb_min[2]);
175
176 tmp.aabb_max[0] = std::min(source_a.aabb_max[0], source_b.aabb_max[0]);
177 tmp.aabb_max[1] = std::min(source_a.aabb_max[1], source_b.aabb_max[1]);
178 tmp.aabb_max[2] = std::min(source_a.aabb_max[2], source_b.aabb_max[2]);
179
180 if (tmp.aabb_min[0] >= tmp.aabb_max[0] || tmp.aabb_min[1] >= tmp.aabb_max[1] || tmp.aabb_min[2] >= tmp.aabb_max[2])
181 continue;
182 tmp.cost = std::max(source_a.cost, source_b.cost);
183 cost_sources.insert(tmp);
184 }
185 }
186}
187
188void removeOverlapping(std::set<CostSource>& cost_sources, const double overlap_fraction)
189{
190 double p[3], q[3];
191 for (auto it = cost_sources.begin(); it != cost_sources.end(); ++it)
192 {
193 const double vol = it->getVolume() * overlap_fraction;
194 std::vector<std::set<CostSource>::iterator> remove;
195 auto it1 = it;
196 for (auto jt = ++it1; jt != cost_sources.end(); ++jt)
197 {
198 p[0] = std::max(it->aabb_min[0], jt->aabb_min[0]);
199 p[1] = std::max(it->aabb_min[1], jt->aabb_min[1]);
200 p[2] = std::max(it->aabb_min[2], jt->aabb_min[2]);
201
202 q[0] = std::min(it->aabb_max[0], jt->aabb_max[0]);
203 q[1] = std::min(it->aabb_max[1], jt->aabb_max[1]);
204 q[2] = std::min(it->aabb_max[2], jt->aabb_max[2]);
205
206 if (p[0] >= q[0] || p[1] >= q[1] || p[2] >= q[2])
207 continue;
208
209 const double intersect_volume = (q[0] - p[0]) * (q[1] - p[1]) * (q[2] - p[2]);
210 if (intersect_volume >= vol)
211 remove.push_back(jt);
212 }
213 for (auto& r : remove)
214 cost_sources.erase(r);
215 }
216}
217
218void removeCostSources(std::set<CostSource>& cost_sources, const std::set<CostSource>& cost_sources_to_remove,
219 const double overlap_fraction)
220{
221 // remove all the boxes that overlap with the intersection previously computed in \e rem
222 double p[3], q[3];
223 for (const auto& source_remove : cost_sources_to_remove)
224 {
225 std::vector<std::set<CostSource>::iterator> remove;
226 std::set<CostSource> add;
227 for (auto it = cost_sources.begin(); it != cost_sources.end(); ++it)
228 {
229 p[0] = std::max(it->aabb_min[0], source_remove.aabb_min[0]);
230 p[1] = std::max(it->aabb_min[1], source_remove.aabb_min[1]);
231 p[2] = std::max(it->aabb_min[2], source_remove.aabb_min[2]);
232
233 q[0] = std::min(it->aabb_max[0], source_remove.aabb_max[0]);
234 q[1] = std::min(it->aabb_max[1], source_remove.aabb_max[1]);
235 q[2] = std::min(it->aabb_max[2], source_remove.aabb_max[2]);
236
237 if (p[0] >= q[0] || p[1] >= q[1] || p[2] >= q[2])
238 continue;
239
240 const double intersect_volume = (q[0] - p[0]) * (q[1] - p[1]) * (q[2] - p[2]);
241 if (intersect_volume >= it->getVolume() * overlap_fraction)
242 {
243 remove.push_back(it);
244 }
245 else
246 {
247 // there is some overlap, but not too large, so we split the cost source into multiple ones
248 for (int i = 0; i < 3; ++i)
249 {
250 // is there a box above axis i in the intersection?
251 if (it->aabb_max[i] > q[i])
252 {
253 CostSource cs = *it;
254 cs.aabb_min[i] = q[i];
255 add.insert(cs);
256 }
257 // is there a box below axis i in the intersection?
258 if (it->aabb_min[i] < p[i])
259 {
260 CostSource cs = *it;
261 cs.aabb_max[i] = p[i];
262 add.insert(cs);
263 }
264 }
265 }
266 }
267 for (auto& r : remove)
268 cost_sources.erase(r);
269 cost_sources.insert(add.begin(), add.end());
270 }
271}
272
273void costSourceToMsg(const CostSource& cost_source, moveit_msgs::msg::CostSource& msg)
274{
275 msg.cost_density = cost_source.cost;
276 msg.aabb_min.x = cost_source.aabb_min[0];
277 msg.aabb_min.y = cost_source.aabb_min[1];
278 msg.aabb_min.z = cost_source.aabb_min[2];
279 msg.aabb_max.x = cost_source.aabb_max[0];
280 msg.aabb_max.y = cost_source.aabb_max[1];
281 msg.aabb_max.z = cost_source.aabb_max[2];
282}
283
284void contactToMsg(const Contact& contact, moveit_msgs::msg::ContactInformation& msg)
285{
286 msg.position = tf2::toMsg(contact.pos);
287 msg.normal = tf2::toMsg2(contact.normal);
288 msg.depth = contact.depth;
289 msg.contact_body_1 = contact.body_name_1;
290 msg.contact_body_2 = contact.body_name_2;
291 if (contact.body_type_1 == BodyTypes::ROBOT_LINK)
292 {
293 msg.body_type_1 = moveit_msgs::msg::ContactInformation::ROBOT_LINK;
294 }
295 else if (contact.body_type_1 == BodyTypes::ROBOT_ATTACHED)
296 {
297 msg.body_type_1 = moveit_msgs::msg::ContactInformation::ROBOT_ATTACHED;
298 }
299 else
300 {
301 msg.body_type_1 = moveit_msgs::msg::ContactInformation::WORLD_OBJECT;
302 }
303 if (contact.body_type_2 == BodyTypes::ROBOT_LINK)
304 {
305 msg.body_type_2 = moveit_msgs::msg::ContactInformation::ROBOT_LINK;
306 }
307 else if (contact.body_type_2 == BodyTypes::ROBOT_ATTACHED)
308 {
309 msg.body_type_2 = moveit_msgs::msg::ContactInformation::ROBOT_ATTACHED;
310 }
311 else
312 {
313 msg.body_type_2 = moveit_msgs::msg::ContactInformation::WORLD_OBJECT;
314 }
315}
316
317} // end of namespace collision_detection
@ ROBOT_LINK
A link on the robot.
@ ROBOT_ATTACHED
A body attached to a robot link.
bool getSensorPositioning(geometry_msgs::msg::Point &point, const std::set< CostSource > &cost_sources)
double getTotalCost(const std::set< CostSource > &cost_sources)
void getCollisionMarkersFromContacts(visualization_msgs::msg::MarkerArray &arr, const std::string &frame_id, const CollisionResult::ContactMap &con, const std_msgs::msg::ColorRGBA &color, const rclcpp::Duration &lifetime, const double radius=0.035)
void getCostMarkers(visualization_msgs::msg::MarkerArray &arr, const std::string &frame_id, std::set< CostSource > &cost_sources)
void intersectCostSources(std::set< CostSource > &cost_sources, const std::set< CostSource > &a, const std::set< CostSource > &b)
void removeCostSources(std::set< CostSource > &cost_sources, const std::set< CostSource > &cost_sources_to_remove, double overlap_fraction)
void contactToMsg(const Contact &contact, moveit_msgs::msg::ContactInformation &msg)
void removeOverlapping(std::set< CostSource > &cost_sources, double overlap_fraction)
void costSourceToMsg(const CostSource &cost_source, moveit_msgs::msg::CostSource &msg)
std::map< std::pair< std::string, std::string >, std::vector< Contact > > ContactMap
A map returning the pairs of body ids in contact, plus their contact details.
Definition of a contact point.
std::string body_name_2
The id of the second body involved in the contact.
std::string body_name_1
The id of the first body involved in the contact.
BodyType body_type_1
The type of the first body involved in the contact.
BodyType body_type_2
The type of the second body involved in the contact.
Eigen::Vector3d normal
normal unit vector at contact
double depth
depth (penetration between bodies)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d pos
contact position
When collision costs are computed, this structure contains information about the partial cost incurre...
std::array< double, 3 > aabb_max
The maximum bound of the AABB defining the volume responsible for this partial cost.
double cost
The partial cost (the probability of existence for the object there is a collision with)
std::array< double, 3 > aabb_min
The minimum bound of the AABB defining the volume responsible for this partial cost.