GridMapTest.cpp
Go to the documentation of this file.
1 /*
2  * GridMapTest.cpp
3  *
4  * Created on: Aug 26, 2015
5  * Author: Péter Fankhauser
6  * Institute: ETH Zurich, ANYbotics
7  */
8 
10 
11 // gtest
12 #include <gtest/gtest.h>
13 
14 namespace grid_map {
15 
16 TEST(GridMap, CopyConstructor) {
17  GridMap map({"layer_a", "layer_b"});
18  map.setGeometry(Length(1.0, 2.0), 0.1, Position(0.1, 0.2));
19  map["layer_a"].setConstant(1.0);
20  map["layer_b"].setConstant(2.0);
21  GridMap mapCopy(map);
22  EXPECT_EQ(map.getSize()[0], mapCopy.getSize()[0]);
23  EXPECT_EQ(map.getSize()[1], mapCopy.getSize()[1]);
24  EXPECT_EQ(map.getLength().x(), mapCopy.getLength().x());
25  EXPECT_EQ(map.getLength().y(), mapCopy.getLength().y());
26  EXPECT_EQ(map.getPosition().x(), mapCopy.getPosition().x());
27  EXPECT_EQ(map.getPosition().y(), mapCopy.getPosition().y());
28  EXPECT_EQ(map.getLayers().size(), mapCopy.getLayers().size());
29  EXPECT_EQ(map["layer_a"](0, 0), mapCopy["layer_a"](0, 0));
30  EXPECT_EQ(map["layer_b"](0, 0), mapCopy["layer_b"](0, 0));
31 }
32 
33 TEST(GridMap, CopyAssign)
34 {
35  GridMap map({"layer_a", "layer_b"});
36  map.setGeometry(Length(1.0, 2.0), 0.1, Position(0.1, 0.2));
37  map["layer_a"].setConstant(1.0);
38  map["layer_b"].setConstant(2.0);
39  GridMap mapCopy;
40  mapCopy = map;
41  EXPECT_EQ(map.getSize()[0], mapCopy.getSize()[0]);
42  EXPECT_EQ(map.getSize()[1], mapCopy.getSize()[1]);
43  EXPECT_EQ(map.getLength().x(), mapCopy.getLength().x());
44  EXPECT_EQ(map.getLength().y(), mapCopy.getLength().y());
45  EXPECT_EQ(map.getPosition().x(), mapCopy.getPosition().x());
46  EXPECT_EQ(map.getPosition().y(), mapCopy.getPosition().y());
47  EXPECT_EQ(map.getLayers().size(), mapCopy.getLayers().size());
48  EXPECT_EQ(map["layer_a"](0, 0), mapCopy["layer_a"](0, 0));
49  EXPECT_EQ(map["layer_b"](0, 0), mapCopy["layer_b"](0, 0));
50 }
51 
52 TEST(GridMap, Move)
53 {
54  GridMap map;
55  map.setGeometry(Length(8.1, 5.1), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5)
56  map.add("layer", 0.0);
57  map.setBasicLayers(map.getLayers());
58  std::vector<BufferRegion> regions;
59  map.move(Position(-3.0, -2.0), regions);
60  Index startIndex = map.getStartIndex();
61 
62  EXPECT_EQ(3, startIndex(0));
63  EXPECT_EQ(2, startIndex(1));
64 
65  Eigen::Matrix<bool, 8, 5> isValidExpected;
66  isValidExpected << false, false, false, false, false, // clang-format off
67  false, false, false, false, false,
68  false, false, false, false, false,
69  false, false, true, true, true,
70  false, false, true, true, true,
71  false, false, true, true, true,
72  false, false, true, true, true,
73  false, false, true, true, true; // clang-format on
74  for(int row{0}; row < 8; row++){
75  for(int col{0}; col < 5; col++){
76  EXPECT_EQ(map.isValid(Index(row, col)), isValidExpected(row, col)) << "Value of map.isValid at ["<<row << ", " << col <<"] is unexpected!";
77  }
78  }
79 
80  EXPECT_EQ(2, regions.size());
81  EXPECT_EQ(0, regions[0].getStartIndex()[0]);
82  EXPECT_EQ(0, regions[0].getStartIndex()[1]);
83  EXPECT_EQ(3, regions[0].getSize()[0]);
84  EXPECT_EQ(5, regions[0].getSize()[1]);
85  EXPECT_EQ(0, regions[1].getStartIndex()[0]);
86  EXPECT_EQ(0, regions[1].getStartIndex()[1]);
87  EXPECT_EQ(8, regions[1].getSize()[0]);
88  EXPECT_EQ(2, regions[1].getSize()[1]);
89 }
90 
91 TEST(GridMap, Transform)
92 {
93  // Initial map.
94  GridMap map;
95  constexpr auto heightLayerName = "height";
96 
97  map.setGeometry(Length(1.0, 2.0), 0.1, Position(0.0, 0.0));
98  map.add(heightLayerName, 0.0);
99  map.setBasicLayers(map.getLayers());
100  map.get(heightLayerName)(0,0) = 1.0;
101 
102  // Transformation (90° rotation).
103  Eigen::Isometry3d transform;
104 
105  transform.translation().x() = 0.0;
106  transform.translation().y() = 0.0;
107  transform.translation().z() = 0.0;
108 
109  transform.linear()(0,0) = 0.0;
110  transform.linear()(0,1) = -1.0;
111  transform.linear()(0,2) = 0.0;
112 
113  transform.linear()(1,0) = 1.0;
114  transform.linear()(1,1) = 0.0;
115  transform.linear()(1,2) = 0.0;
116 
117  transform.linear()(2,0) = 0.0;
118  transform.linear()(2,1) = 0.0;
119  transform.linear()(2,2) = 1.0;
120 
121  // Apply affine transformation.
122  const GridMap transformedMap = map.getTransformedMap(transform, heightLayerName, map.getFrameId(), 0.25);
123 
124  // Check if map has been rotated by 90° about z
125  EXPECT_NEAR(map.getLength().x(), transformedMap.getLength().y(), 1e-6);
126  EXPECT_NEAR(map.getLength().y(), transformedMap.getLength().x(), 1e-6);
127  EXPECT_EQ(map.get(heightLayerName).size(), transformedMap.get(heightLayerName).size());
128  EXPECT_DOUBLE_EQ(map.get(heightLayerName)(0,0), transformedMap.get(heightLayerName)(19,0));
129 }
130 
131 TEST(GridMap, ClipToMap)
132 {
133  GridMap map({"layer_a", "layer_b"});
134  map.setGeometry(Length(1.0, 1.0), 0.1, Position(0.5, 0.5));
135  map["layer_a"].setConstant(1.0);
136  map["layer_b"].setConstant(2.0);
137 
138  const Position positionInMap = Position(0.4, 0.3); // position located inside the map
139  const Position positionOutMap = Position(1.0, 2.0); // position located outside the map
140 
141  const Position clippedPositionInMap = map.getClosestPositionInMap(positionInMap);
142  const Position clippedPositionOutMap = map.getClosestPositionInMap(positionOutMap);
143 
144  // Check if position-in-map remains unchanged.
145  EXPECT_NEAR(clippedPositionInMap.x(),positionInMap.x(), 1e-6);
146  EXPECT_NEAR(clippedPositionInMap.y(), positionInMap.y(), 1e-6);
147 
148  // Check if position-out-map is indeed outside the map.
149  EXPECT_TRUE(!map.isInside(positionOutMap));
150 
151  // Check if position-out-map has been projected into the map.
152  EXPECT_TRUE(map.isInside(clippedPositionOutMap));
153 }
154 
155 
156 
157 TEST(GridMap, ClipToMap2)
158 {
159  GridMap map({"types"});
160  map.setGeometry(Length(1.0, 1.0), 0.05, Position(0.0, 0.0));
161 
162  // Test 8 points outside of map.
163  /*
164  * A B C
165  * +---+
166  * | | X
167  * D| |E ^
168  * | | |
169  * +---+ Y<--+
170  * F G H
171  *
172  * Note: Position to index alignment is a half open interval.
173  * An example position of 0.5 is assigned to the upper index.
174  * The interval in the current example is:
175  * Position: [...)[0.485 ... 0.5)[0.5 ... 0.505)[...)
176  * Index: 8 9 10 11
177  */
178 
179  Index insideIndex;
180  Position outsidePosition;
181 
182  // Point A
183  outsidePosition = Position(1.0, 1.0);
184  auto closestInsidePosition = map.getClosestPositionInMap(outsidePosition);
185  bool isInside = map.getIndex(closestInsidePosition, insideIndex);
186 
187  auto expectedPosition = Position(0.5, 0.5);
188  auto expectedIndex = Index(0, 0);
189 
190  // Check position.
191  EXPECT_DOUBLE_EQ(expectedPosition.x(), closestInsidePosition.x());
192  EXPECT_DOUBLE_EQ(expectedPosition.y(), closestInsidePosition.y());
193 
194  // Check index.
195  EXPECT_EQ(expectedIndex.x(), insideIndex.x()) << "closestInsidePosition" << closestInsidePosition;
196  EXPECT_EQ(expectedIndex.y(), insideIndex.y()) << "closestInsidePosition" << closestInsidePosition;
197 
198  // Check if index is inside.
199  EXPECT_TRUE(isInside) << "position is: " << std::endl
200  << closestInsidePosition << std::endl
201  << " index is: " << std::endl
202  << insideIndex << std::endl;
203 
204  // Point B
205  outsidePosition = Position(1.0, 0.0);
206  closestInsidePosition = map.getClosestPositionInMap(outsidePosition);
207  isInside = map.getIndex(closestInsidePosition, insideIndex);
208 
209  expectedPosition = Position(0.5, 0.0);
210  expectedIndex = Index(0, 10);
211 
212  // Check position.
213  EXPECT_DOUBLE_EQ(expectedPosition.x(), closestInsidePosition.x());
214  EXPECT_DOUBLE_EQ(expectedPosition.y(), closestInsidePosition.y());
215 
216  // Check index.
217  EXPECT_EQ(expectedIndex.x(), insideIndex.x()) << "closestInsidePosition" << closestInsidePosition;
218  EXPECT_EQ(expectedIndex.y(), insideIndex.y()) << "closestInsidePosition" << closestInsidePosition;
219 
220  // Check if index is inside.
221  EXPECT_TRUE(isInside) << "position is: " << std::endl
222  << closestInsidePosition << std::endl
223  << " index is: " << std::endl
224  << insideIndex << std::endl;
225 
226  // Point C
227  outsidePosition = Position(1.0, -1.0);
228  closestInsidePosition = map.getClosestPositionInMap(outsidePosition);
229  isInside = map.getIndex(closestInsidePosition, insideIndex);
230 
231  expectedPosition = Position(0.5, -0.5);
232  expectedIndex = Index(0, 19);
233 
234  // Check position.
235  EXPECT_DOUBLE_EQ(expectedPosition.x(), closestInsidePosition.x());
236  EXPECT_DOUBLE_EQ(expectedPosition.y(), closestInsidePosition.y());
237 
238  // Check index.
239  EXPECT_EQ(expectedIndex.x(), insideIndex.x()) << "closestInsidePosition" << closestInsidePosition;
240  EXPECT_EQ(expectedIndex.y(), insideIndex.y()) << "closestInsidePosition" << closestInsidePosition;
241 
242  // Check if index is inside.
243  EXPECT_TRUE(isInside) << "position is: " << std::endl
244  << closestInsidePosition << std::endl
245  << " index is: " << std::endl
246  << insideIndex << std::endl;
247 
248  // Point D
249  outsidePosition = Position(0.0, 1.0);
250  closestInsidePosition = map.getClosestPositionInMap(outsidePosition);
251  isInside = map.getIndex(closestInsidePosition, insideIndex);
252 
253  expectedPosition = Position(0.0, 0.5);
254  expectedIndex = Index(10, 0);
255 
256  // Check position.
257  EXPECT_DOUBLE_EQ(expectedPosition.x(), closestInsidePosition.x());
258  EXPECT_DOUBLE_EQ(expectedPosition.y(), closestInsidePosition.y());
259 
260  // Check index.
261  EXPECT_EQ(expectedIndex.x(), insideIndex.x()) << "closestInsidePosition" << closestInsidePosition;
262  EXPECT_EQ(expectedIndex.y(), insideIndex.y()) << "closestInsidePosition" << closestInsidePosition;
263 
264  // Check if index is inside.
265  EXPECT_TRUE(isInside) << "position is: " << std::endl
266  << closestInsidePosition << std::endl
267  << " index is: " << std::endl
268  << insideIndex << std::endl;
269 
270  // Point E
271  outsidePosition = Position(0.0, -1.0);
272  closestInsidePosition = map.getClosestPositionInMap(outsidePosition);
273  isInside = map.getIndex(closestInsidePosition, insideIndex);
274 
275  expectedPosition = Position(0.0, -0.5);
276  expectedIndex = Index(10, 19);
277 
278  // Check position.
279  EXPECT_DOUBLE_EQ(expectedPosition.x(), closestInsidePosition.x());
280  EXPECT_DOUBLE_EQ(expectedPosition.y(), closestInsidePosition.y());
281 
282  // Check index.
283  EXPECT_EQ(expectedIndex.x(), insideIndex.x()) << "closestInsidePosition" << closestInsidePosition;
284  EXPECT_EQ(expectedIndex.y(), insideIndex.y()) << "closestInsidePosition" << closestInsidePosition;
285 
286  // Check if index is inside.
287  EXPECT_TRUE(isInside) << "position is: " << std::endl
288  << closestInsidePosition << std::endl
289  << " index is: " << std::endl
290  << insideIndex << std::endl;
291 
292  // Point F
293  outsidePosition = Position(-1.0, 1.0);
294  closestInsidePosition = map.getClosestPositionInMap(outsidePosition);
295  isInside = map.getIndex(closestInsidePosition, insideIndex);
296 
297  expectedPosition = Position(-0.5, 0.5);
298  expectedIndex = Index(19, 0);
299 
300  // Check position.
301  EXPECT_DOUBLE_EQ(expectedPosition.x(), closestInsidePosition.x());
302  EXPECT_DOUBLE_EQ(expectedPosition.y(), closestInsidePosition.y());
303 
304  // Check index.
305  EXPECT_EQ(expectedIndex.x(), insideIndex.x()) << "closestInsidePosition" << closestInsidePosition;
306  EXPECT_EQ(expectedIndex.y(), insideIndex.y()) << "closestInsidePosition" << closestInsidePosition;
307 
308  // Check if index is inside.
309  EXPECT_TRUE(isInside) << "position is: " << std::endl
310  << closestInsidePosition << std::endl
311  << " index is: " << std::endl
312  << insideIndex << std::endl;
313 
314  // Point G
315  outsidePosition = Position(-1.0, 0.0);
316  closestInsidePosition = map.getClosestPositionInMap(outsidePosition);
317  isInside = map.getIndex(closestInsidePosition, insideIndex);
318 
319  expectedPosition = Position(-0.5, 0.0);
320  expectedIndex = Index(19, 10);
321 
322  // Check position.
323  EXPECT_DOUBLE_EQ(expectedPosition.x(), closestInsidePosition.x());
324  EXPECT_DOUBLE_EQ(expectedPosition.y(), closestInsidePosition.y());
325 
326  // Check index.
327  EXPECT_EQ(expectedIndex.x(), insideIndex.x()) << "closestInsidePosition" << closestInsidePosition;
328  EXPECT_EQ(expectedIndex.y(), insideIndex.y()) << "closestInsidePosition" << closestInsidePosition;
329 
330  // Check if index is inside.
331  EXPECT_TRUE(isInside) << "position is: " << std::endl
332  << closestInsidePosition << std::endl
333  << " index is: " << std::endl
334  << insideIndex << std::endl;
335 
336  // Point H
337  outsidePosition = Position(-1.0, -1.0);
338  closestInsidePosition = map.getClosestPositionInMap(outsidePosition);
339  isInside = map.getIndex(closestInsidePosition, insideIndex);
340 
341  expectedPosition = Position(-0.5, -0.5);
342  expectedIndex = Index(19, 19);
343 
344  // Check position.
345  EXPECT_DOUBLE_EQ(expectedPosition.x(), closestInsidePosition.x());
346  EXPECT_DOUBLE_EQ(expectedPosition.y(), closestInsidePosition.y());
347 
348  // Check index.
349  EXPECT_EQ(expectedIndex.x(), insideIndex.x()) << "closestInsidePosition" << closestInsidePosition;
350  EXPECT_EQ(expectedIndex.y(), insideIndex.y()) << "closestInsidePosition" << closestInsidePosition;
351 
352  // Check if index is inside.
353  EXPECT_TRUE(isInside) << "position is: " << std::endl
354  << closestInsidePosition << std::endl
355  << " index is: " << std::endl
356  << insideIndex << std::endl;
357 }
358 
359 TEST(AddDataFrom, ExtendMapAligned)
360 {
361  GridMap map1;
362  GridMap map2;
363  map1.setGeometry(Length(5.1, 5.1), 1.0, Position(0.0, 0.0)); // bufferSize(5, 5)
364  map1.add("zero", 0.0);
365  map1.add("one", 1.0);
366  map1.setBasicLayers(map1.getLayers());
367 
368  map2.setGeometry(Length(3.1, 3.1), 1.0, Position(2.0, 2.0));
369  map2.add("one", 1.1);
370  map2.add("two", 2.0);
371  map2.setBasicLayers(map1.getLayers());
372 
373  map1.addDataFrom(map2, true, true, true);
374 
375  EXPECT_TRUE(map1.exists("two"));
376  EXPECT_TRUE(map1.isInside(Position(3.0, 3.0)));
377  EXPECT_DOUBLE_EQ(6.0, map1.getLength().x());
378  EXPECT_DOUBLE_EQ(6.0, map1.getLength().y());
379  EXPECT_DOUBLE_EQ(0.5, map1.getPosition().x());
380  EXPECT_DOUBLE_EQ(0.5, map1.getPosition().y());
381  EXPECT_NEAR(1.1, map1.atPosition("one", Position(2, 2)), 1e-4);
382  EXPECT_DOUBLE_EQ(1.0, map1.atPosition("one", Position(-2, -2)));
383  EXPECT_DOUBLE_EQ(0.0, map1.atPosition("zero", Position(0.0, 0.0)));
384 }
385 
386 TEST(AddDataFrom, ExtendMapNotAligned)
387 {
388  GridMap map1;
389  GridMap map2;
390  map1.setGeometry(Length(6.1, 6.1), 1.0, Position(0.0, 0.0)); // bufferSize(6, 6)
391  map1.add("nan");
392  map1.add("one", 1.0);
393  map1.add("zero", 0.0);
394  map1.setBasicLayers(map1.getLayers());
395 
396  map2.setGeometry(Length(3.1, 3.1), 1.0, Position(3.2, 3.2));
397  map2.add("nan", 1.0);
398  map2.add("one", 1.1);
399  map2.add("two", 2.0);
400  map2.setBasicLayers(map1.getLayers());
401 
402  std::vector<std::string> stringVector;
403  stringVector.emplace_back("nan");
404  map1.addDataFrom(map2, true, false, false, stringVector);
405  Index index;
406  map1.getIndex(Position(-2, -2), index);
407 
408  EXPECT_FALSE(map1.exists("two"));
409  EXPECT_TRUE(map1.isInside(Position(4.0, 4.0)));
410  EXPECT_DOUBLE_EQ(8.0, map1.getLength().x());
411  EXPECT_DOUBLE_EQ(8.0, map1.getLength().y());
412  EXPECT_DOUBLE_EQ(1.0, map1.getPosition().x());
413  EXPECT_DOUBLE_EQ(1.0, map1.getPosition().y());
414  EXPECT_FALSE(map1.isValid(index, "nan"));
415  EXPECT_DOUBLE_EQ(1.0, map1.atPosition("one", Position(0.0, 0.0)));
416  EXPECT_DOUBLE_EQ(1.0, map1.atPosition("nan", Position(3.0, 3.0)));
417 }
418 
419 TEST(AddDataFrom, CopyData)
420 {
421  GridMap map1;
422  GridMap map2;
423  map1.setGeometry(Length(5.1, 5.1), 1.0, Position(0.0, 0.0)); // bufferSize(5, 5)
424  map1.add("zero", 0.0);
425  map1.add("one");
426  map1.setBasicLayers(map1.getLayers());
427 
428  map2.setGeometry(Length(3.1, 3.1), 1.0, Position(2.0, 2.0));
429  map2.add("one", 1.0);
430  map2.add("two", 2.0);
431  map2.setBasicLayers(map1.getLayers());
432 
433  map1.addDataFrom(map2, false, false, true);
434  Index index;
435  map1.getIndex(Position(-2, -2), index);
436 
437  EXPECT_TRUE(map1.exists("two"));
438  EXPECT_FALSE(map1.isInside(Position(3.0, 3.0)));
439  EXPECT_DOUBLE_EQ(5.0, map1.getLength().x());
440  EXPECT_DOUBLE_EQ(5.0, map1.getLength().y());
441  EXPECT_DOUBLE_EQ(0.0, map1.getPosition().x());
442  EXPECT_DOUBLE_EQ(0.0, map1.getPosition().y());
443  EXPECT_DOUBLE_EQ(1.0, map1.atPosition("one", Position(2, 2)));
444  EXPECT_FALSE(map1.isValid(index, "one"));
445  EXPECT_DOUBLE_EQ(0.0, map1.atPosition("zero", Position(0.0, 0.0)));
446 }
447 
448 TEST(ValueAtPosition, NearestNeighbor)
449 {
450  GridMap map( { "types" });
451  map.setGeometry(Length(3.0, 3.0), 1.0, Position(0.0, 0.0));
452 
453  map.at("types", Index(0,0)) = 0.5;
454  map.at("types", Index(0,1)) = 3.8;
455  map.at("types", Index(0,2)) = 2.0;
456  map.at("types", Index(1,0)) = 2.1;
457  map.at("types", Index(1,1)) = 1.0;
458  map.at("types", Index(1,2)) = 2.0;
459  map.at("types", Index(2,0)) = 1.0;
460  map.at("types", Index(2,1)) = 2.0;
461  map.at("types", Index(2,2)) = 2.0;
462 
463  double value = map.atPosition("types", Position(1.35,-0.4));
464  EXPECT_DOUBLE_EQ((float)3.8, value);
465 
466  value = map.atPosition("types", Position(-0.3,0.0));
467  EXPECT_DOUBLE_EQ(1.0, value);
468 }
469 
470 TEST(ValueAtPosition, LinearInterpolated)
471 {
472  GridMap map( { "types" });
473  map.setGeometry(Length(3.0, 3.0), 1.0, Position(0.0, 0.0));
474 
475  map.at("types", Index(0,0)) = 0.5;
476  map.at("types", Index(0,1)) = 3.8;
477  map.at("types", Index(0,2)) = 2.0;
478  map.at("types", Index(1,0)) = 2.1;
479  map.at("types", Index(1,1)) = 1.0;
480  map.at("types", Index(1,2)) = 2.0;
481  map.at("types", Index(2,0)) = 1.0;
482  map.at("types", Index(2,1)) = 2.0;
483  map.at("types", Index(2,2)) = 2.0;
484 
485  // Close to the border -> reverting to INTER_NEAREST.
486  double value = map.atPosition("types", Position(-0.5,-1.2), InterpolationMethods::INTER_LINEAR);
487  EXPECT_DOUBLE_EQ(2.0, value);
488  // In between 1.0 and 2.0 field.
489  value = map.atPosition("types", Position(-0.5,0.0), InterpolationMethods::INTER_LINEAR);
490  EXPECT_DOUBLE_EQ(1.5, value);
491  // Calculated "by Hand".
492  value = map.atPosition("types", Position(0.69,0.38), InterpolationMethods::INTER_LINEAR);
493  EXPECT_NEAR(2.1963200, value, 0.0000001);
494 }
495 
496 } // namespace grid_map
void setGeometry(const Length &length, const double resolution, const Position &position=Position::Zero())
Definition: GridMap.cpp:44
GridMap getTransformedMap(const Eigen::Isometry3d &transform, const std::string &heightLayerName, const std::string &newFrameId, const double sampleRatio=0.0) const
Definition: GridMap.cpp:332
float & atPosition(const std::string &layer, const Position &position)
Definition: GridMap.cpp:153
void setBasicLayers(const std::vector< std::string > &basicLayers)
Definition: GridMap.cpp:65
const Index & getStartIndex() const
Definition: GridMap.cpp:669
const Matrix & get(const std::string &layer) const
Definition: GridMap.cpp:104
const Size & getSize() const
Definition: GridMap.cpp:661
const std::vector< std::string > & getLayers() const
Definition: GridMap.cpp:149
bool move(const Position &position, std::vector< BufferRegion > &newRegions)
Definition: GridMap.cpp:442
bool isInside(const Position &position) const
Definition: GridMap.cpp:236
bool addDataFrom(const GridMap &other, bool extendMap, bool overwriteData, bool copyAllLayers, std::vector< std::string > layers=std::vector< std::string >())
Definition: GridMap.cpp:514
Eigen::Vector2d Position
Definition: TypeDefs.hpp:18
bool isValid(const Index &index) const
Definition: GridMap.cpp:244
Eigen::Array2i Index
Definition: TypeDefs.hpp:22
Eigen::Array2d Length
Definition: TypeDefs.hpp:24
const std::string & getFrameId() const
Definition: GridMap.cpp:645
void add(const std::string &layer, const double value=NAN)
Definition: GridMap.cpp:82
bool exists(const std::string &layer) const
Definition: GridMap.cpp:100
bool getIndex(const Position &position, Index &index) const
Definition: GridMap.cpp:228
bool getPosition(const Index &index, Position &position) const
Definition: GridMap.cpp:232
TEST(PositionFromIndex, Simple)
const Length & getLength() const
Definition: GridMap.cpp:649


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