map.cpp
Go to the documentation of this file.
1 
2 #include "mrpt_bridge/map.h"
3 #include "mrpt_bridge/pose.h"
4 #include <nav_msgs/OccupancyGrid.h>
5 #include <ros/console.h>
6 
7 // Only include MRPT classes that are really used to avoid slow down compilation
8 #include <mrpt/random.h>
9 
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;
15 #else
16 #include <mrpt/utils/CConfigFile.h>
17 #include <mrpt/utils/CFileGZInputStream.h>
18 using namespace mrpt::utils;
19 #endif
20 
21 #include <mrpt/system/filesystem.h> // for fileExists()
22 #include <mrpt/system/string_utils.h> // for lowerCase()
23 
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;
32 
33 #if MRPT_VERSION >= 0x199
34 #include <mrpt/serialization/CArchive.h>
35 #endif
36 
37 #ifndef INT8_MAX // avoid duplicated #define's
38 #define INT8_MAX 0x7f
39 #define INT8_MIN (-INT8_MAX - 1)
40 #define INT16_MAX 0x7fff
41 #define INT16_MIN (-INT16_MAX - 1)
42 #endif // INT8_MAX
43 
44 namespace mrpt_bridge
45 {
46 MapHdl* MapHdl::instance_ = NULL;
47 
48 MapHdl::MapHdl()
49 {
51  CLogOddsGridMapLUT<COccupancyGridMap2D::cellType> table;
52 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS
53  lut_cellmrpt2rosPtr =
54  lut_cellmrpt2ros + INT8_MAX + 1; // center the pointer
55  lut_cellros2mrptPtr =
56  lut_cellros2mrpt + INT8_MAX + 1; // center the pointer
57  for (int i = INT8_MIN; i < INT8_MAX; i++)
58  {
59 #else
60  lut_cellmrpt2rosPtr =
61  lut_cellmrpt2ros + INT16_MAX + 1; // center the pointer
62  for (int i = INT16_MIN; INT16_MIN < INT16_MAX; i++)
63  {
64 #endif
65  float p = 1.0 - table.l2p(i);
66  int idx = round(p * 100.);
67  lut_cellmrpt2rosPtr[i] = idx;
68  // printf("- cell -> ros = %4i -> %4i, p=%4.3f\n", i, idx, p);
69  }
70  for (int i = INT8_MIN; i < INT8_MAX; i++)
71  {
72  float v = i;
73  if (v > 100) v = 50;
74  if (v < 0) v = 50;
75  float p = 1.0 - (v / 100.0);
76  int idx = table.p2l(p);
77  if (i < 0)
78  lut_cellros2mrptPtr[i] = table.p2l(0.5);
79  else if (i > 100)
80  lut_cellros2mrptPtr[i] = table.p2l(0.5);
81  else
82  lut_cellros2mrptPtr[i] = idx;
83  // printf("- ros -> cell = %4i -> %4i, p=%4.3f\n", i, idx, p);
84  fflush(stdout);
85  }
86 }
87 MapHdl::~MapHdl() {}
88 MapHdl* MapHdl::instance()
89 {
90  if (instance_ == NULL) instance_ = new MapHdl();
91  return instance_;
92 }
93 
94 bool convert(const nav_msgs::OccupancyGrid& src, COccupancyGridMap2D& des)
95 {
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))
100  {
101  std::cerr << "Rotated maps are not supported by mrpt!" << std::endl;
102  return false;
103  }
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;
108 
109  MRPT_START
110  des.setSize(xmin, xmax, ymin, ymax, src.info.resolution);
111  MRPT_END
112  // printf("--------convert: %i x %i, %4.3f, %4.3f, %4.3f, %4.3f,
113  // r:%4.3f\n",des.getSizeX(), des.getSizeY(), des.getXMin(), des.getXMax(),
114  // des.getYMin(), des.getYMax(), des.getResolution());
115 
117  for (unsigned int h = 0; h < src.info.height; h++)
118  {
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++)
122  {
123  *pDes++ = MapHdl::instance()->cellRos2Mrpt(*pSrc++);
124  }
125  }
126  return true;
127 }
128 bool convert(
129  const COccupancyGridMap2D& src, nav_msgs::OccupancyGrid& des,
130  const std_msgs::Header& header)
131 {
132  des.header = header;
133  return convert(src, des);
134 }
135 
136 bool convert(const COccupancyGridMap2D& src, nav_msgs::OccupancyGrid& des)
137 {
138  // printf("--------mrpt2ros: %f, %f, %f, %f, r:%f\n",src.getXMin(),
139  // src.getXMax(), src.getYMin(), src.getYMax(), src.getResolution());
140  des.info.width = src.getSizeX();
141  des.info.height = src.getSizeY();
142  des.info.resolution = src.getResolution();
143 
144  des.info.origin.position.x = src.getXMin();
145  des.info.origin.position.y = src.getYMin();
146  des.info.origin.position.z = 0;
147 
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;
152 
154  des.data.resize(des.info.width * des.info.height);
155  for (unsigned int h = 0; h < des.info.height; h++)
156  {
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++)
160  {
161  *pDes++ = MapHdl::instance()->cellMrpt2Ros(*pSrc++);
162  }
163  }
164  return true;
165 }
166 
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)
170 {
171  using namespace mrpt::maps;
172 
173  TSetOfMetricMapInitializers mapInitializers;
174  mapInitializers.loadFromConfigFile(_config_file, _section_name);
175 
176  CSimpleMap simpleMap;
177 
178  // Load the set of metric maps to consider in the experiments:
179  _metric_map.setListOfMaps(&mapInitializers);
180  if (_debug) mapInitializers.dumpToConsole();
181 
182 #if MRPT_VERSION >= 0x199
183  auto& r = mrpt::random::getRandomGenerator();
184 #else
185  auto& r = mrpt::random::randomGenerator;
186 #endif
187  r.randomize();
188 
189  if (_debug)
190  printf(
191  "%s, _map_file.size() = %zu\n", _map_file.c_str(),
192  _map_file.size());
193  // Load the map (if any):
194  if (_map_file.size() < 3)
195  {
196  if (_debug) printf("No mrpt map file!\n");
197  return false;
198  }
199  else
200  {
201  ASSERT_(mrpt::system::fileExists(_map_file));
202 
203  // Detect file extension:
204  std::string mapExt =
205  mrpt::system::lowerCase(mrpt::system::extractFileExtension(
206  _map_file, true)); // Ignore possible .gz extensions
207 
208  if (!mapExt.compare("simplemap"))
209  {
210  // It's a ".simplemap":
211  if (_debug) printf("Loading '.simplemap' file...");
212  CFileGZInputStream f(_map_file);
213 #if MRPT_VERSION >= 0x199
214  mrpt::serialization::archiveFrom(f) >> simpleMap;
215 #else
216  f >> simpleMap;
217 #endif
218  printf("Ok\n");
219 
220  ASSERTMSG_(
221  simpleMap.size() > 0,
222  "Simplemap was aparently loaded OK, but it is empty!");
223 
224  // Build metric map:
225  if (_debug) printf("Building metric map(s) from '.simplemap'...");
226  _metric_map.loadFromSimpleMap(simpleMap);
227  if (_debug) printf("Ok\n");
228  }
229  else if (!mapExt.compare("gridmap"))
230  {
231  // It's a ".gridmap":
232  if (_debug) printf("Loading gridmap from '.gridmap'...");
233  ASSERTMSG_(
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]);
241 #else
242  fm >> (*_metric_map.m_gridMaps[0]);
243 #endif
244  if (_debug) printf("Ok\n");
245  }
246  else
247  {
248  THROW_EXCEPTION(mrpt::format(
249  "Map file has unknown extension: '%s'", mapExt.c_str()));
250  return false;
251  }
252  }
253  return true;
254 }
255 
256 } // namespace mrpt_bridge
the map class is implemented as singeleton use map::instance ()->ros2mrpt ...
Definition: map.h:70
f
#define INT16_MAX
Definition: map.cpp:40
#define INT8_MAX
Definition: map.cpp:38
Definition: map.h:30
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
#define INT16_MIN
Definition: map.cpp:41
#define INT8_MIN
Definition: map.cpp:39


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Sat Apr 28 2018 02:49:17