1 #ifndef MRPT_BRIDGE_MAP_H 2 #define MRPT_BRIDGE_MAP_H 15 template <
class ContainerAllocator>
22 template <
class ContainerAllocator>
27 #include <mrpt/version.h> 32 class COccupancyGridMap2D;
33 class CMultiMetricMap;
36 using mrpt::maps::COccupancyGridMap2D;
37 using mrpt::maps::CMultiMetricMap;
39 #include <mrpt/version.h> 41 #if MRPT_VERSION<0x199 49 using mrpt::utils::CConfigFile;
58 using mrpt::config::CConfigFile;
74 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS 75 int8_t lut_cellmrpt2ros[0xFF];
76 int8_t* lut_cellmrpt2rosPtr;
79 int8_t lut_cellmrpt2ros[0xFFFF];
83 int8_t lut_cellros2mrpt[0xFF];
98 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS 99 const int8_t cellMrpt2Ros(
int i) {
return lut_cellmrpt2rosPtr[i]; }
113 static const bool loadMap(
114 CMultiMetricMap& _metric_map,
115 const CConfigFile& _config_file,
116 const std::string& _map_file =
"map.simplemap",
117 const std::string& _section_name =
"metricMap",
bool _debug =
false);
151 #endif // MRPT_BRIDGE_MAP_H 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)