#include <ros/ros.h>
#include <geometry_msgs/PolygonStamped.h>
#include <nav_msgs/OccupancyGrid.h>
#include <costmap_cspace_msgs/CSpace3D.h>
#include <costmap_cspace_msgs/CSpace3DUpdate.h>
#include <costmap_cspace/cspace3_cache.h>
#include <costmap_cspace/polygon.h>
#include <string>
#include <map>
Go to the source code of this file.
#define COSTMAP_3D_LAYER_CLASS_LOADER_ENABLE |
( |
| ) |
|
Value:costmap_cspace::Costmap3dLayerClassLoader::ClassList \
costmap_cspace::Costmap3dLayerClassLoader::classes_;
Definition at line 83 of file class_loader.h.
#define COSTMAP_3D_LAYER_CLASS_LOADER_REGISTER |
( |
|
name, |
|
|
|
klass, |
|
|
|
id |
|
) |
| |
Value:namespace \
{ \
struct ClassLoaderRegister##id \
{ \
ClassLoaderRegister##id() \
name, \
} \
}; \
static ClassLoaderRegister##id g_register_class_##id; \
}
static void registerClass(const std::string &name, Costmap3dLayerSpawnerBase::Ptr spawner)
std::shared_ptr< Costmap3dLayerSpawnerBase > Ptr
Definition at line 87 of file class_loader.h.