moveit2
The MoveIt Motion Planning Framework for ROS 2.
collision_matrix.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, E. Gil Jones */
36 
38 #include <rclcpp/logger.hpp>
39 #include <rclcpp/logging.hpp>
40 #include <functional>
41 #include <iomanip>
42 
43 namespace collision_detection
44 {
45 // Logger
46 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_collision_detection.collision_matrix");
47 
49 {
50 }
51 
52 AllowedCollisionMatrix::AllowedCollisionMatrix(const std::vector<std::string>& names, const bool allowed)
53 {
54  for (std::size_t i = 0; i < names.size(); ++i)
55  for (std::size_t j = i; j < names.size(); ++j)
56  setEntry(names[i], names[j], allowed);
57 }
58 
60 {
61  // load collision defaults
62  for (const std::string& name : srdf.getNoDefaultCollisionLinks())
64  // re-enable specific collision pairs
65  for (auto const& collision : srdf.getEnabledCollisionPairs())
66  setEntry(collision.link1_, collision.link2_, false);
67  // *finally* disable selected collision pairs
68  for (auto const& collision : srdf.getDisabledCollisionPairs())
69  setEntry(collision.link1_, collision.link2_, true);
70 }
71 
72 AllowedCollisionMatrix::AllowedCollisionMatrix(const moveit_msgs::msg::AllowedCollisionMatrix& msg)
73 {
74  if (msg.entry_names.size() != msg.entry_values.size() ||
75  msg.default_entry_names.size() != msg.default_entry_values.size())
76  {
77  RCLCPP_ERROR(LOGGER, "The number of links does not match the number of entries in AllowedCollisionMatrix message");
78  return;
79  }
80  for (std::size_t i = 0; i < msg.default_entry_names.size(); ++i)
81  {
82  setDefaultEntry(msg.default_entry_names[i], msg.default_entry_values[i]);
83  }
84 
85  for (std::size_t i = 0; i < msg.entry_names.size(); ++i)
86  {
87  if (msg.entry_values[i].enabled.size() != msg.entry_names.size())
88  {
89  RCLCPP_ERROR(LOGGER, "Number of entries is incorrect for link '%s' in AllowedCollisionMatrix message",
90  msg.entry_names[i].c_str());
91  return;
92  }
93  for (std::size_t j = i + 1; j < msg.entry_values[i].enabled.size(); ++j)
94  {
95  AllowedCollision::Type allowed_default, allowed_entry;
96  if (!getDefaultEntry(msg.entry_names[i], msg.entry_names[j], allowed_default))
97  allowed_default = AllowedCollision::NEVER;
98  allowed_entry = msg.entry_values[i].enabled[j] ? AllowedCollision::ALWAYS : AllowedCollision::NEVER;
99 
100  if (allowed_entry != allowed_default)
101  setEntry(msg.entry_names[i], msg.entry_names[j], allowed_entry);
102  }
103  }
104 }
105 
106 bool AllowedCollisionMatrix::getEntry(const std::string& name1, const std::string& name2, DecideContactFn& fn) const
107 {
108  const auto it1 = allowed_contacts_.find(name1);
109  if (it1 == allowed_contacts_.end())
110  return false;
111  const auto it2 = it1->second.find(name2);
112  if (it2 == it1->second.end())
113  return false;
114  fn = it2->second;
115  return true;
116 }
117 
118 bool AllowedCollisionMatrix::getEntry(const std::string& name1, const std::string& name2,
119  AllowedCollision::Type& allowed_collision) const
120 {
121  const auto it1 = entries_.find(name1);
122  if (it1 == entries_.end())
123  return false;
124  auto it2 = it1->second.find(name2);
125  if (it2 == it1->second.end())
126  return false;
127  allowed_collision = it2->second;
128  return true;
129 }
130 
131 bool AllowedCollisionMatrix::hasEntry(const std::string& name) const
132 {
133  return entries_.find(name) != entries_.end();
134 }
135 
136 bool AllowedCollisionMatrix::hasEntry(const std::string& name1, const std::string& name2) const
137 {
138  const auto it1 = entries_.find(name1);
139  if (it1 == entries_.end())
140  return false;
141  const auto it2 = it1->second.find(name2);
142  return it2 != it1->second.end();
143 }
144 
145 void AllowedCollisionMatrix::setEntry(const std::string& name1, const std::string& name2, const bool allowed)
146 {
148  entries_[name1][name2] = entries_[name2][name1] = v;
149 
150  // remove function pointers, if any
151  auto it = allowed_contacts_.find(name1);
152  if (it != allowed_contacts_.end())
153  {
154  auto jt = it->second.find(name2);
155  if (jt != it->second.end())
156  it->second.erase(jt);
157  }
158  it = allowed_contacts_.find(name2);
159  if (it != allowed_contacts_.end())
160  {
161  auto jt = it->second.find(name1);
162  if (jt != it->second.end())
163  it->second.erase(jt);
164  }
165 }
166 
167 void AllowedCollisionMatrix::setEntry(const std::string& name1, const std::string& name2, DecideContactFn& fn)
168 {
169  entries_[name1][name2] = entries_[name2][name1] = AllowedCollision::CONDITIONAL;
170  allowed_contacts_[name1][name2] = allowed_contacts_[name2][name1] = fn;
171 }
172 
174 {
175  entries_.erase(name);
176  allowed_contacts_.erase(name);
177  for (auto& entry : entries_)
178  entry.second.erase(name);
179  for (auto& allowed_contact : allowed_contacts_)
180  allowed_contact.second.erase(name);
181 }
182 
183 void AllowedCollisionMatrix::removeEntry(const std::string& name1, const std::string& name2)
184 {
185  auto jt = entries_.find(name1);
186  if (jt != entries_.end())
187  {
188  auto it = jt->second.find(name2);
189  if (it != jt->second.end())
190  jt->second.erase(it);
191  }
192  jt = entries_.find(name2);
193  if (jt != entries_.end())
194  {
195  auto it = jt->second.find(name1);
196  if (it != jt->second.end())
197  jt->second.erase(it);
198  }
199 
200  auto it = allowed_contacts_.find(name1);
201  if (it != allowed_contacts_.end())
202  {
203  auto jt = it->second.find(name2);
204  if (jt != it->second.end())
205  it->second.erase(jt);
206  }
207  it = allowed_contacts_.find(name2);
208  if (it != allowed_contacts_.end())
209  {
210  auto jt = it->second.find(name1);
211  if (jt != it->second.end())
212  it->second.erase(jt);
213  }
214 }
215 
216 void AllowedCollisionMatrix::setEntry(const std::string& name, const std::vector<std::string>& other_names,
217  const bool allowed)
218 {
219  for (const auto& other_name : other_names)
220  if (other_name != name)
221  setEntry(other_name, name, allowed);
222 }
223 
224 void AllowedCollisionMatrix::setEntry(const std::vector<std::string>& names1, const std::vector<std::string>& names2,
225  const bool allowed)
226 {
227  for (const auto& name1 : names1)
228  setEntry(name1, names2, allowed);
229 }
230 
231 void AllowedCollisionMatrix::setEntry(const std::string& name, const bool allowed)
232 {
233  std::string last = name;
234  for (auto& entry : entries_)
235  if (name != entry.first && last != entry.first)
236  {
237  last = entry.first;
238  setEntry(name, entry.first, allowed);
239  }
240 }
241 
242 void AllowedCollisionMatrix::setEntry(const bool allowed)
243 {
245  for (auto& entry : entries_)
246  for (auto& it2 : entry.second)
247  it2.second = v;
248 }
249 
250 void AllowedCollisionMatrix::setDefaultEntry(const std::string& name, const bool allowed)
251 {
253  default_entries_[name] = v;
254  default_allowed_contacts_.erase(name);
255 }
256 
258 {
259  default_entries_[name] = AllowedCollision::CONDITIONAL;
260  default_allowed_contacts_[name] = fn;
261 }
262 
263 bool AllowedCollisionMatrix::getDefaultEntry(const std::string& name, AllowedCollision::Type& allowed_collision) const
264 {
265  auto it = default_entries_.find(name);
266  if (it == default_entries_.end())
267  return false;
268  allowed_collision = it->second;
269  return true;
270 }
271 
273 {
274  auto it = default_allowed_contacts_.find(name);
275  if (it == default_allowed_contacts_.end())
276  return false;
277  fn = it->second;
278  return true;
279 }
280 
281 static bool andDecideContact(const DecideContactFn& f1, const DecideContactFn& f2, Contact& contact)
282 {
283  return f1(contact) && f2(contact);
284 }
285 
286 bool AllowedCollisionMatrix::getAllowedCollision(const std::string& name1, const std::string& name2,
287  DecideContactFn& fn) const
288 {
289  const bool found = getEntry(name1, name2, fn);
290  if (!found)
291  {
292  DecideContactFn fn1, fn2;
293  const bool found1 = getDefaultEntry(name1, fn1);
294  const bool found2 = getDefaultEntry(name2, fn2);
295  if (found1 && !found2)
296  fn = fn1;
297  else if (!found1 && found2)
298  fn = fn2;
299  else if (found1 && found2)
300  fn = [fn1, fn2](Contact& contact) { return andDecideContact(fn1, fn2, contact); };
301  else
302  return false;
303  }
304  return true;
305 }
306 
307 bool AllowedCollisionMatrix::getDefaultEntry(const std::string& name1, const std::string& name2,
308  AllowedCollision::Type& allowed_collision) const
309 {
310  AllowedCollision::Type t1, t2;
311  const bool found1 = getDefaultEntry(name1, t1);
312  const bool found2 = getDefaultEntry(name2, t2);
313  if (!found1 && !found2)
314  return false;
315  else if (found1 && !found2)
316  allowed_collision = t1;
317  else if (!found1 && found2)
318  allowed_collision = t2;
319  else if (found1 && found2)
320  {
322  allowed_collision = AllowedCollision::NEVER;
324  allowed_collision = AllowedCollision::CONDITIONAL;
325  else // ALWAYS is the only remaining case
326  allowed_collision = AllowedCollision::ALWAYS;
327  }
328  return true;
329 }
330 
331 bool AllowedCollisionMatrix::getAllowedCollision(const std::string& name1, const std::string& name2,
332  AllowedCollision::Type& allowed_collision) const
333 {
334  return getEntry(name1, name2, allowed_collision) || getDefaultEntry(name1, name2, allowed_collision);
335 }
336 
338 {
339  entries_.clear();
340  allowed_contacts_.clear();
341  default_entries_.clear();
342  default_allowed_contacts_.clear();
343 }
344 
345 void AllowedCollisionMatrix::getAllEntryNames(std::vector<std::string>& names) const
346 {
347  names.clear();
348  for (const auto& entry : entries_)
349  names.push_back(entry.first);
350 
351  for (const auto& item : default_entries_)
352  {
353  auto it = std::lower_bound(names.begin(), names.end(), item.first);
354  if (it != names.end() && *it != item.first)
355  names.insert(it, item.first);
356  }
357 }
358 
359 void AllowedCollisionMatrix::getMessage(moveit_msgs::msg::AllowedCollisionMatrix& msg) const
360 {
361  msg.entry_names.clear();
362  msg.entry_values.clear();
363  msg.default_entry_names.clear();
364  msg.default_entry_values.clear();
365 
366  getAllEntryNames(msg.entry_names);
367 
368  msg.entry_values.resize(msg.entry_names.size());
369  for (std::size_t i = 0; i < msg.entry_names.size(); ++i)
370  msg.entry_values[i].enabled.resize(msg.entry_names.size(), false);
371 
372  // there is an approximation here: if we use a function to decide
373  // whether a collision is allowed or not, we just assume the collision is not allowed.
374  for (std::size_t i = 0; i < msg.entry_names.size(); ++i)
375  {
377  const bool dfound = getDefaultEntry(msg.entry_names[i], dtype);
378  if (dfound)
379  {
380  msg.default_entry_names.push_back(msg.entry_names[i]);
381  msg.default_entry_values.push_back(dtype == AllowedCollision::ALWAYS);
382  }
383 
384  for (std::size_t j = i; j < msg.entry_names.size(); ++j)
385  {
387  getAllowedCollision(msg.entry_names[i], msg.entry_names[j], type);
388  msg.entry_values[i].enabled[j] = msg.entry_values[j].enabled[i] = (type == AllowedCollision::ALWAYS);
389  }
390  }
391 }
392 
393 void AllowedCollisionMatrix::print(std::ostream& out) const
394 {
395  std::vector<std::string> names;
396  getAllEntryNames(names);
397 
398  std::size_t spacing = 4;
399  for (const auto& name : names)
400  {
401  const std::size_t length = name.length();
402  if (length > spacing)
403  spacing = length;
404  }
405  ++spacing;
406 
407  std::size_t number_digits = 2;
408  while (names.size() > pow(10, number_digits) - 1)
409  number_digits++;
410 
411  // print indices along the top of the matrix
412  for (std::size_t j = 0; j < number_digits; ++j)
413  {
414  out << std::setw(spacing + number_digits + 8) << "";
415  for (std::size_t i = 0; i < names.size(); ++i)
416  {
417  std::stringstream ss;
418  ss << std::setw(number_digits) << i;
419  out << std::setw(3) << ss.str().c_str()[j];
420  }
421  out << '\n';
422  }
423 
424  const char* indicator = "01?"; // ALWAYS / NEVER / CONDITIONAL
425  for (std::size_t i = 0; i < names.size(); ++i)
426  {
427  out << std::setw(spacing) << names[i];
428  out << std::setw(number_digits + 1) << i;
429  out << " | ";
430  // print default value
432  if (getDefaultEntry(names[i], type))
433  out << indicator[type];
434  else
435  out << '-';
436  out << " | ";
437  // print pairs
438  for (std::size_t j = 0; j < names.size(); ++j)
439  {
440  const bool found = getAllowedCollision(names[i], names[j], type);
441  if (found)
442  out << std::setw(3) << indicator[type];
443  else
444  out << std::setw(3) << '-';
445  }
446  out << '\n';
447  }
448 }
449 
450 } // end of namespace collision_detection
void getAllEntryNames(std::vector< std::string > &names) const
Get all the names known to the collision matrix.
void clear()
Clear the allowed collision matrix.
void setEntry(const std::string &name1, const std::string &name2, bool allowed)
Set an entry corresponding to a pair of elements.
bool getEntry(const std::string &name1, const std::string &name2, AllowedCollision::Type &allowed_collision_type) const
Get the type of the allowed collision between two elements. Return true if the entry is included in t...
bool getAllowedCollision(const std::string &name1, const std::string &name2, DecideContactFn &fn) const
Get the allowed collision predicate between two elements. Return true if a predicate for entry is inc...
void print(std::ostream &out) const
Print the allowed collision matrix.
void setDefaultEntry(const std::string &name, bool allowed)
Set the default value for entries that include name but are not set explicitly with setEntry().
void removeEntry(const std::string &name1, const std::string &name2)
Remove an entry corresponding to a pair of elements. Nothing happens if the pair does not exist in th...
bool getDefaultEntry(const std::string &name, AllowedCollision::Type &allowed_collision) const
Get the type of the allowed collision to be considered by default for an element. Return true if a de...
bool hasEntry(const std::string &name) const
Check if the allowed collision matrix has an entry at all for an element. Returns true if the element...
void getMessage(moveit_msgs::msg::AllowedCollisionMatrix &msg) const
Get the allowed collision matrix as a message.
@ CONDITIONAL
The collision is allowed depending on a predicate evaluated on the produced contact....
@ NEVER
Collisions between the pair of bodies is never ok, i.e., if two bodies are in contact in a particular...
@ ALWAYS
Collisions between a particular pair of bodies does not imply that the robot configuration is in coll...
std::function< bool(collision_detection::Contact &)> DecideContactFn
Signature of predicate that decides whether a contact is allowed or not (when AllowedCollision::Type ...
name
Definition: setup.py:7
Definition of a contact point.