ExampleHelpers.h
Go to the documentation of this file.
3 #include <lanelet2_core/primitives/LineString.h>
4 
5 namespace lanelet {
6 namespace examples {
7 inline LineString3d getLineStringAtX(double x) {
8  return LineString3d(utils::getId(), {Point3d{utils::getId(), x, 0, 0}, Point3d{utils::getId(), x, 1, 0},
9  Point3d{utils::getId(), x, 2, 0}});
10 }
11 
12 inline LineString3d getLineStringAtY(double y) {
13  return LineString3d(utils::getId(), {Point3d{utils::getId(), 0, y, 0}, Point3d{utils::getId(), 1, y, 0},
14  Point3d{utils::getId(), 2, y, 0}});
15 }
16 
18  Point3d p1{utils::getId(), 0, 0, 0};
19  Point3d p2{utils::getId(), 2, 0, 0};
20  Point3d p3{utils::getId(), 2, -2, 0};
21  return Polygon3d(utils::getId(), {p1, p2, p3});
22 }
23 
24 inline Area getAnArea() {
29  return Area(utils::getId(), {top, right, bottom, left});
30 }
31 
32 inline Lanelet getALanelet() {
35  return Lanelet(utils::getId(), left, right);
36 }
37 
39  LineString3d trafficLight = examples::getLineStringAtX(3);
40  return TrafficLight::make(utils::getId(), {}, {trafficLight});
41 }
42 
44  auto area = getAnArea();
45  auto lanelet = getALanelet();
46  lanelet.addRegulatoryElement(getARegulatoryElement());
47  return std::move(*utils::createMap({lanelet}, {area}));
48 }
49 } // namespace examples
50 } // namespace lanelet
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
static Ptr make(Id id, const AttributeMap &attributes, const LineStringsOrPolygons3d &trafficLights, const Optional< LineString3d > &stopLine={})
Polygon3d getAPolygon()
Lanelet getALanelet()
LaneletMap getALaneletMap()
BasicPolygon3d right
BasicPolygon3d left
BasicPoint p2
RegulatoryElementPtr getARegulatoryElement()
LineString3d getLineStringAtY(double y)
BasicPoint p1
LineString3d invert() const noexcept
LaneletMapUPtr createMap(const Points3d &fromPoints)
LineString3d getLineStringAtX(double x)
Definition: ExampleHelpers.h:7


lanelet2_examples
Author(s): Fabian Poggenhans
autogenerated on Tue Jun 6 2023 02:24:00