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
lanelet::examples::getAPolygon
Polygon3d getAPolygon()
Definition: ExampleHelpers.h:17
LaneletMap.h
lanelet
lanelet::utils::createMap
LaneletMapUPtr createMap(const Areas &fromAreas)
lanelet::RegulatoryElementPtr
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
p2
BasicPoint p2
lanelet::utils::getId
Id getId()
lanelet::examples::getALanelet
Lanelet getALanelet()
Definition: ExampleHelpers.h:32
lanelet::examples::getARegulatoryElement
RegulatoryElementPtr getARegulatoryElement()
Definition: ExampleHelpers.h:38
right
BasicPolygon3d right
lanelet::examples::getALaneletMap
LaneletMap getALaneletMap()
Definition: ExampleHelpers.h:43
BasicRegulatoryElements.h
lanelet::Area
lanelet::LaneletMap
lanelet::Lanelet
lanelet::LineString3d::invert
LineString3d invert() const noexcept
p1
BasicPoint p1
lanelet::examples::getLineStringAtY
LineString3d getLineStringAtY(double y)
Definition: ExampleHelpers.h:12
lanelet::Point3d
left
BasicPolygon3d left
lanelet::Polygon3d
lanelet::examples::getAnArea
Area getAnArea()
Definition: ExampleHelpers.h:24
lanelet::examples::getLineStringAtX
LineString3d getLineStringAtX(double x)
Definition: ExampleHelpers.h:7
lanelet::LineString3d
lanelet::TrafficLight::make
static Ptr make(Id id, const AttributeMap &attributes, const LineStringsOrPolygons3d &trafficLights, const Optional< LineString3d > &stopLine={})


lanelet2_examples
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:15