Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef MOVEIT_COLLISION_DETECTION_COLLISION_MATRIX_
00038 #define MOVEIT_COLLISION_DETECTION_COLLISION_MATRIX_
00039
00040 #include <moveit/collision_detection/collision_common.h>
00041 #include <moveit/macros/class_forward.h>
00042 #include <moveit_msgs/AllowedCollisionMatrix.h>
00043 #include <boost/function.hpp>
00044 #include <iostream>
00045 #include <vector>
00046 #include <string>
00047 #include <map>
00048
00049 namespace collision_detection
00050 {
00052 namespace AllowedCollision
00053 {
00054 enum Type
00055 {
00058 NEVER,
00059
00062 ALWAYS,
00063
00067 CONDITIONAL
00068 };
00069 }
00070
00073 typedef boost::function<bool(collision_detection::Contact&)> DecideContactFn;
00074
00075 MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix);
00076
00081 class AllowedCollisionMatrix
00082 {
00083 public:
00084 AllowedCollisionMatrix();
00085
00090 AllowedCollisionMatrix(const std::vector<std::string>& names, bool allowed = false);
00091
00093 AllowedCollisionMatrix(const moveit_msgs::AllowedCollisionMatrix& msg);
00094
00096 AllowedCollisionMatrix(const AllowedCollisionMatrix& acm);
00097
00104 bool getEntry(const std::string& name1, const std::string& name2,
00105 AllowedCollision::Type& allowed_collision_type) const;
00106
00114 bool getEntry(const std::string& name1, const std::string& name2, DecideContactFn& fn) const;
00115
00119 bool hasEntry(const std::string& name) const;
00120
00125 bool hasEntry(const std::string& name1, const std::string& name2) const;
00126
00131 void removeEntry(const std::string& name1, const std::string& name2);
00132
00135 void removeEntry(const std::string& name);
00136
00144 void setEntry(const std::string& name1, const std::string& name2, bool allowed);
00145
00152 void setEntry(const std::string& name1, const std::string& name2, const DecideContactFn& fn);
00153
00162 void setEntry(const std::string& name, bool allowed);
00163
00172 void setEntry(const std::string& name, const std::vector<std::string>& other_names, bool allowed);
00173
00181 void setEntry(const std::vector<std::string>& names1, const std::vector<std::string>& names2, bool allowed);
00182
00188 void setEntry(bool allowed);
00189
00191 void getAllEntryNames(std::vector<std::string>& names) const;
00192
00194 void getMessage(moveit_msgs::AllowedCollisionMatrix& msg) const;
00195
00197 void clear();
00198
00200 std::size_t getSize() const
00201 {
00202 return entries_.size();
00203 }
00204
00215 void setDefaultEntry(const std::string& name, bool allowed);
00216
00225 void setDefaultEntry(const std::string& name, const DecideContactFn& fn);
00226
00232 bool getDefaultEntry(const std::string& name, AllowedCollision::Type& allowed_collision) const;
00233
00240 bool getDefaultEntry(const std::string& name, DecideContactFn& fn) const;
00241
00255 bool getAllowedCollision(const std::string& name1, const std::string& name2, DecideContactFn& fn) const;
00256
00267 bool getAllowedCollision(const std::string& name1, const std::string& name2,
00268 AllowedCollision::Type& allowed_collision) const;
00269
00271 void print(std::ostream& out) const;
00272
00273 private:
00274 std::map<std::string, std::map<std::string, AllowedCollision::Type> > entries_;
00275 std::map<std::string, std::map<std::string, DecideContactFn> > allowed_contacts_;
00276
00277 std::map<std::string, AllowedCollision::Type> default_entries_;
00278 std::map<std::string, DecideContactFn> default_allowed_contacts_;
00279 };
00280 }
00281
00282 #endif