30 #ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_CLASS_LOADER_H 31 #define COSTMAP_CSPACE_COSTMAP_3D_LAYER_CLASS_LOADER_H 39 #include <geometry_msgs/PolygonStamped.h> 40 #include <nav_msgs/OccupancyGrid.h> 41 #include <costmap_cspace_msgs/CSpace3D.h> 42 #include <costmap_cspace_msgs/CSpace3DUpdate.h> 52 using Ptr = std::shared_ptr<Costmap3dLayerSpawnerBase>;
67 using ClassList = std::map<std::string, Costmap3dLayerSpawnerBase::Ptr>;
73 if (classes_.find(name) == classes_.end())
75 throw std::runtime_error(
"Costmap3dLayerSpawner: class not found");
77 return classes_[name]->spawn();
81 classes_[name] = spawner;
84 #define COSTMAP_3D_LAYER_CLASS_LOADER_ENABLE() \ 85 costmap_cspace::Costmap3dLayerClassLoader::ClassList \ 86 costmap_cspace::Costmap3dLayerClassLoader::classes_; 88 #define COSTMAP_3D_LAYER_CLASS_LOADER_REGISTER(name, klass, id) \ 91 struct ClassLoaderRegister##id \ 93 ClassLoaderRegister##id() \ 95 costmap_cspace::Costmap3dLayerClassLoader::registerClass( \ 97 costmap_cspace::Costmap3dLayerSpawnerBase::Ptr( \ 98 new costmap_cspace::Costmap3dLayerSpawner<klass>)); \ 101 static ClassLoaderRegister##id g_register_class_##id; \ 106 #endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_CLASS_LOADER_H virtual Costmap3dLayerBase::Ptr spawn() const =0
Costmap3dLayerBase::Ptr spawn() const
std::map< std::string, Costmap3dLayerSpawnerBase::Ptr > ClassList
std::shared_ptr< Costmap3dLayerBase > Ptr
static ClassList classes_
static void registerClass(const std::string &name, Costmap3dLayerSpawnerBase::Ptr spawner)
static Costmap3dLayerBase::Ptr loadClass(const std::string &name)
std::shared_ptr< Costmap3dLayerSpawnerBase > Ptr