1 #include <gtest/gtest.h> 30 for (
auto i = 0u; i < 4; ++i) {
31 pointsLeft.push_back(
Point3d(++
id, i, 1));
32 pointsRight.push_back(
Point3d(++
id, i, 0));
34 firstCircle =
LineString3d(++
id, {pointsLeft[0], pointsLeft[1], pointsRight[1], pointsRight[0]});
35 firstCircle1 =
LineString3d(++
id, {pointsLeft[0], pointsLeft[1]});
36 firstCircle2 =
LineString3d(++
id, {pointsLeft[1], pointsRight[1]});
37 firstCircle3 =
LineString3d(++
id, {pointsRight[1], pointsRight[0]});
38 secondCircle1 =
LineString3d(++
id, {pointsLeft[1], pointsLeft[2]});
39 secondCircle2 =
LineString3d(++
id, {pointsLeft[2], pointsRight[2]});
40 secondCircle3 =
LineString3d(++
id, {pointsRight[2], pointsRight[1]});
42 hole =
LineString3d(holeId, {
Point3d(++
id, 1.25, 0.25),
Point3d(++
id, 1.75, 0.25),
Point3d(++
id, 1.75, 0.75),
44 thirdLine1 =
LineString3d(++
id, {pointsLeft[2], pointsLeft[3]});
45 thirdLine2 =
LineString3d(++
id, {pointsRight[2], pointsRight[3]});
48 area1 =
Area(++
id, {firstCircle});
49 area2 =
Area(++
id, {secondCircle1, secondCircle2, secondCircle3}, {{hole}});
50 area3 =
Area(++
id, {firstCircle1, firstCircle2, firstCircle3});
51 area4 =
Area(++
id, {secondCircle1, secondCircle2, secondCircle3, firstCircle2.
invert()});
52 laneletFollowing =
Lanelet(++
id, thirdLine1, thirdLine2);
53 laneletRight =
Lanelet(++
id, secondCircle2.
invert(), rightLine);
54 regelem = std::make_shared<GenericRegulatoryElement>(++
id);
55 laneletBelow =
Lanelet(++
id, secondCircle3.invert(), rightLine);
61 LineString3d firstCircle, firstCircle1, firstCircle2, firstCircle3, secondCircle1, secondCircle2, secondCircle3, hole,
69 area1.attributes()[
"test"] =
true;
70 EXPECT_TRUE(area1.attributeOr(
"test",
false));
71 EXPECT_TRUE(area1.hasAttribute(
"test"));
76 EXPECT_EQ(area1.id(), 123);
80 area1.addRegulatoryElement(regelem);
82 area1.removeRegulatoryElement(regelem);
94 EXPECT_DOUBLE_EQ(1,
d);
99 EXPECT_DOUBLE_EQ(0.25,
d);
104 EXPECT_DOUBLE_EQ(std::sqrt(0.25 * 0.25 + 1),
d);
108 auto area = geometry::area(area1.basicPolygonWithHoles2d());
109 EXPECT_DOUBLE_EQ(1, area);
113 auto area = geometry::area(area2.basicPolygonWithHoles2d());
114 EXPECT_DOUBLE_EQ(0.75, area);
119 EXPECT_EQ(box.min().x(), 1);
120 EXPECT_EQ(box.max().x(), 2);
126 area1.setOuterBound(area2.outerBound());
159 EXPECT_EQ(res->id(), 14);
167 EXPECT_EQ(res->id(), 14);
175 EXPECT_EQ(res->id(), 14);
178 EXPECT_EQ(res->id(), 14);
189 EXPECT_EQ(res->id(), 11);
190 EXPECT_TRUE(res->inverted());
198 EXPECT_EQ(res->id(), 11);
199 EXPECT_FALSE(res->inverted());
207 EXPECT_EQ(res->id(), 11);
208 EXPECT_TRUE(res->inverted());
211 EXPECT_EQ(res->id(), 11);
212 EXPECT_FALSE(res->inverted());
220 EXPECT_EQ(res->id(), 11);
221 EXPECT_FALSE(res->inverted());
224 EXPECT_EQ(res->id(), 11);
225 EXPECT_FALSE(res->inverted());
233 EXPECT_EQ(res->id(), 15);
234 EXPECT_FALSE(res->inverted());
237 EXPECT_EQ(res->id(), 14);
238 EXPECT_FALSE(res->inverted());
244 EXPECT_EQ(res->id(), 15);
245 EXPECT_FALSE(res->inverted());
248 EXPECT_EQ(res->id(), 14);
249 EXPECT_FALSE(res->inverted());
255 EXPECT_EQ(res->id(), 11);
256 EXPECT_FALSE(res->inverted());
259 EXPECT_EQ(res->id(), 11);
260 EXPECT_TRUE(res->inverted());
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
TEST_F(TestArea, attributes)
bool rightOf(const ConstLanelet &left, const ConstArea &area)
Test whether area is right of lanelet.
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.
Optional< ConstLineString3d > determineCommonLineFollowingOrPreceding(const ConstArea &ar, const ConstLanelet &ll)
std::vector< Point3d > Points3d
IfAr< AreaT, bool > overlaps2d(const AreaT &area, const AreaT &otherArea)
A normal 3d linestring with mutable data.
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)
Optional< ConstLineString3d > determineCommonLine(const ConstArea &ar, const ConstLanelet &ll)
IfLS2< LineString3d1T, LineString3d2T, double > distance3d(const LineString3d1T &l1, const LineString3d2T &l2)
RegulatoryElementPtr regelem
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.
LineString3d invert() const noexcept
create a new, inverted linestring from this one
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 ®Elem, const BasicPoint2d &p)