collision_matrix.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Ioan Sucan, E. Gil Jones */
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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Jul 24 2017 02:20:43