GridMapRosConverter.cpp
Go to the documentation of this file.
1 /*
2  * GridMapRosConverter.cpp
3  *
4  * Created on: Jul 14, 2014
5  * Author: Péter Fankhauser
6  * Institute: ETH Zurich, ANYbotics
7  */
8 
12 
13 // ROS
15 #include <geometry_msgs/Point.h>
16 #include <geometry_msgs/Quaternion.h>
17 #include <rosbag/bag.h>
18 #include <rosbag/view.h>
19 
20 // STL
21 #include <limits>
22 #include <algorithm>
23 #include <vector>
24 
25 using namespace std;
26 using namespace Eigen;
27 
28 namespace grid_map {
29 
30 GridMapRosConverter::GridMapRosConverter()
31 {
32 }
33 
34 GridMapRosConverter::~GridMapRosConverter()
35 {
36 }
37 
38 bool GridMapRosConverter::fromMessage(const grid_map_msgs::GridMap& message, grid_map::GridMap& gridMap)
39 {
40  gridMap.setTimestamp(message.info.header.stamp.toNSec());
41  gridMap.setFrameId(message.info.header.frame_id);
42  gridMap.setGeometry(Length(message.info.length_x, message.info.length_y), message.info.resolution,
43  Position(message.info.pose.position.x, message.info.pose.position.y));
44 
45  if (message.layers.size() != message.data.size()) {
46  ROS_ERROR("Different number of layers and data in grid map message.");
47  return false;
48  }
49 
50  for (unsigned int i = 0; i < message.layers.size(); i++) {
51  Matrix data;
52  multiArrayMessageCopyToMatrixEigen(message.data[i], data); // TODO Could we use the data mapping (instead of copying) method here?
53  // TODO Check if size is good. size_ << getRows(message.data[0]), getCols(message.data[0]);
54  gridMap.add(message.layers[i], data);
55  }
56 
57  gridMap.setBasicLayers(message.basic_layers);
58  gridMap.setStartIndex(Index(message.outer_start_index, message.inner_start_index));
59  return true;
60 }
61 
62 void GridMapRosConverter::toMessage(const grid_map::GridMap& gridMap, grid_map_msgs::GridMap& message)
63 {
64  toMessage(gridMap, gridMap.getLayers(), message);
65 }
66 
67 void GridMapRosConverter::toMessage(const grid_map::GridMap& gridMap, const std::vector<std::string>& layers,
68  grid_map_msgs::GridMap& message)
69 {
70  message.info.header.stamp.fromNSec(gridMap.getTimestamp());
71  message.info.header.frame_id = gridMap.getFrameId();
72  message.info.resolution = gridMap.getResolution();
73  message.info.length_x = gridMap.getLength().x();
74  message.info.length_y = gridMap.getLength().y();
75  message.info.pose.position.x = gridMap.getPosition().x();
76  message.info.pose.position.y = gridMap.getPosition().y();
77  message.info.pose.position.z = 0.0;
78  message.info.pose.orientation.x = 0.0;
79  message.info.pose.orientation.y = 0.0;
80  message.info.pose.orientation.z = 0.0;
81  message.info.pose.orientation.w = 1.0;
82 
83  message.layers = layers;
84  message.basic_layers = gridMap.getBasicLayers();
85 
86  message.data.clear();
87  for (const auto& layer : layers) {
88  std_msgs::Float32MultiArray dataArray;
89  matrixEigenCopyToMultiArrayMessage(gridMap.get(layer), dataArray);
90  message.data.push_back(dataArray);
91  }
92 
93  message.outer_start_index = gridMap.getStartIndex()(0);
94  message.inner_start_index = gridMap.getStartIndex()(1);
95 }
96 
97 void GridMapRosConverter::toPointCloud(const grid_map::GridMap& gridMap,
98  const std::string& pointLayer,
99  sensor_msgs::PointCloud2& pointCloud)
100 {
101  toPointCloud(gridMap, gridMap.getLayers(), pointLayer, pointCloud);
102 }
103 
104 void GridMapRosConverter::toPointCloud(const grid_map::GridMap& gridMap,
105  const std::vector<std::string>& layers,
106  const std::string& pointLayer,
107  sensor_msgs::PointCloud2& pointCloud)
108 {
109  // Header.
110  pointCloud.header.frame_id = gridMap.getFrameId();
111  pointCloud.header.stamp.fromNSec(gridMap.getTimestamp());
112  pointCloud.is_dense = false;
113 
114  // Fields.
115  std::vector <std::string> fieldNames;
116 
117  for (const auto& layer : layers) {
118  if (layer == pointLayer) {
119  fieldNames.push_back("x");
120  fieldNames.push_back("y");
121  fieldNames.push_back("z");
122  } else if (layer == "color") {
123  fieldNames.push_back("rgb");
124  } else {
125  fieldNames.push_back(layer);
126  }
127  }
128 
129  pointCloud.fields.clear();
130  pointCloud.fields.reserve(fieldNames.size());
131  int offset = 0;
132 
133  for (auto& name : fieldNames) {
134  sensor_msgs::PointField pointField;
135  pointField.name = name;
136  pointField.count = 1;
137  pointField.datatype = sensor_msgs::PointField::FLOAT32;
138  pointField.offset = offset;
139  pointCloud.fields.push_back(pointField);
140  offset = offset + pointField.count * 4; // 4 for sensor_msgs::PointField::FLOAT32
141  }
142 
143  // Resize.
144  size_t maxNumberOfPoints = gridMap.getSize().prod();
145  pointCloud.height = 1;
146  pointCloud.width = maxNumberOfPoints;
147  pointCloud.point_step = offset;
148  pointCloud.row_step = pointCloud.width * pointCloud.point_step;
149  pointCloud.data.resize(pointCloud.height * pointCloud.row_step);
150 
151  // Points.
152  std::unordered_map<std::string, sensor_msgs::PointCloud2Iterator<float>> fieldIterators;
153  for (auto& name : fieldNames) {
154  fieldIterators.insert(
155  std::pair<std::string, sensor_msgs::PointCloud2Iterator<float>>(
156  name, sensor_msgs::PointCloud2Iterator<float>(pointCloud, name)));
157  }
158 
159  GridMapIterator mapIterator(gridMap);
160  const bool hasBasicLayers = gridMap.getBasicLayers().size() > 0;
161 
162  size_t realNumberOfPoints = 0;
163  for (size_t i = 0; i < maxNumberOfPoints; ++i) {
164  if (hasBasicLayers) {
165  if (!gridMap.isValid(*mapIterator)) {
166  ++mapIterator;
167  continue;
168  }
169  }
170 
171  Position3 position;
172  if (!gridMap.getPosition3(pointLayer, *mapIterator, position)) {
173  ++mapIterator;
174  continue;
175  }
176 
177  for (auto& iterator : fieldIterators) {
178  if (iterator.first == "x") {
179  *iterator.second = (float) position.x();
180  } else if (iterator.first == "y") {
181  *iterator.second = (float) position.y();
182  } else if (iterator.first == "z") {
183  *iterator.second = (float) position.z();
184  } else if (iterator.first == "rgb") {
185  *iterator.second = gridMap.at("color", *mapIterator);
186  } else {
187  *iterator.second = gridMap.at(iterator.first, *mapIterator);
188  }
189  }
190 
191  ++mapIterator;
192  for (auto& iterator : fieldIterators) {
193  ++iterator.second;
194  }
195  ++realNumberOfPoints;
196  }
197 
198  if (realNumberOfPoints != maxNumberOfPoints) {
199  pointCloud.width = realNumberOfPoints;
200  pointCloud.row_step = pointCloud.width * pointCloud.point_step;
201  pointCloud.data.resize(pointCloud.height * pointCloud.row_step);
202  }
203 }
204 
205 bool GridMapRosConverter::fromOccupancyGrid(const nav_msgs::OccupancyGrid& occupancyGrid,
206  const std::string& layer, grid_map::GridMap& gridMap)
207 {
208  const Size size(occupancyGrid.info.width, occupancyGrid.info.height);
209  const double resolution = occupancyGrid.info.resolution;
210  const Length length = resolution * size.cast<double>();
211  const string& frameId = occupancyGrid.header.frame_id;
212  Position position(occupancyGrid.info.origin.position.x, occupancyGrid.info.origin.position.y);
213  // Different conventions of center of map.
214  position += 0.5 * length.matrix();
215 
216  const auto& orientation = occupancyGrid.info.origin.orientation;
217  if (orientation.w != 1.0 && !(orientation.x == 0 && orientation.y == 0
218  && orientation.z == 0 && orientation.w == 0)) {
219  ROS_WARN_STREAM("Conversion of occupancy grid: Grid maps do not support orientation.");
220  ROS_INFO_STREAM("Orientation of occupancy grid: " << endl << occupancyGrid.info.origin.orientation);
221  return false;
222  }
223 
224  if (size.prod() != occupancyGrid.data.size()) {
225  ROS_WARN_STREAM("Conversion of occupancy grid: Size of data does not correspond to width * height.");
226  return false;
227  }
228 
229  // TODO: Split to `initializeFrom` and `from` as for Costmap2d.
230  if ((gridMap.getSize() != size).any() || gridMap.getResolution() != resolution
231  || (gridMap.getLength() != length).any() || gridMap.getPosition() != position
232  || gridMap.getFrameId() != frameId || !gridMap.getStartIndex().isZero()) {
233  gridMap.setTimestamp(occupancyGrid.header.stamp.toNSec());
234  gridMap.setFrameId(frameId);
235  gridMap.setGeometry(length, resolution, position);
236  }
237 
238  // Reverse iteration is required because of different conventions
239  // between occupancy grid and grid map.
240  grid_map::Matrix data(size(0), size(1));
241  for (std::vector<int8_t>::const_reverse_iterator iterator = occupancyGrid.data.rbegin();
242  iterator != occupancyGrid.data.rend(); ++iterator) {
243  size_t i = std::distance(occupancyGrid.data.rbegin(), iterator);
244  data(i) = *iterator != -1 ? *iterator : NAN;
245  }
246 
247  gridMap.add(layer, data);
248  return true;
249 }
250 
251 void GridMapRosConverter::toOccupancyGrid(const grid_map::GridMap& gridMap,
252  const std::string& layer, float dataMin, float dataMax,
253  nav_msgs::OccupancyGrid& occupancyGrid)
254 {
255  occupancyGrid.header.frame_id = gridMap.getFrameId();
256  occupancyGrid.header.stamp.fromNSec(gridMap.getTimestamp());
257  occupancyGrid.info.map_load_time = occupancyGrid.header.stamp; // Same as header stamp as we do not load the map.
258  occupancyGrid.info.resolution = gridMap.getResolution();
259  occupancyGrid.info.width = gridMap.getSize()(0);
260  occupancyGrid.info.height = gridMap.getSize()(1);
261  Position position = gridMap.getPosition() - 0.5 * gridMap.getLength().matrix();
262  occupancyGrid.info.origin.position.x = position.x();
263  occupancyGrid.info.origin.position.y = position.y();
264  occupancyGrid.info.origin.position.z = 0.0;
265  occupancyGrid.info.origin.orientation.x = 0.0;
266  occupancyGrid.info.origin.orientation.y = 0.0;
267  occupancyGrid.info.origin.orientation.z = 0.0;
268  occupancyGrid.info.origin.orientation.w = 1.0;
269  size_t nCells = gridMap.getSize().prod();
270  occupancyGrid.data.resize(nCells);
271 
272  // Occupancy probabilities are in the range [0,100]. Unknown is -1.
273  const float cellMin = 0;
274  const float cellMax = 100;
275  const float cellRange = cellMax - cellMin;
276 
277  for (GridMapIterator iterator(gridMap); !iterator.isPastEnd(); ++iterator) {
278  float value = (gridMap.at(layer, *iterator) - dataMin) / (dataMax - dataMin);
279  if (isnan(value))
280  value = -1;
281  else
282  value = cellMin + min(max(0.0f, value), 1.0f) * cellRange;
283  size_t index = getLinearIndexFromIndex(iterator.getUnwrappedIndex(), gridMap.getSize(), false);
284  // Reverse cell order because of different conventions between occupancy grid and grid map.
285  occupancyGrid.data[nCells - index - 1] = value;
286  }
287 }
288 
289 void GridMapRosConverter::toGridCells(const grid_map::GridMap& gridMap, const std::string& layer,
290  float lowerThreshold, float upperThreshold,
291  nav_msgs::GridCells& gridCells)
292 {
293  gridCells.header.frame_id = gridMap.getFrameId();
294  gridCells.header.stamp.fromNSec(gridMap.getTimestamp());
295  gridCells.cell_width = gridMap.getResolution();
296  gridCells.cell_height = gridMap.getResolution();
297 
298  for (GridMapIterator iterator(gridMap); !iterator.isPastEnd(); ++iterator) {
299  if (!gridMap.isValid(*iterator, layer)) continue;
300  if (gridMap.at(layer, *iterator) >= lowerThreshold
301  && gridMap.at(layer, *iterator) <= upperThreshold) {
302  Position position;
303  gridMap.getPosition(*iterator, position);
304  geometry_msgs::Point point;
305  point.x = position.x();
306  point.y = position.y();
307  gridCells.cells.push_back(point);
308  }
309  }
310 }
311 
312 bool GridMapRosConverter::initializeFromImage(const sensor_msgs::Image& image,
313  const double resolution, grid_map::GridMap& gridMap,
314  const grid_map::Position& position)
315 {
316  const double lengthX = resolution * image.height;
317  const double lengthY = resolution * image.width;
318  Length length(lengthX, lengthY);
319  gridMap.setGeometry(length, resolution, position);
320  gridMap.setFrameId(image.header.frame_id);
321  gridMap.setTimestamp(image.header.stamp.toNSec());
322  return true;
323 }
324 
325 bool GridMapRosConverter::addLayerFromImage(const sensor_msgs::Image& image,
326  const std::string& layer, grid_map::GridMap& gridMap,
327  const float lowerValue, const float upperValue,
328  const double alphaThreshold)
329 {
331  try {
332  // TODO Use `toCvShared()`?
333  cvImage = cv_bridge::toCvCopy(image, image.encoding);
334  } catch (cv_bridge::Exception& e) {
335  ROS_ERROR("cv_bridge exception: %s", e.what());
336  return false;
337  }
338 
339  const int cvEncoding = cv_bridge::getCvType(image.encoding);
340  switch (cvEncoding) {
341  case CV_8UC1:
342  return GridMapCvConverter::addLayerFromImage<unsigned char, 1>(cvImage->image, layer, gridMap, lowerValue, upperValue, alphaThreshold);
343  case CV_8UC3:
344  return GridMapCvConverter::addLayerFromImage<unsigned char, 3>(cvImage->image, layer, gridMap, lowerValue, upperValue, alphaThreshold);
345  case CV_8UC4:
346  return GridMapCvConverter::addLayerFromImage<unsigned char, 4>(cvImage->image, layer, gridMap, lowerValue, upperValue, alphaThreshold);
347  case CV_16UC1:
348  return GridMapCvConverter::addLayerFromImage<unsigned short, 1>(cvImage->image, layer, gridMap, lowerValue, upperValue, alphaThreshold);
349  case CV_16UC3:
350  return GridMapCvConverter::addLayerFromImage<unsigned short, 3>(cvImage->image, layer, gridMap, lowerValue, upperValue, alphaThreshold);
351  case CV_16UC4:
352  return GridMapCvConverter::addLayerFromImage<unsigned short, 4>(cvImage->image, layer, gridMap, lowerValue, upperValue, alphaThreshold);
353  default:
354  ROS_ERROR("Expected MONO8, MONO16, RGB(A)8, RGB(A)16, BGR(A)8, or BGR(A)16 image encoding.");
355  return false;
356  }
357 }
358 
359 bool GridMapRosConverter::addColorLayerFromImage(const sensor_msgs::Image& image,
360  const std::string& layer,
361  grid_map::GridMap& gridMap)
362 {
364  try {
365  cvImage = cv_bridge::toCvCopy(image, image.encoding);
366  } catch (cv_bridge::Exception& e) {
367  ROS_ERROR("cv_bridge exception: %s", e.what());
368  return false;
369  }
370 
371  const int cvEncoding = cv_bridge::getCvType(image.encoding);
372  switch (cvEncoding) {
373  case CV_8UC3:
374  return GridMapCvConverter::addColorLayerFromImage<unsigned char, 3>(cvImage->image, layer, gridMap);
375  case CV_8UC4:
376  return GridMapCvConverter::addColorLayerFromImage<unsigned char, 4>(cvImage->image, layer, gridMap);
377  case CV_16UC3:
378  return GridMapCvConverter::addColorLayerFromImage<unsigned short, 3>(cvImage->image, layer, gridMap);
379  case CV_16UC4:
380  return GridMapCvConverter::addColorLayerFromImage<unsigned short, 4>(cvImage->image, layer, gridMap);
381  default:
382  ROS_ERROR("Expected RGB(A)8, RGB(A)16, BGR(A)8, or BGR(A)16 image encoding.");
383  return false;
384  }
385 }
386 
387 bool GridMapRosConverter::toImage(const grid_map::GridMap& gridMap, const std::string& layer,
388  const std::string encoding, sensor_msgs::Image& image)
389 {
390  cv_bridge::CvImage cvImage;
391  if (!toCvImage(gridMap, layer, encoding, cvImage)) return false;
392  cvImage.toImageMsg(image);
393  return true;
394 }
395 
396 bool GridMapRosConverter::toImage(const grid_map::GridMap& gridMap, const std::string& layer,
397  const std::string encoding, const float lowerValue,
398  const float upperValue, sensor_msgs::Image& image)
399 {
400  cv_bridge::CvImage cvImage;
401  if (!toCvImage(gridMap, layer, encoding, lowerValue, upperValue, cvImage)) return false;
402  cvImage.toImageMsg(image);
403  return true;
404 }
405 
406 bool GridMapRosConverter::toCvImage(const grid_map::GridMap& gridMap, const std::string& layer,
407  const std::string encoding, cv_bridge::CvImage& cvImage)
408 {
409  const float minValue = gridMap.get(layer).minCoeffOfFinites();
410  const float maxValue = gridMap.get(layer).maxCoeffOfFinites();
411  return toCvImage(gridMap, layer, encoding, minValue, maxValue, cvImage);
412 }
413 
414 bool GridMapRosConverter::toCvImage(const grid_map::GridMap& gridMap, const std::string& layer,
415  const std::string encoding, const float lowerValue,
416  const float upperValue, cv_bridge::CvImage& cvImage)
417 {
418  cvImage.header.stamp.fromNSec(gridMap.getTimestamp());
419  cvImage.header.frame_id = gridMap.getFrameId();
420  cvImage.encoding = encoding;
421 
422  const int cvEncoding = cv_bridge::getCvType(encoding);
423  switch (cvEncoding) {
424  case CV_8UC1:
425  return GridMapCvConverter::toImage<unsigned char, 1>(gridMap, layer, cvEncoding, lowerValue, upperValue, cvImage.image);
426  case CV_8UC3:
427  return GridMapCvConverter::toImage<unsigned char, 3>(gridMap, layer, cvEncoding, lowerValue, upperValue, cvImage.image);
428  case CV_8UC4:
429  return GridMapCvConverter::toImage<unsigned char, 4>(gridMap, layer, cvEncoding, lowerValue, upperValue, cvImage.image);
430  case CV_16UC1:
431  return GridMapCvConverter::toImage<unsigned short, 1>(gridMap, layer, cvEncoding, lowerValue, upperValue, cvImage.image);
432  case CV_16UC3:
433  return GridMapCvConverter::toImage<unsigned short, 3>(gridMap, layer, cvEncoding, lowerValue, upperValue, cvImage.image);
434  case CV_16UC4:
435  return GridMapCvConverter::toImage<unsigned short, 4>(gridMap, layer, cvEncoding, lowerValue, upperValue, cvImage.image);
436  default:
437  ROS_ERROR("Expected MONO8, MONO16, RGB(A)8, RGB(A)16, BGR(A)8, or BGR(A)16 image encoding.");
438  return false;
439  }
440 }
441 
442 bool GridMapRosConverter::saveToBag(const grid_map::GridMap& gridMap, const std::string& pathToBag,
443  const std::string& topic)
444 {
445  grid_map_msgs::GridMap message;
446  toMessage(gridMap, message);
447  ros::Time time;
448  time.fromNSec(gridMap.getTimestamp());
449 
450  if (!time.isValid() || time.isZero()) {
452  time = ros::Time::now();
453  }
454 
455  rosbag::Bag bag;
456  bag.open(pathToBag, rosbag::bagmode::Write);
457  bag.write(topic, time, message);
458  bag.close();
459  return true;
460 }
461 
462 bool GridMapRosConverter::loadFromBag(const std::string& pathToBag, const std::string& topic,
463  grid_map::GridMap& gridMap)
464 {
465  rosbag::Bag bag;
466  bag.open(pathToBag, rosbag::bagmode::Read);
467  rosbag::View view(bag, rosbag::TopicQuery(topic));
468 
469  bool isDataFound = false;
470  for (const auto& messageInstance : view) {
471  grid_map_msgs::GridMap::ConstPtr message = messageInstance.instantiate<grid_map_msgs::GridMap>();
472  if (message != NULL) {
473  fromMessage(*message, gridMap);
474  isDataFound = true;
475  } else {
476  bag.close();
477  ROS_WARN("Unable to load data from ROS bag.");
478  return false;
479  }
480  }
481  if (!isDataFound) ROS_WARN_STREAM("No data under the topic '" << topic << "' was found.");
482  bag.close();
483  return true;
484 }
485 
486 } /* namespace */
const Length & getLength() const
Eigen::Array2i Index
void setGeometry(const Length &length, const double resolution, const Position &position=Position::Zero())
Time getTimestamp() const
const Index & getStartIndex() const
void open(std::string const &filename, uint32_t mode=bagmode::Read)
f
bool getPosition(const Index &index, Position &position) const
Time & fromNSec(uint64_t t)
void setBasicLayers(const std::vector< std::string > &basicLayers)
Eigen::Array2i Size
const std::string & getFrameId() const
Eigen::MatrixXf Matrix
std::string encoding
#define ROS_WARN(...)
void close()
bool isValid(const Index &index) const
Eigen::Vector3d Position3
double getResolution() const
const std::vector< std::string > & getLayers() const
Eigen::Vector2d Position
bool multiArrayMessageCopyToMatrixEigen(const MultiArrayMessageType_ &m, EigenType_ &e)
static bool isValid()
const Matrix & get(const std::string &layer) const
static void init()
void setStartIndex(const Index &startIndex)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
bool matrixEigenCopyToMultiArrayMessage(const EigenType_ &e, MultiArrayMessageType_ &m)
#define ROS_WARN_STREAM(args)
float & at(const std::string &layer, const Index &index)
int getCvType(const std::string &encoding)
void add(const std::string &layer, const double value=NAN)
#define ROS_INFO_STREAM(args)
int min(int a, int b)
size_t getLinearIndexFromIndex(const Index &index, const Size &bufferSize, const bool rowMajor=false)
static Time now()
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
void setFrameId(const std::string &frameId)
void setTimestamp(const Time timestamp)
#define ROS_ERROR(...)
bool getPosition3(const std::string &layer, const Index &index, Position3 &position) const
Eigen::Array2d Length
void write(std::string const &topic, ros::MessageEvent< T > const &event)
sensor_msgs::ImagePtr toImageMsg() const
const std::vector< std::string > & getBasicLayers() const
std_msgs::Header header
const Size & getSize() const


grid_map_ros
Author(s): Péter Fankhauser
autogenerated on Tue Jun 25 2019 20:02:19