37 #ifndef MOVEIT_COLLISION_DETECTION_COLLISION_MATRIX_ 38 #define MOVEIT_COLLISION_DETECTION_COLLISION_MATRIX_ 42 #include <moveit_msgs/AllowedCollisionMatrix.h> 43 #include <boost/function.hpp> 52 namespace AllowedCollision
104 bool getEntry(
const std::string& name1,
const std::string& name2,
114 bool getEntry(
const std::string& name1,
const std::string& name2, DecideContactFn& fn)
const;
119 bool hasEntry(
const std::string& name)
const;
125 bool hasEntry(
const std::string& name1,
const std::string& name2)
const;
131 void removeEntry(
const std::string& name1,
const std::string& name2);
135 void removeEntry(
const std::string& name);
144 void setEntry(
const std::string& name1,
const std::string& name2,
bool allowed);
152 void setEntry(
const std::string& name1,
const std::string& name2,
const DecideContactFn& fn);
162 void setEntry(
const std::string& name,
bool allowed);
172 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);
188 void setEntry(
bool allowed);
191 void getAllEntryNames(std::vector<std::string>& names)
const;
194 void getMessage(moveit_msgs::AllowedCollisionMatrix& msg)
const;
202 return entries_.size();
215 void setDefaultEntry(
const std::string& name,
bool allowed);
225 void setDefaultEntry(
const std::string& name,
const DecideContactFn& fn);
240 bool getDefaultEntry(
const std::string& name, DecideContactFn& fn)
const;
255 bool getAllowedCollision(
const std::string& name1,
const std::string& name2, DecideContactFn& fn)
const;
267 bool getAllowedCollision(
const std::string& name1,
const std::string& name2,
271 void print(std::ostream& out)
const;
274 std::map<std::string, std::map<std::string, AllowedCollision::Type> >
entries_;
std::map< std::string, std::map< std::string, AllowedCollision::Type > > entries_
Collisions between the pair of bodies is never ok, i.e., if two bodies are in contact in a particular...
MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix)
boost::function< bool(collision_detection::Contact &)> DecideContactFn
Signature of predicate that decides whether a contact is allowed or not (when AllowedCollision::Type ...
std::map< std::string, AllowedCollision::Type > default_entries_
Generic interface to collision detection.
std::size_t getSize() const
Get the size of the allowed collision matrix (number of specified entries)
std::map< std::string, DecideContactFn > default_allowed_contacts_
The collision is allowed depending on a predicate evaluated on the produced contact. If the predicate returns true, this particular contact is deemed ok (or allowed), i.e., the contact does not imply that the two bodies are in collision.
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
std::map< std::string, std::map< std::string, DecideContactFn > > allowed_contacts_
Collisions between a particular pair of bodies does not imply that the robot configuration is in coll...
void print(PropagationDistanceField &pdf, int numX, int numY, int numZ)