Go to the documentation of this file.
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>;
75 throw std::runtime_error(
"Costmap3dLayerSpawner: class not found");
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
static ClassList classes_
Costmap3dLayerBase::Ptr spawn() const
static Costmap3dLayerBase::Ptr loadClass(const std::string &name)
static void registerClass(const std::string &name, Costmap3dLayerSpawnerBase::Ptr spawner)
std::map< std::string, Costmap3dLayerSpawnerBase::Ptr > ClassList
virtual Costmap3dLayerBase::Ptr spawn() const =0
std::shared_ptr< Costmap3dLayerSpawnerBase > Ptr
std::shared_ptr< Costmap3dLayerBase > Ptr
costmap_cspace
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:10