03_lanelet_map/main.cpp
Go to the documentation of this file.
1 #include <lanelet2_core/geometry/BoundingBox.h>
2 #include <lanelet2_core/geometry/Lanelet.h>
3 #include <lanelet2_core/geometry/Point.h>
4 #include <lanelet2_core/primitives/Lanelet.h>
5 
7 
8 #pragma GCC diagnostic ignored "-Wunused-variable"
9 
10 // we want assert statements to work in release mode
11 #undef NDEBUG
12 
16 void part4LaneletSubmaps();
17 
18 int main() {
19  // this tutorial shows you what LaneletMaps are and how they are supposed to be used.
24  return 0;
25 }
26 
28  using namespace lanelet;
29  // lanelet maps are actually simply a container for all of lanelets primitives. They are the core object of
30  // exchanging whole maps or parts of it. For that, they offer different ways of querying data (we will get to that).
31 
32  LaneletMap map = examples::getALaneletMap(); // we talk about creation later
33 
34  // Lanelet maps are arranged into layers, one for each primitive type:
35  PointLayer& points = map.pointLayer;
36  LineStringLayer& linestrings = map.lineStringLayer;
37 
38  // every layer behaves similar to an unordered map: we can iterate over the primitives or look them up by their id:
39  assert(points.size() > 1);
40  Point3d aPoint = *points.begin();
41  Point3d samePoint = *points.find(aPoint.id());
42  assert(samePoint == aPoint);
43  assert(points.exists(aPoint.id()));
44 
45  // we can do the same thing for the other layers, but it is completely the same thing
46  assert(!linestrings.empty());
47 
48  // maps can not be copied (they are too big for that), but they can be moved:
49  LaneletMap newMap = std::move(map);
50  // map.exists(aPoint.id()); // map is no longer valid after move!
51  assert(newMap.pointLayer.exists(aPoint.id()));
52 
53  // or be passed around as a pointer:
54  LaneletMapUPtr mapPtr = std::make_unique<LaneletMap>(std::move(newMap));
55 
56  // there is also the concept of constness for lanelet maps: const maps return const primitives.
57  const LaneletMap& constMap = *mapPtr;
58  ConstPoint3d aConstPoint = *constMap.pointLayer.begin();
59  assert(aConstPoint == aPoint);
60 }
61 
63  using namespace lanelet;
64  // Maps can be created from in two ways: either by adding data to them one by one, or by creating them directly from
65  // multiple objects:
66  LaneletMap laneletMap;
67 
69  laneletMap.add(lanelet);
70  assert(laneletMap.laneletLayer.size() == 1);
71 
72  // when you add an object, all the things that belong to it (points, linestrings, regulatory elements) are added as
73  // well:
74  assert(!laneletMap.pointLayer.empty());
75  assert(laneletMap.pointLayer.exists(lanelet.leftBound().front().id()));
76 
77  // we have not introduced InvalId (=0) yet. This id can be used to indicate that a primitive is not part of a map
78  // yet. When you add objects with InvalId, LaneletMap will automatically assign an id for them.
79  Point3d invalPoint1(InvalId, 0, 0, 0);
80  Point3d invalPoint2(InvalId, 1, 0, 0);
81  LineString3d invalLs(InvalId, {invalPoint1, invalPoint2});
82  laneletMap.add(invalLs);
83  assert(invalPoint1.id() != InvalId);
84 
85  // however if you want to create a new map from lots of primitives, the add function is not the right choice. The
86  // underlying trees have to be updated (and potentially rebalanced) each time something is added. For efficiently
87  // creating a map from multiple objects, you can use the createMap utility function:
89  LaneletMapUPtr laneletsMap = utils::createMap(lanelets);
90  assert(laneletsMap->laneletLayer.exists(lanelets.front().id()));
91 }
92 
94  using namespace lanelet;
95  // apart from getting primitives by their ID, a lanelet map offers two more ways of querying data: By their
96  // relation and by their position.
97  LaneletMap laneletMap = examples::getALaneletMap();
98  Lanelet mapLanelet = *laneletMap.laneletLayer.begin();
99  TrafficLight::Ptr trafficLight = mapLanelet.regulatoryElementsAs<TrafficLight>().front();
100 
101  // by their relation means we can query elements based on the things that they own. Linestrings by their points,
102  // lanelets and areas by their linestrings or regulatory elements, regulatory elements by anything of the above:
103  // find lanelets with linestrings
104  auto laneletsOwningLinestring = laneletMap.laneletLayer.findUsages(mapLanelet.leftBound());
105  assert(laneletsOwningLinestring.size() == 1 && laneletsOwningLinestring.front() == mapLanelet);
106  // find regelems with linestrings
107  auto regelemsOwningLs =
108  laneletMap.regulatoryElementLayer.findUsages(*trafficLight->trafficLights().front().lineString());
109  assert(regelemsOwningLs.size() == 1 && regelemsOwningLs.front() == trafficLight);
110  // find lanelets with regelems
111  auto laneletsOwningRegelems = laneletMap.laneletLayer.findUsages(trafficLight);
112  assert(!laneletsOwningRegelems.empty());
113 
114  // spacially means we can find primitives with geometrical queries. Because internally all primitives are stored as
115  // bounding boxes, these queries only return the primitive with respect to their *bounding box*.
116  Lanelets lanelets = laneletMap.laneletLayer.nearest(BasicPoint2d(0, 0), 1); // 1 means the nearest "1" lanelets
117  assert(!lanelets.empty()); // lanelets holds the lanelet with the closest bounding box
118 
119  // to get the actually closest lanelets use this utility function:
120  std::vector<std::pair<double, Lanelet>> actuallyNearestLanelets =
121  geometry::findNearest(laneletMap.laneletLayer, BasicPoint2d(0, 0), 1);
122  assert(!actuallyNearestLanelets.empty());
123 
124  // finally we can get primitives using a search region (this also runs on the bounding boxes):
125  Lanelets inRegion = laneletMap.laneletLayer.search(BoundingBox2d(BasicPoint2d(0, 0), BasicPoint2d(10, 10)));
126  assert(!inRegion.empty()); // inRegion contains all lanelets whose bounding boxes intersect with the query
127 
128  // for advanced usage, there are the searchUntil and nearestUntil functions. You pass it a function that is called
129  // with primitives with increasing bounding box distance until the function returns true. This is then the returned
130  // primitive:
131 
132  // in this example we get the first lanelet whose bounding box distance is >3m distance to the query point
133  BasicPoint2d searchPoint = BasicPoint2d(10, 10);
134  // the search func is called with the bounding box of a primitive and the primitive itself
135  auto searchFunc = [&searchPoint](const BoundingBox2d& lltBox, const Lanelet& /*llt*/) {
136  return geometry::distance(searchPoint, lltBox) > 3;
137  };
138  Optional<Lanelet> lanelet = laneletMap.laneletLayer.nearestUntil(searchPoint, searchFunc);
139  assert(!!lanelet && geometry::distance(geometry::boundingBox2d(*lanelet), searchPoint) > 3);
140 }
141 
143  using namespace lanelet;
144  // While LaneletMap has the property that when an element is added, all the things referenced by it are added as well,
145  // LaneletSubmap does not have this property. This can be useful if you want to avoid that if you add a Lanelet, all
146  // Lanelets referenced by its RegulatoryElements are added as well. Apart from that, basically everything you can do
147  // with a LaneletMap can also be done with a LaneletSubmap:
148  LaneletSubmap submap{examples::getALaneletMap()}; // it can be constructed (moved) from an existing map
149 
150  // you can search its layers
151  Lanelets inRegion = submap.laneletLayer.search(BoundingBox2d(BasicPoint2d(0, 0), BasicPoint2d(10, 10)));
152 
153  // you can create new submaps from some elements
154  LaneletSubmapUPtr newSubmap = utils::createSubmap(inRegion);
155 
156  // but this submap will not contain any elements except for the ones you explicitly added
157  assert(newSubmap->pointLayer.empty());
158  assert(newSubmap->size() == inRegion.size());
159 
160  // ... unless you convert back into a laneletMap. This will again contain all primitives:
161  LaneletMapUPtr newMap = newSubmap->laneletMap();
162  assert(!newMap->pointLayer.empty());
163 }
lanelet::InvalId
constexpr Id InvalId
lanelet::LaneletMapLayers::laneletLayer
LaneletLayer laneletLayer
PrimitiveLayer< Point3d >::begin
iterator begin()
lanelet::utils::createSubmap
LaneletSubmapUPtr createSubmap(const Areas &fromAreas)
lanelet
lanelet::utils::createMap
LaneletMapUPtr createMap(const Areas &fromAreas)
lanelet::LaneletMap::add
void add(Area area)
lanelet::LaneletMapLayers::pointLayer
PointLayer pointLayer
lanelet::LaneletLayer::findUsages
Lanelets findUsages(const RegulatoryElementConstPtr &regElem)
part4LaneletSubmaps
void part4LaneletSubmaps()
Definition: 03_lanelet_map/main.cpp:142
lanelet::examples::getALanelet
Lanelet getALanelet()
Definition: ExampleHelpers.h:32
Lanelets
std::vector< Lanelet > Lanelets
lanelet::LaneletMapLayers::regulatoryElementLayer
RegulatoryElementLayer regulatoryElementLayer
lanelet::examples::getALaneletMap
LaneletMap getALaneletMap()
Definition: ExampleHelpers.h:43
lanelet::PrimitiveLayer::findUsages
std::vector< PrimitiveT > findUsages(const traits::ConstPrimitiveType< traits::OwnedT< PrimitiveT >> &primitive)
lanelet::BoundingBox2d
LaneletMapUPtr
std::unique_ptr< LaneletMap > LaneletMapUPtr
lanelet::ConstPoint3d
lanelet::LaneletMap
Optional
boost::optional< T > Optional
lanelet::Lanelet
lanelet::TrafficLight::Ptr
std::shared_ptr< TrafficLight > Ptr
lanelet::TrafficLight
PrimitiveLayer< Point3d >
part3QueryingInformation
void part3QueryingInformation()
Definition: 03_lanelet_map/main.cpp:93
part2CreatingLaneletMaps
void part2CreatingLaneletMaps()
Definition: 03_lanelet_map/main.cpp:62
main
int main()
Definition: 03_lanelet_map/main.cpp:18
ExampleHelpers.h
PrimitiveLayer< Lanelet >::nearestUntil
OptConstPrimitiveT nearestUntil(const BasicPoint2d &point, const ConstSearchFunction &func) const
map
map
PrimitiveLayer< LineString3d >::empty
bool empty() const
lanelet::BasicPoint2d
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
lanelet::Point3d
lanelet::geometry::findNearest
std::vector< std::pair< double, traits::ConstPrimitiveType< PrimT > > > findNearest(const PrimitiveLayer< PrimT > &map, const BasicPoint2d &pt, unsigned count)
PrimitiveLayer< Lanelet >::nearest
PrimitiveVec nearest(const BasicPoint2d &point, unsigned n)
lanelet::geometry::boundingBox2d
IfAr< AreaT, BoundingBox2d > boundingBox2d(const AreaT &area)
PrimitiveLayer< Point3d >::size
size_t size() const
PrimitiveLayer< Point3d >::exists
bool exists(Id id) const
lanelet::LaneletSubmap
PrimitiveLayer< Lanelet >::search
PrimitiveVec search(const BoundingBox2d &area)
LaneletSubmapUPtr
std::unique_ptr< LaneletSubmap > LaneletSubmapUPtr
lanelet::Lanelet::leftBound
LineString3d leftBound()
PrimitiveLayer< Point3d >::find
iterator find(Id id)
lanelet::LineString3d
ConstPrimitive< PointData >::id
Id id() const noexcept
part1AboutLaneletMaps
void part1AboutLaneletMaps()
Definition: 03_lanelet_map/main.cpp:27
lanelet::Lanelet::regulatoryElementsAs
std::vector< std::shared_ptr< RegElemT > > regulatoryElementsAs()


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