world.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, 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, Acorn Pooley, Sachin Chitta */
00036 
00037 #ifndef MOVEIT_COLLISION_DETECTION_WORLD_
00038 #define MOVEIT_COLLISION_DETECTION_WORLD_
00039 
00040 #include <moveit/macros/class_forward.h>
00041 
00042 #include <string>
00043 #include <vector>
00044 #include <map>
00045 #include <boost/function.hpp>
00046 #include <Eigen/Geometry>
00047 #include <eigen_stl_containers/eigen_stl_vector_container.h>
00048 #include <geometric_shapes/shapes.h>
00049 
00050 namespace collision_detection
00051 {
00052 MOVEIT_CLASS_FORWARD(World);
00053 
00055 class World
00056 {
00057 public:
00059   World();
00060 
00064   World(const World& other);
00065 
00066   ~World();
00067 
00068   /**********************************************************************/
00069   /* Collision Bodies                                                   */
00070   /**********************************************************************/
00071 
00072   MOVEIT_CLASS_FORWARD(Object);
00073 
00075   struct Object
00076   {
00077     Object(const std::string& id) : id_(id)
00078     {
00079     }
00080 
00081     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00082 
00084     std::string id_;
00085 
00097     std::vector<shapes::ShapeConstPtr> shapes_;
00098 
00102     EigenSTL::vector_Affine3d shape_poses_;
00103   };
00104 
00106   std::vector<std::string> getObjectIds() const;
00107 
00109   ObjectConstPtr getObject(const std::string& id) const;
00110 
00112   typedef std::map<std::string, ObjectPtr>::const_iterator const_iterator;
00114   const_iterator begin() const
00115   {
00116     return objects_.begin();
00117   }
00119   const_iterator end() const
00120   {
00121     return objects_.end();
00122   }
00124   std::size_t size() const
00125   {
00126     return objects_.size();
00127   }
00129   const_iterator find(const std::string& id) const
00130   {
00131     return objects_.find(id);
00132   }
00133 
00135   bool hasObject(const std::string& id) const;
00136 
00142   void addToObject(const std::string& id, const std::vector<shapes::ShapeConstPtr>& shapes,
00143                    const EigenSTL::vector_Affine3d& poses);
00144 
00149   void addToObject(const std::string& id, const shapes::ShapeConstPtr& shape, const Eigen::Affine3d& pose);
00150 
00153   bool moveShapeInObject(const std::string& id, const shapes::ShapeConstPtr& shape, const Eigen::Affine3d& pose);
00154 
00161   bool removeShapeFromObject(const std::string& id, const shapes::ShapeConstPtr& shape);
00162 
00167   bool removeObject(const std::string& id);
00168 
00172   void clearObjects();
00173 
00174   enum ActionBits
00175   {
00176     UNINITIALIZED = 0,
00177     CREATE = 1,        
00178     DESTROY = 2,       
00179     MOVE_SHAPE = 4,    
00180     ADD_SHAPE = 8,     
00181     REMOVE_SHAPE = 16, 
00182   };
00183 
00187   class Action
00188   {
00189   public:
00190     Action() : action_(UNINITIALIZED)
00191     {
00192     }
00193     Action(int v) : action_(v)
00194     {
00195     }
00196     operator ActionBits() const
00197     {
00198       return ActionBits(action_);
00199     }
00200 
00201   private:
00202     int action_;
00203   };
00204 
00205 private:
00206   class Observer;
00207 
00208 public:
00209   class ObserverHandle
00210   {
00211   public:
00212     ObserverHandle() : observer_(NULL)
00213     {
00214     }
00215 
00216   private:
00217     ObserverHandle(const Observer* o) : observer_(o)
00218     {
00219     }
00220     const Observer* observer_;
00221     friend class World;
00222   };
00223 
00224   typedef boost::function<void(const ObjectConstPtr&, Action)> ObserverCallbackFn;
00225 
00230   ObserverHandle addObserver(const ObserverCallbackFn& callback);
00231 
00233   void removeObserver(const ObserverHandle observer_handle);
00234 
00237   void notifyObserverAllObjects(const ObserverHandle observer_handle, Action action) const;
00238 
00239 private:
00241   void notify(const ObjectConstPtr&, Action);
00242 
00244   void notifyAll(Action action);
00245 
00249   void ensureUnique(ObjectPtr& obj);
00250 
00251   /* Add a shape with no checking */
00252   virtual void addToObjectInternal(const ObjectPtr& obj, const shapes::ShapeConstPtr& shape,
00253                                    const Eigen::Affine3d& pose);
00254 
00256   std::map<std::string, ObjectPtr> objects_;
00257 
00258   /* observers to call when something changes */
00259   class Observer
00260   {
00261   public:
00262     Observer(const ObserverCallbackFn& callback) : callback_(callback)
00263     {
00264     }
00265     ObserverCallbackFn callback_;
00266   };
00267   std::vector<Observer*> observers_;
00268 };
00269 }
00270 
00271 #endif


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