12 #include <nav_msgs/OccupancyGrid.h> 
   16 #include <mrpt/random.h> 
   18 #if MRPT_VERSION >= 0x199 
   19 #include <mrpt/config/CConfigFile.h> 
   20 #include <mrpt/io/CFileGZInputStream.h> 
   21 using namespace mrpt::config;
 
   22 using namespace mrpt::io;
 
   24 #include <mrpt/utils/CConfigFile.h> 
   25 #include <mrpt/utils/CFileGZInputStream.h> 
   29 #include <mrpt/system/filesystem.h>   
   30 #include <mrpt/system/string_utils.h>   
   32 #include <mrpt/version.h> 
   33 #include <mrpt/maps/COccupancyGridMap2D.h> 
   34 #include <mrpt/maps/CMultiMetricMap.h> 
   35 #include <mrpt/maps/CSimpleMap.h> 
   36 using mrpt::maps::CLogOddsGridMapLUT;
 
   37 using mrpt::maps::CMultiMetricMap;
 
   38 using mrpt::maps::COccupancyGridMap2D;
 
   39 using mrpt::maps::CSimpleMap;
 
   41 #if MRPT_VERSION >= 0x199 
   42 #include <mrpt/serialization/CArchive.h> 
   45 #ifndef INT8_MAX  // avoid duplicated #define's 
   47 #define INT8_MIN (-INT8_MAX - 1) 
   48 #define INT16_MAX 0x7fff 
   49 #define INT16_MIN (-INT16_MAX - 1) 
   54 MapHdl* MapHdl::instance_ = NULL;
 
   59         CLogOddsGridMapLUT<COccupancyGridMap2D::cellType> table;
 
   60 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS 
   73                 float p = 1.0 - table.l2p(i);
 
   74                 int idx = round(p * 100.);
 
   75                 lut_cellmrpt2rosPtr[i] = idx;
 
   83                 float p = 1.0 - (v / 100.0);
 
   84                 int idx = table.p2l(p);
 
   86                         lut_cellros2mrptPtr[i] = table.p2l(0.5);
 
   88                         lut_cellros2mrptPtr[i] = table.p2l(0.5);
 
   90                         lut_cellros2mrptPtr[i] = idx;
 
   98         if (instance_ == NULL) instance_ = 
new MapHdl();
 
  104         if ((src.info.origin.orientation.x != 0) ||
 
  105                 (src.info.origin.orientation.y != 0) ||
 
  106                 (src.info.origin.orientation.z != 0) ||
 
  107                 (src.info.origin.orientation.w != 1))
 
  109                 std::cerr << 
"Rotated maps are not supported by mrpt!" << std::endl;
 
  112         float xmin = src.info.origin.position.x;
 
  113         float ymin = src.info.origin.position.y;
 
  114         float xmax = xmin + src.info.width * src.info.resolution;
 
  115         float ymax = ymin + src.info.height * src.info.resolution;
 
  118         des.setSize(xmin, xmax, ymin, ymax, src.info.resolution);
 
  125         for (
unsigned int h = 0; h < src.info.height; h++)
 
  127                 COccupancyGridMap2D::cellType* pDes = des.getRow(h);
 
  128                 const int8_t* pSrc = &src.data[h * src.info.width];
 
  129                 for (
unsigned int w = 0; w < src.info.width; w++)
 
  131                         *pDes++ = MapHdl::instance()->cellRos2Mrpt(*pSrc++);
 
  148         des.info.width = src.getSizeX();
 
  149         des.info.height = src.getSizeY();
 
  150         des.info.resolution = src.getResolution();
 
  152         des.info.origin.position.x = src.getXMin();
 
  153         des.info.origin.position.y = src.getYMin();
 
  154         des.info.origin.position.z = 0;
 
  156         des.info.origin.orientation.x = 0;
 
  157         des.info.origin.orientation.y = 0;
 
  158         des.info.origin.orientation.z = 0;
 
  159         des.info.origin.orientation.w = 1;
 
  162         des.data.resize(des.info.width * des.info.height);
 
  163         for (
unsigned int h = 0; h < des.info.height; h++)
 
  165                 const COccupancyGridMap2D::cellType* pSrc = src.getRow(h);
 
  166                 int8_t* pDes = &des.data[h * des.info.width];
 
  167                 for (
unsigned int w = 0; w < des.info.width; w++)
 
  169                         *pDes++ = MapHdl::instance()->cellMrpt2Ros(*pSrc++);
 
  175 const bool MapHdl::loadMap(
 
  176         CMultiMetricMap& _metric_map, 
const CConfigFile& _config_file,
 
  177         const std::string& _map_file, 
const std::string& _section_name, 
bool _debug)
 
  181         TSetOfMetricMapInitializers mapInitializers;
 
  182         mapInitializers.loadFromConfigFile(_config_file, _section_name);
 
  184         CSimpleMap simpleMap;
 
  187         _metric_map.setListOfMaps(mapInitializers);
 
  188         if (_debug) mapInitializers.dumpToConsole();
 
  190 #if MRPT_VERSION >= 0x199 
  191         auto& r = mrpt::random::getRandomGenerator();
 
  193         auto& r = mrpt::random::randomGenerator;
 
  199                         "%s, _map_file.size() = %zu\n", _map_file.c_str(),
 
  202         if (_map_file.size() < 3)
 
  204                 if (_debug) printf(
"No mrpt map file!\n");
 
  209                 ASSERT_(mrpt::system::fileExists(_map_file));
 
  213                         mrpt::system::lowerCase(mrpt::system::extractFileExtension(
 
  216                 if (!mapExt.compare(
"simplemap"))
 
  219                         if (_debug) printf(
"Loading '.simplemap' file...");
 
  220                         CFileGZInputStream 
f(_map_file);
 
  221 #if MRPT_VERSION >= 0x199 
  222                         mrpt::serialization::archiveFrom(
f) >> simpleMap;
 
  229                                 simpleMap.size() > 0,
 
  230                                 "Simplemap was aparently loaded OK, but it is empty!");
 
  233                         if (_debug) printf(
"Building metric map(s) from '.simplemap'...");
 
  234                         _metric_map.loadFromSimpleMap(simpleMap);
 
  235                         if (_debug) printf(
"Ok\n");
 
  237                 else if (!mapExt.compare(
"gridmap"))
 
  240                         if (_debug) printf(
"Loading gridmap from '.gridmap'...");
 
  242 #
if MRPT_VERSION >= 0x199
 
  243                                 _metric_map.countMapsByClass<COccupancyGridMap2D>() == 1,
 
  245                                 _metric_map.m_gridMaps.size() == 1,
 
  247                                 "Error: Trying to load a gridmap into a multi-metric map " 
  248                                 "requires 1 gridmap member.");
 
  249                         CFileGZInputStream fm(_map_file);
 
  250 #if MRPT_VERSION >= 0x199 
  251                         mrpt::serialization::archiveFrom(fm) >>
 
  252                                 (*_metric_map.mapByClass<COccupancyGridMap2D>());
 
  254                         fm >> (*_metric_map.m_gridMaps[0]);
 
  256                         if (_debug) printf(
"Ok\n");
 
  260                         THROW_EXCEPTION(mrpt::format(
 
  261                                 "Map file has unknown extension: '%s'", mapExt.c_str()));