38 #include <rclcpp/logger.hpp>
39 #include <rclcpp/logging.hpp>
46 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_collision_detection.collision_matrix");
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);
62 for (
const std::string&
name : srdf.getNoDefaultCollisionLinks())
65 for (
auto const& collision : srdf.getEnabledCollisionPairs())
66 setEntry(collision.link1_, collision.link2_,
false);
68 for (
auto const& collision : srdf.getDisabledCollisionPairs())
69 setEntry(collision.link1_, collision.link2_,
true);
74 if (msg.entry_names.size() != msg.entry_values.size() ||
75 msg.default_entry_names.size() != msg.default_entry_values.size())
77 RCLCPP_ERROR(LOGGER,
"The number of links does not match the number of entries in AllowedCollisionMatrix message");
80 for (std::size_t i = 0; i < msg.default_entry_names.size(); ++i)
82 setDefaultEntry(msg.default_entry_names[i], msg.default_entry_values[i]);
85 for (std::size_t i = 0; i < msg.entry_names.size(); ++i)
87 if (msg.entry_values[i].enabled.size() != msg.entry_names.size())
89 RCLCPP_ERROR(LOGGER,
"Number of entries is incorrect for link '%s' in AllowedCollisionMatrix message",
90 msg.entry_names[i].c_str());
93 for (std::size_t j = i + 1; j < msg.entry_values[i].enabled.size(); ++j)
96 if (!
getDefaultEntry(msg.entry_names[i], msg.entry_names[j], allowed_default))
100 if (allowed_entry != allowed_default)
101 setEntry(msg.entry_names[i], msg.entry_names[j], allowed_entry);
108 const auto it1 = allowed_contacts_.find(name1);
109 if (it1 == allowed_contacts_.end())
111 const auto it2 = it1->second.find(name2);
112 if (it2 == it1->second.end())
121 const auto it1 = entries_.find(name1);
122 if (it1 == entries_.end())
124 auto it2 = it1->second.find(name2);
125 if (it2 == it1->second.end())
127 allowed_collision = it2->second;
133 return entries_.find(
name) != entries_.end();
138 const auto it1 = entries_.find(name1);
139 if (it1 == entries_.end())
141 const auto it2 = it1->second.find(name2);
142 return it2 != it1->second.end();
148 entries_[name1][name2] = entries_[name2][name1] = v;
151 auto it = allowed_contacts_.find(name1);
152 if (it != allowed_contacts_.end())
154 auto jt = it->second.find(name2);
155 if (jt != it->second.end())
156 it->second.erase(jt);
158 it = allowed_contacts_.find(name2);
159 if (it != allowed_contacts_.end())
161 auto jt = it->second.find(name1);
162 if (jt != it->second.end())
163 it->second.erase(jt);
170 allowed_contacts_[name1][name2] = allowed_contacts_[name2][name1] = fn;
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);
185 auto jt = entries_.find(name1);
186 if (jt != entries_.end())
188 auto it = jt->second.find(name2);
189 if (it != jt->second.end())
190 jt->second.erase(it);
192 jt = entries_.find(name2);
193 if (jt != entries_.end())
195 auto it = jt->second.find(name1);
196 if (it != jt->second.end())
197 jt->second.erase(it);
200 auto it = allowed_contacts_.find(name1);
201 if (it != allowed_contacts_.end())
203 auto jt = it->second.find(name2);
204 if (jt != it->second.end())
205 it->second.erase(jt);
207 it = allowed_contacts_.find(name2);
208 if (it != allowed_contacts_.end())
210 auto jt = it->second.find(name1);
211 if (jt != it->second.end())
212 it->second.erase(jt);
219 for (
const auto& other_name : other_names)
220 if (other_name !=
name)
227 for (
const auto& name1 : names1)
233 std::string last =
name;
234 for (
auto& entry : entries_)
235 if (
name != entry.first && last != entry.first)
245 for (
auto& entry : entries_)
246 for (
auto& it2 : entry.second)
253 default_entries_[
name] = v;
254 default_allowed_contacts_.erase(
name);
260 default_allowed_contacts_[
name] = fn;
265 auto it = default_entries_.find(
name);
266 if (it == default_entries_.end())
268 allowed_collision = it->second;
274 auto it = default_allowed_contacts_.find(
name);
275 if (it == default_allowed_contacts_.end())
283 return f1(contact) && f2(contact);
289 const bool found =
getEntry(name1, name2, fn);
295 if (found1 && !found2)
297 else if (!found1 && found2)
299 else if (found1 && found2)
300 fn = [fn1, fn2](
Contact& contact) {
return andDecideContact(fn1, fn2, contact); };
313 if (!found1 && !found2)
315 else if (found1 && !found2)
316 allowed_collision = t1;
317 else if (!found1 && found2)
318 allowed_collision = t2;
319 else if (found1 && found2)
340 allowed_contacts_.clear();
341 default_entries_.clear();
342 default_allowed_contacts_.clear();
348 for (
const auto& entry : entries_)
349 names.push_back(entry.first);
351 for (
const auto& item : default_entries_)
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);
361 msg.entry_names.clear();
362 msg.entry_values.clear();
363 msg.default_entry_names.clear();
364 msg.default_entry_values.clear();
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);
374 for (std::size_t i = 0; i < msg.entry_names.size(); ++i)
380 msg.default_entry_names.push_back(msg.entry_names[i]);
384 for (std::size_t j = i; j < msg.entry_names.size(); ++j)
395 std::vector<std::string> names;
398 std::size_t spacing = 4;
399 for (
const auto&
name : names)
401 const std::size_t length =
name.length();
402 if (length > spacing)
407 std::size_t number_digits = 2;
408 while (names.size() > pow(10, number_digits) - 1)
412 for (std::size_t j = 0; j < number_digits; ++j)
414 out << std::setw(spacing + number_digits + 8) <<
"";
415 for (std::size_t i = 0; i < names.size(); ++i)
417 std::stringstream ss;
418 ss << std::setw(number_digits) << i;
419 out << std::setw(3) << ss.str().c_str()[j];
424 const char* indicator =
"01?";
425 for (std::size_t i = 0; i < names.size(); ++i)
427 out << std::setw(spacing) << names[i];
428 out << std::setw(number_digits + 1) << i;
433 out << indicator[
type];
438 for (std::size_t j = 0; j < names.size(); ++j)
442 out << std::setw(3) << indicator[
type];
444 out << std::setw(3) <<
'-';
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 ...