collision_matrix.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan, E. Gil Jones */
36 
37 #ifndef MOVEIT_COLLISION_DETECTION_COLLISION_MATRIX_
38 #define MOVEIT_COLLISION_DETECTION_COLLISION_MATRIX_
39 
42 #include <moveit_msgs/AllowedCollisionMatrix.h>
43 #include <boost/function.hpp>
44 #include <iostream>
45 #include <vector>
46 #include <string>
47 #include <map>
48 
49 namespace collision_detection
50 {
52 namespace AllowedCollision
53 {
54 enum Type
55 {
59 
63 
68 };
69 }
70 
73 typedef boost::function<bool(collision_detection::Contact&)> DecideContactFn;
74 
76 
82 {
83 public:
85 
90  AllowedCollisionMatrix(const std::vector<std::string>& names, bool allowed = false);
91 
93  AllowedCollisionMatrix(const moveit_msgs::AllowedCollisionMatrix& msg);
94 
97 
104  bool getEntry(const std::string& name1, const std::string& name2,
105  AllowedCollision::Type& allowed_collision_type) const;
106 
114  bool getEntry(const std::string& name1, const std::string& name2, DecideContactFn& fn) const;
115 
119  bool hasEntry(const std::string& name) const;
120 
125  bool hasEntry(const std::string& name1, const std::string& name2) const;
126 
131  void removeEntry(const std::string& name1, const std::string& name2);
132 
135  void removeEntry(const std::string& name);
136 
144  void setEntry(const std::string& name1, const std::string& name2, bool allowed);
145 
152  void setEntry(const std::string& name1, const std::string& name2, const DecideContactFn& fn);
153 
162  void setEntry(const std::string& name, bool allowed);
163 
172  void setEntry(const std::string& name, const std::vector<std::string>& other_names, bool allowed);
173 
181  void setEntry(const std::vector<std::string>& names1, const std::vector<std::string>& names2, bool allowed);
182 
188  void setEntry(bool allowed);
189 
191  void getAllEntryNames(std::vector<std::string>& names) const;
192 
194  void getMessage(moveit_msgs::AllowedCollisionMatrix& msg) const;
195 
197  void clear();
198 
200  std::size_t getSize() const
201  {
202  return entries_.size();
203  }
204 
215  void setDefaultEntry(const std::string& name, bool allowed);
216 
225  void setDefaultEntry(const std::string& name, const DecideContactFn& fn);
226 
232  bool getDefaultEntry(const std::string& name, AllowedCollision::Type& allowed_collision) const;
233 
240  bool getDefaultEntry(const std::string& name, DecideContactFn& fn) const;
241 
255  bool getAllowedCollision(const std::string& name1, const std::string& name2, DecideContactFn& fn) const;
256 
267  bool getAllowedCollision(const std::string& name1, const std::string& name2,
268  AllowedCollision::Type& allowed_collision) const;
269 
271  void print(std::ostream& out) const;
272 
273 private:
274  std::map<std::string, std::map<std::string, AllowedCollision::Type> > entries_;
275  std::map<std::string, std::map<std::string, DecideContactFn> > allowed_contacts_;
276 
277  std::map<std::string, AllowedCollision::Type> default_entries_;
278  std::map<std::string, DecideContactFn> default_allowed_contacts_;
279 };
280 }
281 
282 #endif
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)


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Oct 18 2020 13:16:33