23 template <
class ContainerAllocator>
30 template <
class ContainerAllocator>
35 #include <mrpt/version.h> 47 #include <mrpt/version.h> 49 #if MRPT_VERSION < 0x199 66 using mrpt::config::CConfigFile;
82 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS 83 int8_t lut_cellmrpt2ros[0xFF];
84 int8_t* lut_cellmrpt2rosPtr;
87 int8_t lut_cellmrpt2ros[0xFFFF];
91 int8_t lut_cellros2mrpt[0xFF];
104 static MapHdl* instance();
106 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS 107 const int8_t cellMrpt2Ros(
int i) {
return lut_cellmrpt2rosPtr[i]; }
121 static const bool loadMap(
123 const std::string& _map_file =
"map.simplemap",
124 const std::string& _section_name =
"metricMap",
bool _debug =
false);
the map class is implemented as singeleton use map::instance ()->ros2mrpt ...
bool convert(const COccupancyGridMap2D &src, nav_msgs::OccupancyGrid &msg)
int8_t * lut_cellros2mrptPtr
OccupancyGrid_< std::allocator< void > > OccupancyGrid
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
int8_t * lut_cellmrpt2rosPtr
const int8_t cellRos2Mrpt(int i)
static MapHdl * instance_
const int16_t cellMrpt2Ros(int i)