map.cpp
Go to the documentation of this file.
00001 
00002 #include "mrpt_bridge/map.h"
00003 #include "mrpt_bridge/pose.h"
00004 #include <nav_msgs/OccupancyGrid.h>
00005 #include <ros/console.h>
00006 
00007 // Only include MRPT classes that are really used to avoid slow down compilation
00008 #include <mrpt/random.h>
00009 
00010 #if MRPT_VERSION >= 0x199
00011 #include <mrpt/config/CConfigFile.h>
00012 #include <mrpt/io/CFileGZInputStream.h>
00013 using namespace mrpt::config;
00014 using namespace mrpt::io;
00015 #else
00016 #include <mrpt/utils/CConfigFile.h>
00017 #include <mrpt/utils/CFileGZInputStream.h>
00018 using namespace mrpt::utils;
00019 #endif
00020 
00021 #include <mrpt/system/filesystem.h>  // for fileExists()
00022 #include <mrpt/system/string_utils.h>  // for lowerCase()
00023 
00024 #include <mrpt/version.h>
00025 #include <mrpt/maps/COccupancyGridMap2D.h>
00026 #include <mrpt/maps/CMultiMetricMap.h>
00027 #include <mrpt/maps/CSimpleMap.h>
00028 using mrpt::maps::CLogOddsGridMapLUT;
00029 using mrpt::maps::CMultiMetricMap;
00030 using mrpt::maps::COccupancyGridMap2D;
00031 using mrpt::maps::CSimpleMap;
00032 
00033 #if MRPT_VERSION >= 0x199
00034 #include <mrpt/serialization/CArchive.h>
00035 #endif
00036 
00037 #ifndef INT8_MAX  // avoid duplicated #define's
00038 #define INT8_MAX 0x7f
00039 #define INT8_MIN (-INT8_MAX - 1)
00040 #define INT16_MAX 0x7fff
00041 #define INT16_MIN (-INT16_MAX - 1)
00042 #endif  // INT8_MAX
00043 
00044 namespace mrpt_bridge
00045 {
00046 MapHdl* MapHdl::instance_ = NULL;
00047 
00048 MapHdl::MapHdl()
00049 {
00051         CLogOddsGridMapLUT<COccupancyGridMap2D::cellType> table;
00052 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS
00053         lut_cellmrpt2rosPtr =
00054                 lut_cellmrpt2ros + INT8_MAX + 1;  // center the pointer
00055         lut_cellros2mrptPtr =
00056                 lut_cellros2mrpt + INT8_MAX + 1;  // center the pointer
00057         for (int i = INT8_MIN; i < INT8_MAX; i++)
00058         {
00059 #else
00060         lut_cellmrpt2rosPtr =
00061                 lut_cellmrpt2ros + INT16_MAX + 1;  // center the pointer
00062         for (int i = INT16_MIN; INT16_MIN < INT16_MAX; i++)
00063         {
00064 #endif
00065                 float p = 1.0 - table.l2p(i);
00066                 int idx = round(p * 100.);
00067                 lut_cellmrpt2rosPtr[i] = idx;
00068                 // printf("- cell -> ros = %4i -> %4i, p=%4.3f\n", i, idx, p);
00069         }
00070         for (int i = INT8_MIN; i < INT8_MAX; i++)
00071         {
00072                 float v = i;
00073                 if (v > 100) v = 50;
00074                 if (v < 0) v = 50;
00075                 float p = 1.0 - (v / 100.0);
00076                 int idx = table.p2l(p);
00077                 if (i < 0)
00078                         lut_cellros2mrptPtr[i] = table.p2l(0.5);
00079                 else if (i > 100)
00080                         lut_cellros2mrptPtr[i] = table.p2l(0.5);
00081                 else
00082                         lut_cellros2mrptPtr[i] = idx;
00083                 // printf("- ros -> cell = %4i -> %4i, p=%4.3f\n", i, idx, p);
00084                 fflush(stdout);
00085         }
00086 }
00087 MapHdl::~MapHdl() {}
00088 MapHdl* MapHdl::instance()
00089 {
00090         if (instance_ == NULL) instance_ = new MapHdl();
00091         return instance_;
00092 }
00093 
00094 bool convert(const nav_msgs::OccupancyGrid& src, COccupancyGridMap2D& des)
00095 {
00096         if ((src.info.origin.orientation.x != 0) ||
00097                 (src.info.origin.orientation.y != 0) ||
00098                 (src.info.origin.orientation.z != 0) ||
00099                 (src.info.origin.orientation.w != 1))
00100         {
00101                 std::cerr << "Rotated maps are not supported by mrpt!" << std::endl;
00102                 return false;
00103         }
00104         float xmin = src.info.origin.position.x;
00105         float ymin = src.info.origin.position.y;
00106         float xmax = xmin + src.info.width * src.info.resolution;
00107         float ymax = ymin + src.info.height * src.info.resolution;
00108 
00109         MRPT_START
00110         des.setSize(xmin, xmax, ymin, ymax, src.info.resolution);
00111         MRPT_END
00112         // printf("--------convert:  %i x %i, %4.3f, %4.3f, %4.3f, %4.3f,
00113         // r:%4.3f\n",des.getSizeX(), des.getSizeY(), des.getXMin(), des.getXMax(),
00114         // des.getYMin(), des.getYMax(), des.getResolution());
00115 
00117         for (unsigned int h = 0; h < src.info.height; h++)
00118         {
00119                 COccupancyGridMap2D::cellType* pDes = des.getRow(h);
00120                 const int8_t* pSrc = &src.data[h * src.info.width];
00121                 for (unsigned int w = 0; w < src.info.width; w++)
00122                 {
00123                         *pDes++ = MapHdl::instance()->cellRos2Mrpt(*pSrc++);
00124                 }
00125         }
00126         return true;
00127 }
00128 bool convert(
00129         const COccupancyGridMap2D& src, nav_msgs::OccupancyGrid& des,
00130         const std_msgs::Header& header)
00131 {
00132         des.header = header;
00133         return convert(src, des);
00134 }
00135 
00136 bool convert(const COccupancyGridMap2D& src, nav_msgs::OccupancyGrid& des)
00137 {
00138         // printf("--------mrpt2ros:  %f, %f, %f, %f, r:%f\n",src.getXMin(),
00139         // src.getXMax(), src.getYMin(), src.getYMax(), src.getResolution());
00140         des.info.width = src.getSizeX();
00141         des.info.height = src.getSizeY();
00142         des.info.resolution = src.getResolution();
00143 
00144         des.info.origin.position.x = src.getXMin();
00145         des.info.origin.position.y = src.getYMin();
00146         des.info.origin.position.z = 0;
00147 
00148         des.info.origin.orientation.x = 0;
00149         des.info.origin.orientation.y = 0;
00150         des.info.origin.orientation.z = 0;
00151         des.info.origin.orientation.w = 1;
00152 
00154         des.data.resize(des.info.width * des.info.height);
00155         for (unsigned int h = 0; h < des.info.height; h++)
00156         {
00157                 const COccupancyGridMap2D::cellType* pSrc = src.getRow(h);
00158                 int8_t* pDes = &des.data[h * des.info.width];
00159                 for (unsigned int w = 0; w < des.info.width; w++)
00160                 {
00161                         *pDes++ = MapHdl::instance()->cellMrpt2Ros(*pSrc++);
00162                 }
00163         }
00164         return true;
00165 }
00166 
00167 const bool MapHdl::loadMap(
00168         CMultiMetricMap& _metric_map, const CConfigFile& _config_file,
00169         const std::string& _map_file, const std::string& _section_name, bool _debug)
00170 {
00171         using namespace mrpt::maps;
00172 
00173         TSetOfMetricMapInitializers mapInitializers;
00174         mapInitializers.loadFromConfigFile(_config_file, _section_name);
00175 
00176         CSimpleMap simpleMap;
00177 
00178         // Load the set of metric maps to consider in the experiments:
00179         _metric_map.setListOfMaps(&mapInitializers);
00180         if (_debug) mapInitializers.dumpToConsole();
00181 
00182 #if MRPT_VERSION >= 0x199
00183         auto& r = mrpt::random::getRandomGenerator();
00184 #else
00185         auto& r = mrpt::random::randomGenerator;
00186 #endif
00187         r.randomize();
00188 
00189         if (_debug)
00190                 printf(
00191                         "%s, _map_file.size() = %zu\n", _map_file.c_str(),
00192                         _map_file.size());
00193         // Load the map (if any):
00194         if (_map_file.size() < 3)
00195         {
00196                 if (_debug) printf("No mrpt map file!\n");
00197                 return false;
00198         }
00199         else
00200         {
00201                 ASSERT_(mrpt::system::fileExists(_map_file));
00202 
00203                 // Detect file extension:
00204                 std::string mapExt =
00205                         mrpt::system::lowerCase(mrpt::system::extractFileExtension(
00206                                 _map_file, true));  // Ignore possible .gz extensions
00207 
00208                 if (!mapExt.compare("simplemap"))
00209                 {
00210                         // It's a ".simplemap":
00211                         if (_debug) printf("Loading '.simplemap' file...");
00212                         CFileGZInputStream f(_map_file);
00213 #if MRPT_VERSION >= 0x199
00214                         mrpt::serialization::archiveFrom(f) >> simpleMap;
00215 #else
00216                         f >> simpleMap;
00217 #endif
00218                         printf("Ok\n");
00219 
00220                         ASSERTMSG_(
00221                                 simpleMap.size() > 0,
00222                                 "Simplemap was aparently loaded OK, but it is empty!");
00223 
00224                         // Build metric map:
00225                         if (_debug) printf("Building metric map(s) from '.simplemap'...");
00226                         _metric_map.loadFromSimpleMap(simpleMap);
00227                         if (_debug) printf("Ok\n");
00228                 }
00229                 else if (!mapExt.compare("gridmap"))
00230                 {
00231                         // It's a ".gridmap":
00232                         if (_debug) printf("Loading gridmap from '.gridmap'...");
00233                         ASSERTMSG_(
00234                                 _metric_map.m_gridMaps.size() == 1,
00235                                 "Error: Trying to load a gridmap into a multi-metric map "
00236                                 "requires 1 gridmap member.");
00237                         CFileGZInputStream fm(_map_file);
00238 #if MRPT_VERSION >= 0x199
00239                         mrpt::serialization::archiveFrom(fm) >>
00240                                 (*_metric_map.m_gridMaps[0]);
00241 #else
00242                         fm >> (*_metric_map.m_gridMaps[0]);
00243 #endif
00244                         if (_debug) printf("Ok\n");
00245                 }
00246                 else
00247                 {
00248                         THROW_EXCEPTION(mrpt::format(
00249                                 "Map file has unknown extension: '%s'", mapExt.c_str()));
00250                         return false;
00251                 }
00252         }
00253         return true;
00254 }
00255 
00256 }  // namespace mrpt_bridge


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Fri Apr 27 2018 05:10:54