41 #include <moveit_msgs/msg/allowed_collision_matrix.hpp>
50 namespace AllowedCollision
107 bool getEntry(
const std::string& name1,
const std::string& name2,
128 bool hasEntry(
const std::string& name1,
const std::string& name2)
const;
134 void removeEntry(
const std::string& name1,
const std::string& name2);
146 void setEntry(
const std::string& name1,
const std::string& name2,
bool allowed);
173 void setEntry(
const std::string&
name,
const std::vector<std::string>& other_names,
bool allowed);
181 void setEntry(
const std::vector<std::string>& names1,
const std::vector<std::string>& names2,
bool allowed);
193 void getMessage(moveit_msgs::msg::AllowedCollisionMatrix& msg)
const;
201 return entries_.size();
247 void print(std::ostream& out)
const;
250 bool getDefaultEntry(
const std::string& name1,
const std::string& name2,
253 std::map<std::string, std::map<std::string, AllowedCollision::Type> > entries_;
254 std::map<std::string, std::map<std::string, DecideContactFn> > allowed_contacts_;
256 std::map<std::string, AllowedCollision::Type> default_entries_;
257 std::map<std::string, DecideContactFn> default_allowed_contacts_;
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
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...
std::size_t getSize() const
Get the size of the allowed collision matrix (number of specified entries)
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...
AllowedCollisionMatrix & operator=(const AllowedCollisionMatrix &)=default
Copy assignment.
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.
AllowedCollisionMatrix(const AllowedCollisionMatrix &acm)=default
Copy constructor.
@ 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...
MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix)
std::function< bool(collision_detection::Contact &)> DecideContactFn
Signature of predicate that decides whether a contact is allowed or not (when AllowedCollision::Type ...