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


grid_map_ros
Author(s): Péter Fankhauser
autogenerated on Wed Jul 5 2023 02:23:44