Go to the documentation of this file.
41 #include <moveit_msgs/AllowedCollisionMatrix.h>
42 #include <boost/function.hpp>
51 namespace AllowedCollision
80 class AllowedCollisionMatrix
102 bool getEntry(
const std::string& name1,
const std::string& name2,
123 bool hasEntry(
const std::string& name1,
const std::string& name2)
const;
129 void removeEntry(
const std::string& name1,
const std::string& name2);
141 void setEntry(
const std::string& name1,
const std::string& name2,
bool allowed);
159 void setEntry(
const std::string& name,
bool allowed);
168 void setEntry(
const std::string& name,
const std::vector<std::string>& other_names,
bool allowed);
176 void setEntry(
const std::vector<std::string>& names1,
const std::vector<std::string>& names2,
bool allowed);
188 void getMessage(moveit_msgs::AllowedCollisionMatrix& msg)
const;
242 void print(std::ostream& out)
const;
245 bool getDefaultEntry(
const std::string& name1,
const std::string& name2,
248 std::map<std::string, std::map<std::string, AllowedCollision::Type> >
entries_;
249 std::map<std::string, std::map<std::string, DecideContactFn> >
allowed_contacts_;
void setDefaultEntry(const std::string &name, bool allowed)
Set the default value for entries that include name but are not set explicity with setEntry().
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...
std::map< std::string, std::map< std::string, AllowedCollision::Type > > entries_
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...
std::size_t getSize() const
Get the size of the allowed collision matrix (number of specified entries)
MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix)
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...
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...
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...
@ ALWAYS
Collisions between a particular pair of bodies does not imply that the robot configuration is in coll...
void getMessage(moveit_msgs::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....
void print(std::ostream &out) const
Print the allowed collision matrix.
void clear()
Clear the allowed collision matrix.
std::map< std::string, std::map< std::string, DecideContactFn > > allowed_contacts_
std::map< std::string, AllowedCollision::Type > default_entries_
std::map< std::string, DecideContactFn > default_allowed_contacts_
void getAllEntryNames(std::vector< std::string > &names) const
Get all the names known to the collision matrix.
boost::function< bool(collision_detection::Contact &)> DecideContactFn
Signature of predicate that decides whether a contact is allowed or not (when AllowedCollision::Type ...
@ NEVER
Collisions between the pair of bodies is never ok, i.e., if two bodies are in contact in a particular...
void setEntry(const std::string &name1, const std::string &name2, bool allowed)
Set an entry corresponding to a pair of elements.
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:14