4 #include <nav_msgs/OccupancyGrid.h> 8 #include <mrpt/random.h> 10 #if MRPT_VERSION >= 0x199 11 #include <mrpt/config/CConfigFile.h> 12 #include <mrpt/io/CFileGZInputStream.h> 13 using namespace mrpt::config;
14 using namespace mrpt::io;
16 #include <mrpt/utils/CConfigFile.h> 17 #include <mrpt/utils/CFileGZInputStream.h> 21 #include <mrpt/system/filesystem.h> 22 #include <mrpt/system/string_utils.h> 24 #include <mrpt/version.h> 25 #include <mrpt/maps/COccupancyGridMap2D.h> 26 #include <mrpt/maps/CMultiMetricMap.h> 27 #include <mrpt/maps/CSimpleMap.h> 28 using mrpt::maps::CLogOddsGridMapLUT;
29 using mrpt::maps::CMultiMetricMap;
30 using mrpt::maps::COccupancyGridMap2D;
31 using mrpt::maps::CSimpleMap;
33 #if MRPT_VERSION >= 0x199 34 #include <mrpt/serialization/CArchive.h> 37 #ifndef INT8_MAX // avoid duplicated #define's 39 #define INT8_MIN (-INT8_MAX - 1) 40 #define INT16_MAX 0x7fff 41 #define INT16_MIN (-INT16_MAX - 1) 46 MapHdl* MapHdl::instance_ = NULL;
51 CLogOddsGridMapLUT<COccupancyGridMap2D::cellType> table;
52 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS 56 lut_cellros2mrpt + INT8_MAX + 1;
65 float p = 1.0 - table.l2p(i);
66 int idx = round(p * 100.);
67 lut_cellmrpt2rosPtr[i] = idx;
75 float p = 1.0 - (v / 100.0);
76 int idx = table.p2l(p);
78 lut_cellros2mrptPtr[i] = table.p2l(0.5);
80 lut_cellros2mrptPtr[i] = table.p2l(0.5);
82 lut_cellros2mrptPtr[i] = idx;
90 if (instance_ == NULL) instance_ =
new MapHdl();
96 if ((src.info.origin.orientation.x != 0) ||
97 (src.info.origin.orientation.y != 0) ||
98 (src.info.origin.orientation.z != 0) ||
99 (src.info.origin.orientation.w != 1))
101 std::cerr <<
"Rotated maps are not supported by mrpt!" << std::endl;
104 float xmin = src.info.origin.position.x;
105 float ymin = src.info.origin.position.y;
106 float xmax = xmin + src.info.width * src.info.resolution;
107 float ymax = ymin + src.info.height * src.info.resolution;
110 des.setSize(xmin, xmax, ymin, ymax, src.info.resolution);
117 for (
unsigned int h = 0; h < src.info.height; h++)
119 COccupancyGridMap2D::cellType* pDes = des.getRow(h);
120 const int8_t* pSrc = &src.data[h * src.info.width];
121 for (
unsigned int w = 0;
w < src.info.width;
w++)
123 *pDes++ = MapHdl::instance()->cellRos2Mrpt(*pSrc++);
140 des.info.width = src.getSizeX();
141 des.info.height = src.getSizeY();
142 des.info.resolution = src.getResolution();
144 des.info.origin.position.x = src.getXMin();
145 des.info.origin.position.y = src.getYMin();
146 des.info.origin.position.z = 0;
148 des.info.origin.orientation.x = 0;
149 des.info.origin.orientation.y = 0;
150 des.info.origin.orientation.z = 0;
151 des.info.origin.orientation.w = 1;
154 des.data.resize(des.info.width * des.info.height);
155 for (
unsigned int h = 0; h < des.info.height; h++)
157 const COccupancyGridMap2D::cellType* pSrc = src.getRow(h);
158 int8_t* pDes = &des.data[h * des.info.width];
159 for (
unsigned int w = 0;
w < des.info.width;
w++)
161 *pDes++ = MapHdl::instance()->cellMrpt2Ros(*pSrc++);
167 const bool MapHdl::loadMap(
168 CMultiMetricMap& _metric_map,
const CConfigFile& _config_file,
169 const std::string& _map_file,
const std::string& _section_name,
bool _debug)
173 TSetOfMetricMapInitializers mapInitializers;
174 mapInitializers.loadFromConfigFile(_config_file, _section_name);
176 CSimpleMap simpleMap;
179 _metric_map.setListOfMaps(&mapInitializers);
180 if (_debug) mapInitializers.dumpToConsole();
182 #if MRPT_VERSION >= 0x199 183 auto& r = mrpt::random::getRandomGenerator();
185 auto& r = mrpt::random::randomGenerator;
191 "%s, _map_file.size() = %zu\n", _map_file.c_str(),
194 if (_map_file.size() < 3)
196 if (_debug) printf(
"No mrpt map file!\n");
201 ASSERT_(mrpt::system::fileExists(_map_file));
205 mrpt::system::lowerCase(mrpt::system::extractFileExtension(
208 if (!mapExt.compare(
"simplemap"))
211 if (_debug) printf(
"Loading '.simplemap' file...");
212 CFileGZInputStream
f(_map_file);
213 #if MRPT_VERSION >= 0x199 214 mrpt::serialization::archiveFrom(f) >> simpleMap;
221 simpleMap.size() > 0,
222 "Simplemap was aparently loaded OK, but it is empty!");
225 if (_debug) printf(
"Building metric map(s) from '.simplemap'...");
226 _metric_map.loadFromSimpleMap(simpleMap);
227 if (_debug) printf(
"Ok\n");
229 else if (!mapExt.compare(
"gridmap"))
232 if (_debug) printf(
"Loading gridmap from '.gridmap'...");
234 _metric_map.m_gridMaps.size() == 1,
235 "Error: Trying to load a gridmap into a multi-metric map " 236 "requires 1 gridmap member.");
237 CFileGZInputStream fm(_map_file);
238 #if MRPT_VERSION >= 0x199 239 mrpt::serialization::archiveFrom(fm) >>
240 (*_metric_map.m_gridMaps[0]);
242 fm >> (*_metric_map.m_gridMaps[0]);
244 if (_debug) printf(
"Ok\n");
248 THROW_EXCEPTION(mrpt::format(
249 "Map file has unknown extension: '%s'", mapExt.c_str()));
the map class is implemented as singeleton use map::instance ()->ros2mrpt ...
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
bool convert(const mrpt_msgs::ObservationRangeBeacon &_msg, const mrpt::poses::CPose3D &_pose, mrpt::obs::CObservationBeaconRanges &_obj)
TFSIMD_FORCE_INLINE const tfScalar & w() const