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


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Mon Sep 18 2017 03:12:06