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 #ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_CLASS_LOADER_H
00031 #define COSTMAP_CSPACE_COSTMAP_3D_LAYER_CLASS_LOADER_H
00032
00033 #include <ros/ros.h>
00034
00035 #include <geometry_msgs/PolygonStamped.h>
00036 #include <nav_msgs/OccupancyGrid.h>
00037 #include <costmap_cspace_msgs/CSpace3D.h>
00038 #include <costmap_cspace_msgs/CSpace3DUpdate.h>
00039
00040 #include <costmap_cspace/cspace3_cache.h>
00041 #include <costmap_cspace/polygon.h>
00042
00043 #include <string>
00044 #include <map>
00045
00046 namespace costmap_cspace
00047 {
00048 class Costmap3dLayerSpawnerBase
00049 {
00050 public:
00051 using Ptr = std::shared_ptr<Costmap3dLayerSpawnerBase>;
00052 virtual Costmap3dLayerBase::Ptr spawn() const = 0;
00053 };
00054 template <typename T>
00055 class Costmap3dLayerSpawner : public Costmap3dLayerSpawnerBase
00056 {
00057 public:
00058 Costmap3dLayerBase::Ptr spawn() const
00059 {
00060 return Costmap3dLayerBase::Ptr(new T);
00061 }
00062 };
00063 class Costmap3dLayerClassLoader
00064 {
00065 protected:
00066 using ClassList = std::map<std::string, Costmap3dLayerSpawnerBase::Ptr>;
00067 static ClassList classes_;
00068
00069 public:
00070 static Costmap3dLayerBase::Ptr loadClass(const std::string& name)
00071 {
00072 if (classes_.find(name) == classes_.end())
00073 {
00074 throw std::runtime_error("Costmap3dLayerSpawner: class not found");
00075 }
00076 return classes_[name]->spawn();
00077 };
00078 static void registerClass(const std::string& name, Costmap3dLayerSpawnerBase::Ptr spawner)
00079 {
00080 classes_[name] = spawner;
00081 };
00082 };
00083 #define COSTMAP_3D_LAYER_CLASS_LOADER_ENABLE() \
00084 costmap_cspace::Costmap3dLayerClassLoader::ClassList \
00085 costmap_cspace::Costmap3dLayerClassLoader::classes_;
00086
00087 #define COSTMAP_3D_LAYER_CLASS_LOADER_REGISTER(name, klass, id) \
00088 namespace \
00089 { \
00090 struct ClassLoaderRegister##id \
00091 { \
00092 ClassLoaderRegister##id() \
00093 { \
00094 costmap_cspace::Costmap3dLayerClassLoader::registerClass( \
00095 name, \
00096 costmap_cspace::Costmap3dLayerSpawnerBase::Ptr( \
00097 new costmap_cspace::Costmap3dLayerSpawner<klass>)); \
00098 } \
00099 }; \
00100 static ClassLoaderRegister##id g_register_class_##id; \
00101 } // namespace
00102
00103 }
00104
00105 #endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_CLASS_LOADER_H