Lanelet.cpp
Go to the documentation of this file.
2 
3 #include <boost/geometry/algorithms/equals.hpp>
4 
10 
11 namespace lanelet {
12 namespace bg = boost::geometry;
13 namespace bgi = boost::geometry::index;
14 using OptDistance = boost::optional<double>;
15 
16 namespace {
17 // gcc does not like boost optional in release builds
18 #pragma GCC diagnostic push
19 #pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
20 template <typename Point>
21 auto centerpoint(Point p1, Point p2) {
22  bg::add_point(p1, p2);
23  bg::multiply_value(p1, 0.5);
24  return p1;
25 }
26 
27 auto makeCenterpoint(const ConstPoint2d& p1, const ConstPoint2d& p2) {
28  return Point3d(InvalId, centerpoint(utils::to3D(p1).basicPoint(), utils::to3D(p2).basicPoint()));
29 }
30 
31 using SegmentTree = bgi::rtree<BasicSegment2d, bgi::linear<2>>;
32 using PointNode = std::pair<BasicPoint2d, ConstLineString2d::const_iterator>;
33 using PointTree = bgi::rtree<PointNode, bgi::linear<16>>;
34 
35 class BoundChecker {
36  public:
37  BoundChecker(const ConstLineString2d& left, const ConstLineString2d& right)
38  : leftSegments_{makeSegments(left)},
39  rightSegments_{makeSegments(right)},
40  leftPts_{makePoints(left)},
41  rightPts_{makePoints(right)},
42  entry_{right.front().basicPoint(), left.front().basicPoint()},
43  exit_{left.back().basicPoint(), right.back().basicPoint()} {}
44 
45  bool intersects(const BasicSegment2d& seg) const {
46  const bool result = intersectsLeft(seg) || intersectsRight(seg) || crossesEntry(seg) || crossesExit(seg);
47  return result;
48  }
49 
50  bool intersectsLeft(const BasicSegment2d& seg) const {
51  for (auto it = leftSegments_.qbegin(bgi::intersects(seg)); it != leftSegments_.qend(); ++it) {
52  if (!boost::geometry::equals(it->first, seg.first)) {
53  return true;
54  }
55  }
56  return false;
57  }
58 
59  bool intersectsRight(const BasicSegment2d& seg) const {
60  for (auto it = rightSegments_.qbegin(bgi::intersects(seg)); it != rightSegments_.qend(); ++it) {
61  if (!boost::geometry::equals(it->first, seg.first)) {
62  return true;
63  }
64  }
65  return false;
66  }
67 
68  bool secondCrossesBounds(const BasicSegment2d& seg, bool left) const {
69  const auto& segmentTree = left ? leftSegments_ : rightSegments_;
70  for (auto it = segmentTree.qbegin(bgi::intersects(seg)); it != segmentTree.qend(); ++it) {
71  using boost::geometry::equals;
72  if (!equals(it->first, seg.second) && !equals(it->second, seg.second)) {
73  return true;
74  }
75  }
76  return false;
77  }
78 
79  bool crossesEntry(const BasicSegment2d& seg) const {
80  if (geometry::intersects(seg, entry_)) {
81  return geometry::internal::pointIsLeftOf(entry_.first, entry_.second, seg.second);
82  }
83  return false;
84  }
85 
86  bool crossesExit(const BasicSegment2d& seg) const {
87  if (geometry::intersects(seg, exit_)) {
88  return geometry::internal::pointIsLeftOf(exit_.first, exit_.second, seg.second);
89  }
90  return false;
91  }
92 
93  template <typename Func>
94  void forEachNearestPointLeftUntil(ConstLineString2d::const_iterator iter, Func&& f) const {
95  return forEachNearestPointUntilImpl(iter, leftPts_, std::forward<Func>(f));
96  }
97  template <typename Func>
98  void forEachNearestPointRightUntil(ConstLineString2d::const_iterator iter, Func&& f) const {
99  return forEachNearestPointUntilImpl(iter, rightPts_, std::forward<Func>(f));
100  }
101 
102  private:
103  template <typename Func>
104  static void forEachNearestPointUntilImpl(ConstLineString2d::const_iterator iter, const PointTree& tree, Func&& f) {
105  for (auto qIt = tree.qbegin(boost::geometry::index::nearest(iter->basicPoint(), unsigned(tree.size())));
106  qIt != tree.qend(); ++qIt) {
107  if (f(qIt->second)) {
108  break;
109  }
110  }
111  }
112  static std::vector<PointNode> makePoints(const ConstLineString2d& ls) {
113  std::vector<PointNode> nodes;
114  nodes.reserve(ls.size());
115  for (auto it = ls.begin(); it != ls.end(); ++it) {
116  nodes.emplace_back(it->basicPoint(), it);
117  }
118  return nodes;
119  }
120  static std::vector<BasicSegment2d> makeSegments(const ConstLineString2d& line) {
121  std::vector<BasicSegment2d> segments;
122  segments.reserve(line.numSegments());
123  auto makeSegment = [](const auto& seg) { return BasicSegment2d(seg.first.basicPoint(), seg.second.basicPoint()); };
124  for (auto i = 0u; i < line.numSegments(); ++i) {
125  segments.push_back(makeSegment(line.segment(i)));
126  }
127  return segments;
128  }
130  PointTree leftPts_, rightPts_;
132 };
133 
134 std::pair<ConstLineString2d::const_iterator, OptDistance> findClosestNonintersectingPoint(
136  const BoundChecker& bounds, const Point3d& lastPoint, bool isLeft) {
138  ConstLineString2d::const_iterator closestPosition;
139  BasicPoint2d last2d = utils::to2D(lastPoint).basicPoint();
140  double dLastOther = bg::distance(*otherPoint, last2d);
141  // this lambda is called with points of increasing distance to otherPoint
142  auto nonintersectingPointLoop = [&](ConstLineString2d::const_iterator candidate) {
143  // point must be after currPosition
144  if (candidate < currPosition) {
145  return false;
146  }
147  // we use the triangle inequation to find a distance where we can not
148  // expect a closer point than the current one
149  if (!!distance && bg::distance(*otherPoint, *candidate) / 2 - dLastOther > *distance) {
150  return true; // stops the loop
151  }
152  auto candidateDistance = bg::distance(*candidate, *otherPoint) / 2;
153  if (!!distance && *distance <= candidateDistance) {
154  return false;
155  }
156  // Candidates are only valid candidates if
157  // 1. their distance is minimal (at least for now) -> checked above
158  // 2. the new connection does not intersect with the borders
159  // 3. connection between point on one bound and point on other bound
160  // does not intersect with other parts of the boundary
161  BasicSegment2d boundConnection(otherPoint->basicPoint(), candidate->basicPoint());
162  BasicSegment2d invBoundConnection(boundConnection.second, boundConnection.first);
163  auto centerlinePointCand = centerpoint(boundConnection.first, boundConnection.second);
164  BasicSegment2d centerlineCandidate{utils::to2D(lastPoint).basicPoint(), centerlinePointCand};
165  if (!bounds.intersects(centerlineCandidate) && !bounds.secondCrossesBounds(boundConnection, isLeft) &&
166  !bounds.secondCrossesBounds(invBoundConnection, !isLeft)) {
167  distance = candidateDistance;
168  closestPosition = candidate;
169  }
170  return false;
171  };
172  if (isLeft) {
173  bounds.forEachNearestPointLeftUntil(otherPoint, nonintersectingPointLoop);
174  } else {
175  bounds.forEachNearestPointRightUntil(otherPoint, nonintersectingPointLoop);
176  }
177  return {closestPosition, distance};
178 }
179 
180 std::shared_ptr<ConstLineString3d> calculateCenterline(const ConstLineString2d& leftBound,
181  const ConstLineString2d& rightBound) {
182  LineString3d centerlinePoints(InvalId);
183 
184  // Catch degenerated case
185  if (leftBound.empty() || rightBound.empty()) {
186  return std::make_shared<ConstLineString3d>(centerlinePoints);
187  }
188 
189  BoundChecker bounds(utils::to2D(leftBound), utils::to2D(rightBound));
190 
191  // Initial point
192  centerlinePoints.push_back(makeCenterpoint(leftBound.front(), rightBound.front()));
193 
194  auto leftCurrent = leftBound.begin();
195  auto rightCurrent = rightBound.begin();
196  // special handling is required if the first two points are identical (i.e. the lanelet is closed at the beginning)
197  if (*leftCurrent == *rightCurrent) {
198  ++leftCurrent;
199  }
200  while (leftCurrent != leftBound.end() || rightCurrent != rightBound.end()) {
201  OptDistance leftCandidateDistance;
202  OptDistance rightCandidateDistance;
203  ConstLineString2d::const_iterator leftCandidate;
204  ConstLineString2d::const_iterator rightCandidate;
205 
206  // Determine left candidate
207  std::tie(leftCandidate, leftCandidateDistance) =
208  findClosestNonintersectingPoint(std::next(leftCurrent), rightCurrent, bounds, centerlinePoints.back(), true);
209 
210  // Determine right candidate
211  std::tie(rightCandidate, rightCandidateDistance) =
212  findClosestNonintersectingPoint(std::next(rightCurrent), leftCurrent, bounds, centerlinePoints.back(), false);
213  // Choose the better one
214  if (leftCandidateDistance && (!rightCandidateDistance || leftCandidateDistance <= rightCandidateDistance)) {
215  assert(leftCandidate != leftBound.end());
216 
217  const auto& leftPoint = leftBound[size_t(leftCandidate - leftBound.begin())];
218  const auto& rightPoint = rightBound[size_t(rightCurrent - rightBound.begin())];
219  centerlinePoints.push_back(makeCenterpoint(leftPoint, rightPoint));
220  leftCurrent = leftCandidate;
221  } else if (rightCandidateDistance && (!leftCandidateDistance || leftCandidateDistance > rightCandidateDistance)) {
222  assert(rightCandidate != rightBound.end());
223 
224  const auto& leftPoint = leftBound[size_t(leftCurrent - leftBound.begin())];
225  const auto& rightPoint = rightBound[size_t(rightCandidate - rightBound.begin())];
226  centerlinePoints.push_back(makeCenterpoint(leftPoint, rightPoint));
227  rightCurrent = rightCandidate;
228  } else {
229  // no next point found. We are done here
230  break;
231  }
232  }
233 
234  // we want the centerpoint defined by the endpoints inside in any case
235  if (!(leftCurrent == std::prev(leftBound.end()) && rightCurrent == std::prev(rightBound.end()))) {
236  centerlinePoints.push_back(makeCenterpoint(leftBound.back(), rightBound.back()));
237  }
238 
239  return std::make_shared<ConstLineString3d>(centerlinePoints);
240 }
241 #pragma GCC diagnostic pop
242 } // namespace
243 
244 // =============================================================
245 // Class LaneletData
246 // =============================================================
249  auto centerline = std::atomic_load_explicit(&centerline_, std::memory_order_acquire);
250  if (!centerline) {
251  centerline = calculateCenterline(utils::to2D(leftBound()), utils::to2D(rightBound()));
252  std::atomic_store_explicit(&centerline_, centerline, std::memory_order_release);
253  }
254  return *centerline;
255 }
256 
258  if (bound != leftBound_) {
259  resetCache();
260  leftBound_ = bound;
261  }
262 }
263 
265  if (bound != rightBound_) {
266  resetCache();
267  rightBound_ = bound;
268  }
269 }
270 
271 void LaneletData::setCenterline(const LineString3d& centerline) {
272  centerline_ = std::make_shared<ConstLineString3d>(centerline);
273 }
274 
276  auto centerline = std::atomic_load_explicit(&centerline_, std::memory_order_acquire);
277  return !!centerline && centerline->id() != InvalId;
278 }
279 
282 }
283 
285  if (!hasCustomCenterline()) {
286  std::atomic_store_explicit(&centerline_, std::shared_ptr<ConstLineString3d>(), std::memory_order_release);
287  }
288 }
289 
290 std::ostream& operator<<(std::ostream& stream, const ConstLanelet& obj) {
291  stream << "[id: " << obj.id();
292  if (obj.inverted()) {
293  stream << ", inverted";
294  }
295  stream << ", left id: " << obj.leftBound().id();
296  if (obj.leftBound().inverted()) {
297  stream << " (inverted)";
298  }
299  stream << ", right id: " << obj.rightBound().id();
300  if (obj.rightBound().inverted()) {
301  stream << " (inverted)";
302  }
303  return stream << "]";
304 }
305 
306 namespace utils {
307 bool has(const ConstLanelet& ll, Id id) {
308  auto regelems = ll.regulatoryElements();
309  return has(ll.leftBound(), id) || has(ll.rightBound(), id) ||
310  std::any_of(regelems.begin(), regelems.end(), [&id](const auto& elem) { return elem->id() == id; });
311 }
312 } // namespace utils
313 
314 CompoundPolygon3d ConstLanelet::polygon3d() const { return constData()->polygon(); }
315 
317 
318 // namespace utils
319 
320 } // namespace lanelet
exit_
BasicSegment2d exit_
Definition: Lanelet.cpp:131
lanelet::InvalId
constexpr Id InvalId
indicates a primitive that is not part of a map
Definition: Forward.h:199
lanelet::ConstLineStrings3d
std::vector< ConstLineString3d > ConstLineStrings3d
Definition: Forward.h:58
lanelet::LaneletData::resetCache
void resetCache() const
call this to indicate that the objects data has been modified.
Definition: Lanelet.cpp:284
lanelet::CompoundPolygon3d
Combines multiple linestrings to one polygon in 3d.
Definition: CompoundPolygon.h:40
lanelet::traits::to2D
BoundingBox2d to2D(const BoundingBox3d &primitive)
Definition: primitives/BoundingBox.h:304
lanelet
Definition: Attribute.h:13
boost::geometry
Definition: geometry/Polygon.h:30
rightSegments_
SegmentTree rightSegments_
Definition: Lanelet.cpp:129
p2
BasicPoint p2
Definition: LineStringGeometry.cpp:167
lanelet::ConstLanelet::inverted
bool inverted() const
returns if this is an inverted lanelet
Definition: primitives/Lanelet.h:154
lanelet::LaneletData::rightBound_
LineString3d rightBound_
represents the right bound
Definition: primitives/Lanelet.h:78
Polygon.h
lanelet::Id
int64_t Id
Definition: Forward.h:198
lanelet::operator<<
std::ostream & operator<<(std::ostream &stream, const Attribute &obj)
Definition: Attribute.h:369
lanelet::LaneletData::setLeftBound
void setLeftBound(const LineString3d &bound)
Sets a new left bound. Resets all cached data of this object.
Definition: Lanelet.cpp:257
lanelet::ConstLineStringImpl::back
const ConstPointType & back() const noexcept
returns the last point (if it exist)
Definition: primitives/LineString.h:295
lanelet::ConstLineStringImpl::inverted
bool inverted() const noexcept
Returns whether this is an inverted linestring.
Definition: primitives/LineString.h:257
lanelet::ConstLanelet::regulatoryElements
RegulatoryElementConstPtrs regulatoryElements() const
get a list of regulatory elements that affect this lanelet
Definition: primitives/Lanelet.h:178
lanelet::LaneletData::hasCustomCenterline
bool hasCustomCenterline() const
Returns whether the centerline has been overridden by setCenterline.
Definition: Lanelet.cpp:275
lanelet::ConstLineString2d
A normal 2d linestring with immutable data.
Definition: primitives/LineString.h:552
lanelet::ConstPrimitive< LaneletData >::constData
const std::shared_ptr< const LaneletData > & constData() const
get the internal data of this primitive
Definition: Primitive.h:178
LineString.h
rightPts_
PointTree rightPts_
Definition: Lanelet.cpp:130
lanelet::LaneletData::centerline_
std::shared_ptr< ConstLineString3d > centerline_
Definition: primitives/Lanelet.h:82
lanelet::ConstLineStringImpl::numSegments
size_t numSegments() const noexcept
Returns the number of (geometrically valid) segments.
Definition: primitives/LineString.h:333
lanelet::ConstLanelet::polygon2d
CompoundPolygon2d polygon2d() const
returns the surface covered by this lanelet as 2-dimensional polygon.
Definition: Lanelet.cpp:316
lanelet::ConstLineString3d::invert
ConstLineString3d invert() const noexcept
create a new, inverted linestring from this one
Definition: primitives/LineString.h:532
Lanelet.h
lanelet::geometry::internal::pointIsLeftOf
bool pointIsLeftOf(const PointT &pSeg1, const PointT &pSeg2, const PointT &p)
Definition: geometry/impl/LineString.h:52
lanelet::CompoundPolygon2d
Combines multiple linestrings to one polygon in 2d.
Definition: CompoundPolygon.h:11
p1
BasicPoint p1
Definition: LineStringGeometry.cpp:166
lanelet::LaneletData::centerline
ConstLineString3d centerline() const
Returns centerline by computing it, if necessary. Result is cached.
Definition: Lanelet.cpp:247
entry_
BasicSegment2d entry_
Definition: Lanelet.cpp:131
CompoundPolygon.h
lanelet::LaneletData::setRightBound
void setRightBound(const LineString3d &bound)
Sets a new right bound. Resets all cached data of this object.
Definition: Lanelet.cpp:264
lanelet::BasicPoint2d
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
a simple 2d-point
Definition: primitives/Point.h:20
lanelet::ConstLineStringImpl::segment
ConstSegmentType segment(size_t idx) const noexcept
returns the n-th segment. If n equals size() -1, the segment from back() to front() is returned.
Definition: primitives/LineString.h:325
lanelet::Point3d
A mutable 3d point.
Definition: primitives/Point.h:271
lanelet::utils::has
bool has(const ConstArea &ll, Id id)
returns true if element of a regulatory element has a matching Id
Definition: primitives/Area.h:324
leftSegments_
SegmentTree leftSegments_
Definition: Lanelet.cpp:129
lanelet::ConstLineStringImpl< Point2d >::const_iterator
internal::SelectLsIteratorT< const ConstPointType > const_iterator
Definition: primitives/LineString.h:230
RegulatoryElement.h
lanelet::OptDistance
boost::optional< double > OptDistance
Definition: Lanelet.cpp:14
lanelet::LaneletData::leftBound_
LineString3d leftBound_
represents the left bound
Definition: primitives/Lanelet.h:77
lanelet::ConstLineStringImpl::size
size_t size() const noexcept
Return the number of points in this linestring.
Definition: primitives/LineString.h:260
lanelet::ConstLineStringImpl::front
const ConstPointType & front() const noexcept
returns the first point (if it exist)
Definition: primitives/LineString.h:286
lanelet::ConstLineString3d
A normal 3d linestring with immutable data.
Definition: primitives/LineString.h:521
Lanelet.h
lanelet::ConstLanelet
An immutable lanelet.
Definition: primitives/Lanelet.h:131
leftPts_
PointTree leftPts_
Definition: Lanelet.cpp:130
distance
Optional< double > distance
Definition: LineStringGeometry.cpp:168
lanelet::LaneletData::leftBound
const ConstLineString3d & leftBound() const
Definition: primitives/Lanelet.h:35
lanelet::ConstLineStringImpl::end
const_iterator end() const noexcept
Returns an iterator to end of the points.
Definition: primitives/LineString.h:278
lanelet::ConstLineStringImpl::begin
const_iterator begin() const noexcept
Returns an iterator to the start of the points.
Definition: primitives/LineString.h:271
lanelet::LaneletData::setCenterline
void setCenterline(const LineString3d &centerline)
Sets a new right bound. Resets all cached data of this object.
Definition: Lanelet.cpp:271
lanelet::ConstLanelet::leftBound
ConstLineString3d leftBound() const
get the left bound.
Definition: primitives/Lanelet.h:160
lanelet::LaneletData::polygon
CompoundPolygon3d polygon() const
Get the bounding polygon of this lanelet. Result is cached.
Definition: Lanelet.cpp:280
lanelet::LaneletData::rightBound
const ConstLineString3d & rightBound() const
Definition: primitives/Lanelet.h:38
lanelet::LineString3d
A normal 3d linestring with mutable data.
Definition: primitives/LineString.h:538
lanelet::ConstPrimitive::id
Id id() const noexcept
get the unique id of this primitive
Definition: Primitive.h:96
lanelet::ConstLanelet::polygon3d
CompoundPolygon3d polygon3d() const
returns the surface covered by this lanelet as 3-dimensional polygon.
Definition: Lanelet.cpp:314
lanelet::ConstLanelet::rightBound
ConstLineString3d rightBound() const
get the right bound.
Definition: primitives/Lanelet.h:169
lanelet::BasicSegment2d
Segment< BasicPoint2d > BasicSegment2d
Definition: primitives/LineString.h:24
lanelet::ConstPoint2d
An immutable 2d point.
Definition: primitives/Point.h:150
lanelet::geometry::internal::SegmentTree
bgi::rtree< BasicSegment2d, bgi::linear< 4 > > SegmentTree
Definition: geometry/impl/LineString.h:271
lanelet::traits::to3D
BoundingBox3d to3D(const BoundingBox2d &primitive)
Definition: primitives/BoundingBox.h:303


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52