PolygonIteratorTest.cpp
Go to the documentation of this file.
1 /*
2  * PolygonIteratorTest.cpp
3  *
4  * Created on: Sep 19, 2014
5  * Author: Péter Fankhauser
6  * Institute: ETH Zurich, ANYbotics
7  */
8 
12 
13 // gtest
14 #include <gtest/gtest.h>
15 
16 // Vector
17 #include <vector>
18 
19 using grid_map::GridMap;
20 using grid_map::Length;
21 using grid_map::Polygon;
23 using grid_map::Position;
24 
25 TEST(PolygonIterator, FullCover) {
26  std::vector<std::string> types;
27  types.emplace_back("type");
28  GridMap map(types);
29  map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5)
30 
31  Polygon polygon;
32  polygon.addVertex(Position(-100.0, 100.0));
33  polygon.addVertex(Position(100.0, 100.0));
34  polygon.addVertex(Position(100.0, -100.0));
35  polygon.addVertex(Position(-100.0, -100.0));
36 
37  PolygonIterator iterator(map, polygon);
38 
39  EXPECT_FALSE(iterator.isPastEnd());
40  EXPECT_EQ(0, (*iterator)(0));
41  EXPECT_EQ(0, (*iterator)(1));
42 
43  ++iterator;
44  EXPECT_FALSE(iterator.isPastEnd());
45  EXPECT_EQ(0, (*iterator)(0));
46  EXPECT_EQ(1, (*iterator)(1));
47 
48  ++iterator;
49  EXPECT_FALSE(iterator.isPastEnd());
50  EXPECT_EQ(0, (*iterator)(0));
51  EXPECT_EQ(2, (*iterator)(1));
52 
53  for (int i = 0; i < 37; ++i) {
54  ++iterator;
55  }
56 
57  EXPECT_FALSE(iterator.isPastEnd());
58  EXPECT_EQ(7, (*iterator)(0));
59  EXPECT_EQ(4, (*iterator)(1));
60 
61  ++iterator;
62  EXPECT_TRUE(iterator.isPastEnd());
63 }
64 
66 {
67  GridMap map({"types"});
68  map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5)
69 
70  Polygon polygon;
71  polygon.addVertex(Position(99.0, 101.0));
72  polygon.addVertex(Position(101.0, 101.0));
73  polygon.addVertex(Position(101.0, 99.0));
74  polygon.addVertex(Position(99.0, 99.0));
75 
76  PolygonIterator iterator(map, polygon);
77 
78  EXPECT_TRUE(iterator.isPastEnd());
79 }
80 
82 {
83  GridMap map({"types"});
84  map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5)
85 
86  Polygon polygon;
87  polygon.addVertex(Position(-1.0, 1.5));
88  polygon.addVertex(Position(1.0, 1.5));
89  polygon.addVertex(Position(1.0, -1.5));
90  polygon.addVertex(Position(-1.0, -1.5));
91 
92  PolygonIterator iterator(map, polygon);
93 
94  EXPECT_FALSE(iterator.isPastEnd());
95  EXPECT_EQ(3, (*iterator)(0));
96  EXPECT_EQ(1, (*iterator)(1));
97 
98  ++iterator;
99  EXPECT_FALSE(iterator.isPastEnd());
100  EXPECT_EQ(3, (*iterator)(0));
101  EXPECT_EQ(2, (*iterator)(1));
102 
103  ++iterator;
104  EXPECT_FALSE(iterator.isPastEnd());
105  EXPECT_EQ(3, (*iterator)(0));
106  EXPECT_EQ(3, (*iterator)(1));
107 
108  ++iterator;
109  EXPECT_FALSE(iterator.isPastEnd());
110  EXPECT_EQ(4, (*iterator)(0));
111  EXPECT_EQ(1, (*iterator)(1));
112 
113  ++iterator;
114  EXPECT_FALSE(iterator.isPastEnd());
115  EXPECT_EQ(4, (*iterator)(0));
116  EXPECT_EQ(2, (*iterator)(1));
117 
118  ++iterator;
119  EXPECT_FALSE(iterator.isPastEnd());
120  EXPECT_EQ(4, (*iterator)(0));
121  EXPECT_EQ(3, (*iterator)(1));
122 
123  ++iterator;
124  EXPECT_TRUE(iterator.isPastEnd());
125 }
126 
127 TEST(PolygonIterator, TopLeftTriangle)
128 {
129  GridMap map({"types"});
130  map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5)
131 
132  Polygon polygon;
133  polygon.addVertex(Position(-40.1, 20.6));
134  polygon.addVertex(Position(40.1, 20.4));
135  polygon.addVertex(Position(-40.1, -20.6));
136 
137  PolygonIterator iterator(map, polygon);
138 
139  EXPECT_FALSE(iterator.isPastEnd());
140  EXPECT_EQ(0, (*iterator)(0));
141  EXPECT_EQ(0, (*iterator)(1));
142 
143  ++iterator;
144  EXPECT_FALSE(iterator.isPastEnd());
145  EXPECT_EQ(1, (*iterator)(0));
146  EXPECT_EQ(0, (*iterator)(1));
147 
148  // TODO Extend.
149 }
150 
152 {
153  GridMap map({"layer"});
154  map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5)
155  map.move(Position(2.0, 0.0));
156 
157  Polygon polygon;
158  polygon.addVertex(Position(6.1, 1.6));
159  polygon.addVertex(Position(0.9, 1.6));
160  polygon.addVertex(Position(0.9, -1.6));
161  polygon.addVertex(Position(6.1, -1.6));
162  PolygonIterator iterator(map, polygon);
163 
164  EXPECT_FALSE(iterator.isPastEnd());
165  EXPECT_EQ(6, (*iterator)(0));
166  EXPECT_EQ(1, (*iterator)(1));
167 
168  ++iterator;
169  EXPECT_FALSE(iterator.isPastEnd());
170  EXPECT_EQ(6, (*iterator)(0));
171  EXPECT_EQ(2, (*iterator)(1));
172 
173  for (int i = 0; i < 4; ++i) {
174  ++iterator;
175  }
176 
177  EXPECT_FALSE(iterator.isPastEnd());
178  EXPECT_EQ(7, (*iterator)(0));
179  EXPECT_EQ(3, (*iterator)(1));
180 
181  ++iterator;
182  EXPECT_FALSE(iterator.isPastEnd());
183  EXPECT_EQ(0, (*iterator)(0));
184  EXPECT_EQ(1, (*iterator)(1));
185 
186  for (int i = 0; i < 8; ++i) {
187  ++iterator;
188  }
189 
190  EXPECT_FALSE(iterator.isPastEnd());
191  EXPECT_EQ(2, (*iterator)(0));
192  EXPECT_EQ(3, (*iterator)(1));
193 
194  ++iterator;
195  EXPECT_TRUE(iterator.isPastEnd());
196 }
void setGeometry(const Length &length, const double resolution, const Position &position=Position::Zero())
Definition: GridMap.cpp:44
Eigen::Vector2d Position
Definition: TypeDefs.hpp:18
TEST(PolygonIterator, FullCover)
void addVertex(const Position &vertex)
Definition: Polygon.cpp:44
Eigen::Array2d Length
Definition: TypeDefs.hpp:24


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