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_msgs/AllowedCollisionMatrix.h>
00042 #include <boost/function.hpp>
00043 #include <iostream>
00044 #include <vector>
00045 #include <string>
00046 #include <map>
00047 
00048 namespace collision_detection
00049 {
00050 
00052   namespace AllowedCollision
00053   {
00054     enum Type
00055     {
00058       NEVER,
00059 
00062       ALWAYS,
00063 
00067       CONDITIONAL
00068     };
00069   }
00070 
00072   typedef boost::function<bool(collision_detection::Contact&)> DecideContactFn;
00073 
00077   class AllowedCollisionMatrix
00078   {
00079   public:
00080 
00081     AllowedCollisionMatrix();
00082 
00087     AllowedCollisionMatrix(const std::vector<std::string>& names, bool allowed = false);
00088 
00090     AllowedCollisionMatrix(const moveit_msgs::AllowedCollisionMatrix &msg);
00091 
00093     AllowedCollisionMatrix(const AllowedCollisionMatrix& acm);
00094 
00100     bool getEntry(const std::string& name1, const std::string& name2, AllowedCollision::Type& allowed_collision_type) const;
00101 
00107     bool getEntry(const std::string& name1, const std::string& name2, DecideContactFn& fn) const;
00108 
00111     bool hasEntry(const std::string& name) const;
00112 
00116     bool hasEntry(const std::string& name1, const std::string &name2) const;
00117 
00121     void removeEntry(const std::string& name1, const std::string &name2);
00122 
00125     void removeEntry(const std::string& name);
00126 
00133     void setEntry(const std::string& name1, const std::string& name2, bool allowed);
00134 
00139     void setEntry(const std::string& name1, const std::string& name2, const DecideContactFn &fn);
00140 
00147     void setEntry(const std::string& name, bool allowed);
00148 
00156     void setEntry(const std::string& name, const std::vector<std::string>& other_names, bool allowed);
00157 
00164     void setEntry(const std::vector<std::string> &names1, const std::vector<std::string> &names2, bool allowed);
00165 
00170     void setEntry(bool allowed);
00171 
00173     void getAllEntryNames(std::vector<std::string>& names) const;
00174 
00176     void getMessage(moveit_msgs::AllowedCollisionMatrix &msg) const;
00177 
00179     void clear();
00180 
00182     std::size_t getSize() const
00183     {
00184       return entries_.size();
00185     }
00186 
00193     void setDefaultEntry(const std::string &name, bool allowed);
00194 
00200     void setDefaultEntry(const std::string &name, const DecideContactFn &fn);
00201 
00206     bool getDefaultEntry(const std::string &name, AllowedCollision::Type& allowed_collision) const;
00207 
00212     bool getDefaultEntry(const std::string &name, DecideContactFn &fn) const;
00213 
00222     bool getAllowedCollision(const std::string& name1, const std::string& name2, DecideContactFn &fn) const;
00223 
00231     bool getAllowedCollision(const std::string& name1, const std::string& name2, AllowedCollision::Type& allowed_collision) const;
00232 
00234     void print(std::ostream& out) const;
00235 
00236   private:
00237 
00238     std::map<std::string, std::map<std::string, AllowedCollision::Type> > entries_;
00239     std::map<std::string, std::map<std::string, DecideContactFn> >        allowed_contacts_;
00240 
00241     std::map<std::string, AllowedCollision::Type>                         default_entries_;
00242     std::map<std::string, DecideContactFn>                                default_allowed_contacts_;
00243 
00244   };
00245 
00246   typedef boost::shared_ptr<AllowedCollisionMatrix> AllowedCollisionMatrixPtr;
00247   typedef boost::shared_ptr<const AllowedCollisionMatrix> AllowedCollisionMatrixConstPtr;
00248 }
00249 
00250 #endif


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Aug 27 2015 13:58:52