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


mrpt_bridge
Author(s):
autogenerated on Mon Aug 11 2014 11:23:21