test_area.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
2 
8 
9 using namespace lanelet;
10 
11 /* 1 f1 3 s1 5 tl1 7
12  * X------>X------>X------>X
13  * | llU |
14  * |f2 h |s2 llF
15  * a1/3 V a2/4 V
16  * X<------X<------X------>X
17  * 2 f3 4 s3 6 tl2 8
18  *
19  * llB/R
20  * X-------X
21  * rightLine
22  * y ^
23  * |
24  * O--->
25  * x
26  */
27 class TestArea : public testing::Test {
28  public:
30  for (auto i = 0u; i < 4; ++i) {
31  pointsLeft.push_back(Point3d(++id, i, 1)); // 1, 3, 5, 7
32  pointsRight.push_back(Point3d(++id, i, 0)); // 2, 4, 6, 8
33  }
34  firstCircle = LineString3d(++id, {pointsLeft[0], pointsLeft[1], pointsRight[1], pointsRight[0]}); // 9
35  firstCircle1 = LineString3d(++id, {pointsLeft[0], pointsLeft[1]}); // 10
36  firstCircle2 = LineString3d(++id, {pointsLeft[1], pointsRight[1]}); // 11
37  firstCircle3 = LineString3d(++id, {pointsRight[1], pointsRight[0]}); // 12
38  secondCircle1 = LineString3d(++id, {pointsLeft[1], pointsLeft[2]}); // 13
39  secondCircle2 = LineString3d(++id, {pointsLeft[2], pointsRight[2]}); // 14
40  secondCircle3 = LineString3d(++id, {pointsRight[2], pointsRight[1]}); // 15
41  auto holeId = ++id; // 16
42  hole = LineString3d(holeId, {Point3d(++id, 1.25, 0.25), Point3d(++id, 1.75, 0.25), Point3d(++id, 1.75, 0.75),
43  Point3d(++id, 1.25, 0.75)}); // 17, 18, 19, 20
44  thirdLine1 = LineString3d(++id, {pointsLeft[2], pointsLeft[3]}); // 21
45  thirdLine2 = LineString3d(++id, {pointsRight[2], pointsRight[3]}); // 22
46  auto lineId = ++id; // 23
47  rightLine = LineString3d(lineId, {Point3d(++id, 1, -1), Point3d(++id, 2, -1)}); // 24, 25
48  area1 = Area(++id, {firstCircle}); // 26
49  area2 = Area(++id, {secondCircle1, secondCircle2, secondCircle3}, {{hole}}); // 27
50  area3 = Area(++id, {firstCircle1, firstCircle2, firstCircle3}); // 28
51  area4 = Area(++id, {secondCircle1, secondCircle2, secondCircle3, firstCircle2.invert()}); // 29
52  laneletFollowing = Lanelet(++id, thirdLine1, thirdLine2); // 30
53  laneletRight = Lanelet(++id, secondCircle2.invert(), rightLine); // 31
54  regelem = std::make_shared<GenericRegulatoryElement>(++id); // 32
55  laneletBelow = Lanelet(++id, secondCircle3.invert(), rightLine); // 33
56  laneletUpwards = Lanelet(++id, firstCircle2.invert(), secondCircle2.invert()); // 34
57  }
58 
59  Id id{0};
60  Points3d pointsLeft, pointsRight;
61  LineString3d firstCircle, firstCircle1, firstCircle2, firstCircle3, secondCircle1, secondCircle2, secondCircle3, hole,
62  thirdLine1, thirdLine2, rightLine;
63  Area area1, area2, area3, area4;
64  Lanelet laneletFollowing, laneletRight, laneletBelow, laneletUpwards;
66 };
67 
68 TEST_F(TestArea, attributes) { // NOLINT
69  area1.attributes()["test"] = true;
70  EXPECT_TRUE(area1.attributeOr("test", false));
71  EXPECT_TRUE(area1.hasAttribute("test"));
72 }
73 
74 TEST_F(TestArea, id) { // NOLINT
75  area1.setId(123);
76  EXPECT_EQ(area1.id(), 123);
77 }
78 
79 TEST_F(TestArea, regelem) { // NOLINT
80  area1.addRegulatoryElement(regelem);
81  EXPECT_EQ(1ul, area1.regulatoryElementsAs<GenericRegulatoryElement>().size());
82  area1.removeRegulatoryElement(regelem);
83  EXPECT_TRUE(area1.regulatoryElementsAs<GenericRegulatoryElement>().empty());
84 }
85 
86 TEST_F(TestArea, inside) { // NOLINT
87  EXPECT_TRUE(geometry::inside(area1, BasicPoint2d(0.5, 0.5)));
88  EXPECT_FALSE(geometry::inside(area2, BasicPoint2d(0.5, 0.5)));
89  EXPECT_FALSE(geometry::inside(area2, BasicPoint2d(1.5, 0.5)));
90 }
91 
92 TEST_F(TestArea, distance2d) { // NOLINT
93  auto d = geometry::distance2d(area2, utils::to2D(pointsLeft[3].basicPoint()));
94  EXPECT_DOUBLE_EQ(1, d);
95 }
96 
97 TEST_F(TestArea, distance2dWithHole) { // NOLINT
98  auto d = geometry::distance2d(area2, BasicPoint2d(1.5, 0.5));
99  EXPECT_DOUBLE_EQ(0.25, d);
100 }
101 
102 TEST_F(TestArea, distance3dWithHole) { // NOLINT
103  auto d = geometry::distance3d(area2, BasicPoint3d(1.5, 0.5, 1));
104  EXPECT_DOUBLE_EQ(std::sqrt(0.25 * 0.25 + 1), d);
105 }
106 
107 TEST_F(TestArea, area) { // NOLINT
108  auto area = geometry::area(area1.basicPolygonWithHoles2d());
109  EXPECT_DOUBLE_EQ(1, area);
110 }
111 
112 TEST_F(TestArea, areaWithHole) { // NOLINT
113  auto area = geometry::area(area2.basicPolygonWithHoles2d());
114  EXPECT_DOUBLE_EQ(0.75, area);
115 }
116 
117 TEST_F(TestArea, boundingBox) { // NOLINT
118  auto box = geometry::boundingBox2d(area2);
119  EXPECT_EQ(box.min().x(), 1);
120  EXPECT_EQ(box.max().x(), 2);
121 }
122 
123 TEST_F(TestArea, adjacent) { // NOLINT
124  EXPECT_TRUE(geometry::adjacent(area2, area1));
125  EXPECT_TRUE(geometry::adjacent(area1, area2));
126  area1.setOuterBound(area2.outerBound());
127  EXPECT_FALSE(geometry::adjacent(area1, area2));
128 }
129 
130 TEST_F(TestArea, overlaps) { // NOLINT
131  EXPECT_FALSE(geometry::overlaps2d(area2, area1));
132  EXPECT_FALSE(geometry::overlaps3d(area2, area1, 1));
133  EXPECT_FALSE(geometry::overlaps2d(area2, laneletRight));
134  EXPECT_FALSE(geometry::overlaps3d(area2, laneletFollowing, 1));
135 }
136 
137 TEST_F(TestArea, follows) { // NOLINT
138  EXPECT_TRUE(geometry::follows(area2, laneletFollowing));
139  EXPECT_TRUE(geometry::follows(laneletFollowing.invert(), area2));
140  EXPECT_FALSE(geometry::follows(laneletFollowing, area2));
141  EXPECT_FALSE(geometry::follows(laneletFollowing, area1));
142 }
143 
144 TEST_F(TestArea, leftOf) { // NOLINT
145  EXPECT_TRUE(geometry::leftOf(laneletRight, area2));
146  EXPECT_FALSE(geometry::leftOf(laneletRight.invert(), area2));
147  EXPECT_FALSE(geometry::leftOf(laneletRight, area1));
148 }
149 
150 TEST_F(TestArea, rightOf) { // NOLINT
151  EXPECT_FALSE(geometry::rightOf(laneletRight, area2));
152  EXPECT_TRUE(geometry::rightOf(laneletRight.invert(), area2));
153  EXPECT_FALSE(geometry::rightOf(laneletRight, area1));
154 }
155 
157  auto res = geometry::determineCommonLinePreceding(laneletFollowing.invert(), area2);
158  ASSERT_TRUE(!!res);
159  EXPECT_EQ(res->id(), 14);
160  EXPECT_FALSE(!!geometry::determineCommonLinePreceding(laneletFollowing, area2));
161  EXPECT_FALSE(!!geometry::determineCommonLinePreceding(laneletFollowing.invert(), area1));
162 }
163 
165  auto res = geometry::determineCommonLineFollowing(area2, laneletFollowing);
166  ASSERT_TRUE(!!res);
167  EXPECT_EQ(res->id(), 14);
168  EXPECT_FALSE(!!geometry::determineCommonLineFollowing(area2, laneletFollowing.invert()));
169  EXPECT_FALSE(!!geometry::determineCommonLineFollowing(area1, laneletFollowing));
170 }
171 
173  auto res = geometry::determineCommonLineFollowingOrPreceding(area2, laneletFollowing);
174  ASSERT_TRUE(!!res);
175  EXPECT_EQ(res->id(), 14);
176  res = geometry::determineCommonLineFollowingOrPreceding(area2, laneletFollowing.invert());
177  ASSERT_TRUE(!!res);
178  EXPECT_EQ(res->id(), 14);
179  EXPECT_FALSE(!!geometry::determineCommonLineFollowingOrPreceding(area1, laneletFollowing.invert()));
180  EXPECT_FALSE(!!geometry::determineCommonLineFollowingOrPreceding(area1, laneletFollowing));
181  EXPECT_FALSE(!!geometry::determineCommonLineFollowingOrPreceding(area2, laneletRight));
182  EXPECT_FALSE(!!geometry::determineCommonLineFollowingOrPreceding(area1, laneletBelow));
183  EXPECT_FALSE(!!geometry::determineCommonLineFollowingOrPreceding(area2, laneletBelow));
184 }
185 
187  auto res = geometry::determineCommonLineLeft(laneletUpwards, area3);
188  ASSERT_TRUE(!!res);
189  EXPECT_EQ(res->id(), 11);
190  EXPECT_TRUE(res->inverted());
191  EXPECT_FALSE(!!geometry::determineCommonLineLeft(laneletUpwards, area2));
192  EXPECT_FALSE(!!geometry::determineCommonLineLeft(laneletUpwards, area4));
193 }
194 
196  auto res = geometry::determineCommonLineRight(laneletUpwards.invert(), area3);
197  ASSERT_TRUE(!!res);
198  EXPECT_EQ(res->id(), 11);
199  EXPECT_FALSE(res->inverted());
200  EXPECT_FALSE(!!geometry::determineCommonLineRight(laneletUpwards.invert(), area2));
201  EXPECT_FALSE(!!geometry::determineCommonLineRight(laneletUpwards.invert(), area4));
202 }
203 
204 TEST_F(TestArea, determineCommonLineSidewaysLanelet) {
205  auto res = geometry::determineCommonLineSideways(laneletUpwards, area3);
206  ASSERT_TRUE(!!res);
207  EXPECT_EQ(res->id(), 11);
208  EXPECT_TRUE(res->inverted());
209  res = geometry::determineCommonLineSideways(laneletUpwards.invert(), area3);
210  ASSERT_TRUE(!!res);
211  EXPECT_EQ(res->id(), 11);
212  EXPECT_FALSE(res->inverted());
213  EXPECT_FALSE(!!geometry::determineCommonLineSideways(laneletUpwards, area2));
214  EXPECT_FALSE(!!geometry::determineCommonLineSideways(laneletUpwards, area4));
215 }
216 
217 TEST_F(TestArea, determineCommonLineSidewaysArea) {
218  auto res = geometry::determineCommonLineSideways(area3, laneletUpwards);
219  ASSERT_TRUE(!!res);
220  EXPECT_EQ(res->id(), 11);
221  EXPECT_FALSE(res->inverted());
222  res = geometry::determineCommonLineSideways(area3, laneletUpwards.invert());
223  ASSERT_TRUE(!!res);
224  EXPECT_EQ(res->id(), 11);
225  EXPECT_FALSE(res->inverted());
226  EXPECT_FALSE(!!geometry::determineCommonLineSideways(area2, laneletUpwards));
227  EXPECT_FALSE(!!geometry::determineCommonLineSideways(area4, laneletUpwards));
228 }
229 
230 TEST_F(TestArea, determineCommonLineInArea) {
231  auto res = geometry::determineCommonLine(area2, laneletBelow);
232  ASSERT_TRUE(!!res);
233  EXPECT_EQ(res->id(), 15);
234  EXPECT_FALSE(res->inverted());
235  res = geometry::determineCommonLine(area2, laneletFollowing);
236  ASSERT_TRUE(!!res);
237  EXPECT_EQ(res->id(), 14);
238  EXPECT_FALSE(res->inverted());
239 }
240 
241 TEST_F(TestArea, determineCommonLineInAreaInverted) {
242  auto res = geometry::determineCommonLine(area2, laneletBelow.invert());
243  ASSERT_TRUE(!!res);
244  EXPECT_EQ(res->id(), 15);
245  EXPECT_FALSE(res->inverted());
246  res = geometry::determineCommonLine(area2, laneletFollowing.invert());
247  ASSERT_TRUE(!!res);
248  EXPECT_EQ(res->id(), 14);
249  EXPECT_FALSE(res->inverted());
250 }
251 
252 TEST_F(TestArea, determineCommonLineArea) {
253  auto res = geometry::determineCommonLine(area3, area4);
254  ASSERT_TRUE(!!res);
255  EXPECT_EQ(res->id(), 11);
256  EXPECT_FALSE(res->inverted());
257  res = geometry::determineCommonLine(area4, area3);
258  ASSERT_TRUE(!!res);
259  EXPECT_EQ(res->id(), 11);
260  EXPECT_TRUE(res->inverted());
261 }
IfAr< AreaT, bool > inside(const AreaT &area, const BasicPoint2d &point)
Checks whether a point is within or at the border of a area.
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
Definition: Forward.h:192
TEST_F(TestArea, attributes)
Definition: test_area.cpp:68
bool rightOf(const ConstLanelet &left, const ConstArea &area)
Test whether area is right of lanelet.
Lanelet laneletUpwards
Definition: test_area.cpp:64
int64_t Id
Definition: Forward.h:198
Eigen::Vector3d BasicPoint3d
a simple 3d-point
bool follows(const ConstLanelet &prev, const ConstArea &next)
Test whether area follows lanelet.
Optional< ConstLineString3d > determineCommonLineFollowing(const ConstArea &ar, const ConstLanelet &ll)
The famous (mutable) lanelet class.
A GenericRegulatoryElement can hold any parameters.
Points3d pointsRight
Definition: test_area.cpp:60
Optional< ConstLineString3d > determineCommonLineFollowingOrPreceding(const ConstArea &ar, const ConstLanelet &ll)
std::vector< Point3d > Points3d
Definition: Forward.h:34
IfAr< AreaT, bool > overlaps2d(const AreaT &area, const AreaT &otherArea)
A normal 3d linestring with mutable data.
A mutable 3d point.
IfAr< AreaT, bool > overlaps3d(const AreaT &area, const AreaT &otherArea, double heightTolerance)
Optional< ConstLineString3d > determineCommonLineSideways(const ConstLanelet &ll, const ConstArea &ar)
bool empty() const
returns true if this object contains no parameters
Optional< ConstLineString3d > determineCommonLineRight(const ConstLanelet &left, const ConstArea &right)
IfAr< AreaT, BoundingBox2d > boundingBox2d(const AreaT &area)
calculates an up-right 2d bounding box
Optional< ConstLineString3d > determineCommonLinePreceding(const ConstLanelet &ll, const ConstArea &ar)
LineString3d thirdLine2
Definition: test_area.cpp:61
Optional< ConstLineString3d > determineCommonLine(const ConstArea &ar, const ConstLanelet &ll)
IfLS2< LineString3d1T, LineString3d2T, double > distance3d(const LineString3d1T &l1, const LineString3d2T &l2)
RegulatoryElementPtr regelem
Definition: test_area.cpp:65
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
a simple 2d-point
Famous Area class that represents a basic area as element of the map.
Id id
Definition: LaneletMap.cpp:63
LineString3d invert() const noexcept
create a new, inverted linestring from this one
Area area4
Definition: test_area.cpp:63
Optional< ConstLineString3d > determineCommonLineLeft(const ConstLanelet &right, const ConstArea &left)
bool adjacent(const ConstArea &area1, const ConstArea &area2)
Test if two areas are adjacent.
BoundingBox2d to2D(const BoundingBox3d &primitive)
size_t size() const
get the number of roles in this regulatoryElement
bool leftOf(const ConstLanelet &right, const ConstArea &left)
Test whether area is left of lanelet.
double distance2d(const RegulatoryElement &regElem, const BasicPoint2d &p)


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Tue Jun 6 2023 02:23:32