primitives/LineString.h
Go to the documentation of this file.
1 #pragma once
2 #include <utility>
3 
11 
12 namespace lanelet {
13 
16 
17 template <typename PointT>
18 using Segment = std::pair<PointT, PointT>;
19 
26 
27 namespace traits {
28 template <>
35 };
36 template <>
37 struct LineStringTraits<BasicLineString2d> : public PrimitiveTraits<BasicLineString2d> {
40 };
41 template <>
48 };
49 template <>
50 struct LineStringTraits<BasicLineString3d> : public PrimitiveTraits<BasicLineString3d> {
53 };
54 template <typename PointT>
55 struct PrimitiveTraits<Segment<PointT>> {
61 };
62 template <typename PointT>
63 struct LineStringTraits<Segment<PointT>> : public PrimitiveTraits<Segment<PointT>> {
64  using PointType = PointT;
66 };
67 template <>
69  BasicLineString2d ls2d(primitive.size());
70  std::transform(primitive.begin(), primitive.end(), ls2d.begin(), utils::to2D<BasicPoint3d>);
71  return ls2d;
72 }
73 
74 template <typename PointT>
76  return std::make_pair(toBasicPoint(s.first), toBasicPoint(s.second));
77 }
78 
79 } // namespace traits
80 
81 namespace utils {
83 }
84 
85 namespace internal {
86 template <typename PointT>
89 };
90 template <typename PointT>
91 struct SelectLsIterator<const PointT> {
92  using Iterator =
94 };
95 template <>
98 };
99 template <>
100 struct SelectLsIterator<const Point3d> {
102 };
103 
104 template <typename T>
106 
107 template <typename PointT>
109 
110 template <>
113 };
114 
115 template <>
118 };
119 
120 template <typename T>
122 
124  return Points3d::iterator(it);
125 }
126 template <typename T>
129 };
130 template <>
131 struct SelectInsertIterator<typename SelectLsIterator<Point2d>::Iterator> {
133 };
134 
135 } // namespace internal
136 
140  public:
141  explicit LineStringData(Id id) : PrimitiveData(id) {}
143  : PrimitiveData(id, std::move(attributes)), points_(std::move(points)) {}
144  // NOLINTNEXTLINE
146  // NOLINTNEXTLINE
148 
154  Points3d& points() { return points_; }
155 
156  template <typename IteratorT = const_iterator>
157  IteratorT begin(bool inverted) const noexcept {
158  return inverted ? IteratorT(const_iterator(points_.rbegin())) : IteratorT(const_iterator(points_.begin()));
159  }
160 
161  template <typename IteratorT = iterator>
162  IteratorT begin(bool inverted) noexcept {
163  return inverted ? IteratorT(iterator(points_.rbegin())) : IteratorT(iterator(points_.begin()));
164  }
165 
166  template <typename IteratorT = const_iterator>
167  IteratorT end(bool inverted) const noexcept {
168  return inverted ? IteratorT(const_iterator(points_.rend())) : IteratorT(const_iterator(points_.end()));
169  }
170  template <typename IteratorT = iterator>
171  IteratorT end(bool inverted) noexcept {
172  return inverted ? IteratorT(iterator(points_.rend())) : IteratorT(iterator(points_.end()));
173  }
174  auto size() const noexcept { return points_.size(); }
175  auto empty() const noexcept { return points_.empty(); }
176  const ConstPoint3d& at(bool inverted, size_t idx) const noexcept {
177  return inverted ? points_[points_.size() - 1 - idx] : points_[idx];
178  }
179  const ConstPoint3d& front(bool inverted) const noexcept { return inverted ? points_.back() : points_.front(); }
180  const ConstPoint3d& back(bool inverted) const noexcept { return inverted ? points_.front() : points_.back(); }
181 
182  private:
184 }; // class LineStringData
185 
217 
219 template <typename PointT>
220 class ConstLineStringImpl : public ConstPrimitive<LineStringData> {
221  public:
222  // using declarations
228 
229  // NOLINTNEXTLINE
231  using iterator = const_iterator; // NOLINT
232  using value_type = ConstPointType; // NOLINT
233  using size_type = size_t; // NOLINT
234  using difference_type = typename iterator::difference_type; // NOLINT
235 
241 
243  explicit ConstLineStringImpl(Id id = InvalId, Points3d points = Points3d(),
245  : ConstPrimitive{std::make_shared<LineStringData>(id, std::move(points), attributes)} {}
246 
248  explicit ConstLineStringImpl(const std::shared_ptr<const LineStringData>& data, bool inverted = false)
249  : ConstPrimitive(data), inverted_{inverted} {}
250 
252  template <typename OtherT>
254  : ConstPrimitive(other.constData()), inverted_{other.inverted()} {}
255 
257  bool inverted() const noexcept { return inverted_; }
258 
260  size_t size() const noexcept { return constData()->size(); }
261 
263  bool empty() const noexcept { return constData()->empty(); }
264 
266 
271  const_iterator begin() const noexcept { return constData()->template begin<const_iterator>(inverted()); }
273 
278  const_iterator end() const noexcept { return constData()->template end<const_iterator>(inverted()); }
279 
281 
286  const ConstPointType& front() const noexcept { return constData()->front(inverted()); }
287 
295  const ConstPointType& back() const noexcept { return constData()->back(inverted()); }
296 
304  const ConstPointType& operator[](size_t idx) const noexcept {
305  assert(idx < size());
306  return constData()->at(inverted(), idx);
307  }
308 
313  BasicIterator basicBegin() const noexcept { return constData()->template begin<BasicIterator>(inverted_); }
314 
319  BasicIterator basicEnd() const noexcept { return constData()->template end<BasicIterator>(inverted_); }
320 
325  ConstSegmentType segment(size_t idx) const noexcept {
326  assert(idx < size());
327  auto first = begin() + idx;
328  auto second = idx + 1 == size() ? begin() : first + 1;
329  return ConstSegmentType(*first, *second);
330  }
331 
333  size_t numSegments() const noexcept { return size() <= 1 ? 0 : size() - 1; }
334 
345  BasicLineString basicLineString() const noexcept { return {basicBegin(), basicEnd()}; }
346 
347  template <typename LineStringT>
349 
350  protected:
351  // This class is only an implementation class and should never be instanciated
352  ConstLineStringImpl(ConstLineStringImpl&& rhs) noexcept = default;
353  ConstLineStringImpl& operator=(ConstLineStringImpl&& rhs) noexcept = default;
354  ConstLineStringImpl(const ConstLineStringImpl& rhs) = default;
355  ConstLineStringImpl& operator=(const ConstLineStringImpl& rhs) = default;
356  ~ConstLineStringImpl() noexcept = default;
357 
358  private:
359  bool inverted_{false};
360 }; // class ConstLineStringImpl
361 
363 template <typename ConstLineStringT>
364 class LineStringImpl : public Primitive<ConstLineStringT> {
365  protected:
367  using Base::data;
368 
369  public:
372  using Base::Base;
373  using Base::inverted;
374  using Base::size;
375  using SegmentType = typename Base::SegmentType;
376  LineStringImpl() = default; // Not inherited from base class
377 
379  template <typename OtherT>
380  explicit LineStringImpl(const LineStringImpl<OtherT>& other) : Base(other) {}
381 
382  explicit LineStringImpl(const std::shared_ptr<const LineStringData>&, bool inverted) = delete;
383 
385  explicit LineStringImpl(const std::shared_ptr<LineStringData>& data, bool inverted) : Base(data, inverted) {}
386 
388  LineStringImpl& operator=(std::vector<PointType> rhs) {
389  if (inverted()) {
390  points() = utils::transform(rhs.rbegin(), rhs.rend(), [](const auto& v) { return Point3d(v); });
391  } else {
392  points() = utils::transform(rhs.begin(), rhs.end(), [](const auto& v) { return Point3d(v); });
393  }
394  return *this;
395  }
396 
398  LineStringImpl& operator=(std::vector<Point3d>&& rhs) {
399  if (inverted()) {
400  utils::invert(rhs);
401  }
402  points() = std::move(rhs);
403  return *this;
404  }
405 
413  iterator insert(iterator position, const PointType& point) {
414  using Iter = LineStringData::iterator;
415  auto fwIter = points().insert(internal::pointIter(position), Point3d(point));
416  return inverted() ? Iter::reversed(fwIter + 1) : Iter(fwIter);
417  }
418 
420  template <typename InIter>
421  iterator insert(iterator position, InIter start, InIter end) {
422  using Viter = typename internal::SelectInsertIterator<InIter>::Type;
423  using RIter = LineStringData::iterator;
424  if (inverted()) {
425  using RViter = std::reverse_iterator<Viter>;
426  auto fwIter = points().insert(internal::pointIter(position), RViter(end), RViter(start));
427  return RIter(Points3d::reverse_iterator(fwIter + 1));
428  }
429  auto fwIter = points().insert(internal::pointIter(position), Viter(start), Viter(end));
430  return RIter(fwIter);
431  }
432 
434  void push_back(const PointType& point) { // NOLINT
435  inverted() ? void(points().insert(points().begin(), Point3d(point))) : points().push_back(Point3d(point));
436  }
437 
439  iterator erase(iterator position) { // NOLINT
440  if (inverted()) {
441  position += 1;
442  }
443  using Iter = LineStringData::iterator;
444  auto it = points().erase(internal::pointIter(position));
445  return inverted() ? Iter::reversed(it) : Iter(it);
446  }
447 
449  void pop_back() { // NOLINT
450  inverted() ? void(points().erase(points().begin())) : points().pop_back();
451  }
452 
454  void reserve(size_t num) { points().reserve(num); }
455 
458  void resize(size_t num) {
459  if (inverted()) {
460  std::reverse(begin(), end());
461  }
462  points().resize(num);
463  if (inverted()) {
464  std::reverse(begin(), end());
465  }
466  }
467 
470  void clear() { points().clear(); }
471 
472  // inherit the const versions
473  using Base::back;
474  using Base::begin;
475  using Base::end;
476  using Base::front;
477  using Base::operator[];
478  using Base::segment;
479 
481  iterator begin() { return inverted() ? iterator(points().rbegin()) : iterator(points().begin()); }
482 
484  iterator end() { return inverted() ? iterator(points().rend()) : iterator(points().end()); }
485 
487  PointType& front() { return inverted() ? points().back() : points().front(); }
488 
490  PointType& back() { return inverted() ? points().front() : points().back(); }
491 
493  PointType& operator[](size_t idx) {
494  assert(idx < size());
495  return points()[inverted() ? points().size() - 1 - idx : idx];
496  }
497 
502  SegmentType segment(size_t idx) noexcept {
503  assert(idx < size());
504  const auto snd = idx + 1;
505  return SegmentType(operator[](idx), operator[](snd == size() ? 0 : snd));
506  }
507 
508  protected:
509  // This class is only an implementation class and should never be instanciated
510  LineStringImpl(LineStringImpl&& rhs) noexcept = default;
511  LineStringImpl& operator=(LineStringImpl&& rhs) noexcept = default;
512  LineStringImpl(const LineStringImpl& rhs) = default;
513  LineStringImpl& operator=(const LineStringImpl& rhs) = default;
514  ~LineStringImpl() noexcept = default;
515  Points3d& points() { return data()->points(); }
516 }; // class LineStringImpl
517 
521 class ConstLineString3d : public ConstLineStringImpl<Point3d> {
522  public:
529  ConstLineString3d() = default; // Not inherited from base class
530 
532  ConstLineString3d invert() const noexcept { return ConstLineString3d{constData(), !inverted()}; }
533 };
534 
538 class LineString3d : public LineStringImpl<ConstLineString3d> {
539  public:
543  LineString3d() = default; // Not inherited from base class
544 
546  LineString3d invert() const noexcept { return LineString3d{data(), !inverted()}; }
547 };
548 
552 class ConstLineString2d : public ConstLineStringImpl<Point2d> {
553  public:
560  ConstLineString2d() = default; // Not inherited from base class
561 
563  ConstLineString2d invert() const noexcept { return ConstLineString2d{constData(), !inverted()}; }
564 };
565 
569 class LineString2d : public LineStringImpl<ConstLineString2d> {
570  public:
574  LineString2d() = default; // Not inherited from base class
575 
577  LineString2d invert() const noexcept { return LineString2d{data(), !inverted()}; }
578 };
579 
586  public:
588  using const_iterator = BasicIterator; // NOLINT
589  using iterator = BasicIterator; // NOLINT
594 
596  ConstHybridLineString3d() = default; // Not inherited from base class
599 
602 
604  BasicIterator begin() const noexcept { return basicBegin(); }
605 
607  BasicIterator end() const noexcept { return basicEnd(); }
608 
610  const BasicPointType& front() const noexcept { return ConstLineString3d::front().basicPoint(); }
611 
613  const BasicPointType& back() const noexcept { return ConstLineString3d::back().basicPoint(); }
614 
616  const BasicPointType& operator[](size_t idx) const noexcept {
617  return ConstLineString3d::operator[](idx).basicPoint();
618  }
619 
624  SegmentType segment(size_t idx) const noexcept {
625  assert(idx < size());
626  const auto snd = idx + 1;
627  return {operator[](idx), operator[](snd == size() ? 0 : snd)};
628  }
629 };
630 
637  public:
639  using const_iterator = BasicIterator; // NOLINT
640  using iterator = BasicIterator; // NOLINT
645 
647  ConstHybridLineString2d() = default; // Not inherited from base class
650 
653 
655  BasicIterator begin() const noexcept { return basicBegin(); }
656 
658  BasicIterator end() const noexcept { return basicEnd(); }
659 
661  const BasicPointType& front() const noexcept { return ConstLineString2d::front().basicPoint(); }
662 
664  const BasicPointType& back() const noexcept { return ConstLineString2d::back().basicPoint(); }
665 
667  const BasicPointType& operator[](size_t idx) const noexcept {
668  return ConstLineString2d::operator[](idx).basicPoint();
669  }
670 
675  SegmentType segment(size_t idx) const noexcept {
676  assert(idx < size());
677  const auto snd = idx + 1;
678  return {operator[](idx), operator[](snd == size() ? 0 : snd)};
679  }
680 };
681 
682 inline std::ostream& operator<<(std::ostream& stream, const ConstLineString2d& obj) {
683  stream << "[id: " << obj.id();
684  if (obj.inverted()) {
685  stream << ", inverted";
686  }
687  stream << " point ids: ";
688  for (auto it = obj.begin(); it != obj.end(); ++it) {
689  stream << it->id();
690  if (std::next(it) != obj.end()) {
691  stream << ", ";
692  }
693  }
694  return stream << "]";
695 }
696 
697 inline std::ostream& operator<<(std::ostream& stream, const ConstLineString3d& obj) {
698  stream << "[id: " << obj.id();
699  if (obj.inverted()) {
700  stream << ", inverted";
701  }
702  stream << " point ids: ";
703  for (auto it = obj.begin(); it != obj.end(); ++it) {
704  stream << it->id();
705  if (std::next(it) != obj.end()) {
706  stream << ", ";
707  }
708  }
709  return stream << "]";
710 }
711 
712 // comparison
713 template <typename LhsPointT, typename RhsPointT>
715  return lhs.constData() == rhs.constData() && lhs.inverted() == rhs.inverted();
716 }
717 template <typename LhsPointT, typename RhsPointT>
719  return !(lhs == rhs);
720 }
721 
722 template <typename PointT>
723 bool operator==(const ConstLineStringImpl<PointT>& lhs, const std::vector<PointT>& rhs) {
724  return lhs.size() == rhs.size() && std::equal(lhs.begin(), lhs.end(), rhs.begin());
725 }
726 
727 template <typename PointT>
728 bool operator==(const std::vector<PointT>& lhs, const ConstLineStringImpl<PointT>& rhs) {
729  return rhs == lhs;
730 }
731 
732 template <typename PointT>
733 bool operator!=(const ConstLineStringImpl<PointT>& lhs, const std::vector<PointT>& rhs) {
734  return !(lhs == rhs);
735 }
736 
737 template <typename PointT>
738 bool operator!=(const std::vector<PointT>& lhs, const ConstLineStringImpl<PointT>& rhs) {
739  return !(lhs == rhs);
740 }
741 
742 namespace traits {
743 template <typename T>
744 constexpr bool isLinestringT() {
745  return isCategory<T, traits::LineStringTag>();
746 }
747 
748 namespace detail {
749 template <typename T, typename Enable = void>
750 struct HybridType {};
751 
752 template <typename T>
753 struct HybridType<T, std::enable_if_t<traits::isLinestringT<T>(), void>> {
755 };
756 template <typename T>
757 struct HybridType<T, std::enable_if_t<!traits::isLinestringT<T>(), void>> {
759 };
760 } // namespace detail
761 template <typename LineStringT>
763 
764 template <typename LineStringT>
765 constexpr auto toHybrid(const LineStringT ls) {
766  return HybridT<LineStringT>(ls);
767 }
768 } // namespace traits
769 
770 template <typename T, typename RetT>
771 using IfLS = std::enable_if_t<traits::isLinestringT<T>(), RetT>;
772 
773 template <typename T1, typename T2, typename RetT>
774 using IfLS2 = std::enable_if_t<traits::isLinestringT<T1>() && traits::isLinestringT<T2>(), RetT>;
775 
776 namespace utils {
777 using traits::toHybrid;
778 
789 template <typename PointT>
790 bool has(const ConstLineStringImpl<PointT>& ls, Id id) {
791  return std::any_of(ls.begin(), ls.end(), [&id](const auto& elem) { return elem.id() == id; });
792 }
793 } // namespace utils
794 
795 } // namespace lanelet
796 
797 // Hash function for usage in containers
798 namespace std {
799 template <>
800 struct hash<lanelet::LineString3d> : public lanelet::HashBase<lanelet::LineString3d> {};
801 template <>
802 struct hash<lanelet::ConstLineString3d> : public lanelet::HashBase<lanelet::ConstLineString3d> {};
803 template <>
804 struct hash<lanelet::LineString2d> : public lanelet::HashBase<lanelet::LineString2d> {};
805 template <>
806 struct hash<lanelet::ConstLineString2d> : public lanelet::HashBase<lanelet::ConstLineString2d> {};
807 template <>
808 struct hash<lanelet::ConstHybridLineString2d> : public lanelet::HashBase<lanelet::ConstHybridLineString2d> {};
809 template <>
810 struct hash<lanelet::ConstHybridLineString3d> : public lanelet::HashBase<lanelet::ConstHybridLineString3d> {};
811 } // namespace std
lanelet::InvalId
constexpr Id InvalId
indicates a primitive that is not part of a map
Definition: Forward.h:199
lanelet::HashBase
Definition: Primitive.h:328
lanelet::LineStringImpl::pop_back
void pop_back()
removes element from the end
Definition: primitives/LineString.h:449
lanelet::LineString3d::LineString3d
LineString3d()=default
lanelet::Primitive
Base class for all mutable Primitives of lanelet2.
Definition: Primitive.h:243
lanelet::ConstLineStringImpl::operator[]
const ConstPointType & operator[](size_t idx) const noexcept
returns the point at this position
Definition: primitives/LineString.h:304
lanelet::ConstHybridLineString3d::begin
BasicIterator begin() const noexcept
BasicPoint3d Iterator to begin.
Definition: primitives/LineString.h:604
lanelet::ConstLineString2d::invert
ConstLineString2d invert() const noexcept
create a new, inverted linestring from this one
Definition: primitives/LineString.h:563
lanelet::ConstLineStringImpl::basicLineString
BasicLineString basicLineString() const noexcept
Create a basic linestring (ie a vector of Eigen Points)
Definition: primitives/LineString.h:345
lanelet::ConstHybridLineString3d::invert
ConstHybridLineString3d invert() const noexcept
Returns an inverted linestring, O(0)
Definition: primitives/LineString.h:601
lanelet::IfLS2
std::enable_if_t< traits::isLinestringT< T1 >() &&traits::isLinestringT< T2 >(), RetT > IfLS2
Definition: primitives/LineString.h:774
lanelet::ConstLineStringImpl::basicBegin
BasicIterator basicBegin() const noexcept
returns a normal iterator to the internal point type at begin
Definition: primitives/LineString.h:313
lanelet::ConstHybridLineString2d::PointType
BasicPointType PointType
Definition: primitives/LineString.h:638
lanelet::traits::PrimitiveTraits< BasicLineString3d >::TwoDType
BasicLineString2d TwoDType
Definition: primitives/LineString.h:45
lanelet::traits::toBasicSegment
auto toBasicSegment(const Segment< PointT > &s)
Definition: primitives/LineString.h:75
lanelet::ConstLineStringImpl::Dimension
static constexpr traits::Dimensions Dimension
Definition: primitives/LineString.h:240
lanelet::BasicPoints3d
std::vector< BasicPoint3d > BasicPoints3d
multiple simple 3d-points
Definition: primitives/Point.h:23
lanelet::ConstLineStringImpl< Point3d >::PointType
ConstPointType PointType
Definition: primitives/LineString.h:225
lanelet::internal::SelectBasicLineString
Definition: primitives/LineString.h:108
lanelet::LineStringData::LineStringData
LineStringData(Id id, Points3d points, AttributeMap attributes)
Definition: primitives/LineString.h:142
lanelet::traits::PrimitiveTraits< BasicLineString2d >::TwoDType
BasicLineString2d TwoDType
Definition: primitives/LineString.h:32
lanelet::ConstHybridLineString2d::segment
SegmentType 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:675
lanelet::LineStringImpl::LineStringImpl
LineStringImpl(const LineStringImpl< OtherT > &other)
Construct from other (mutable!) LineStrings.
Definition: primitives/LineString.h:380
lanelet::PrimitiveData
Common data class for all lanelet primitives.
Definition: Primitive.h:31
lanelet::ConstSegment3d
Segment< ConstPoint3d > ConstSegment3d
Definition: primitives/LineString.h:23
lanelet::traits::PrimitiveTraits< BasicLineString2d >::ThreeDType
BasicLineString3d ThreeDType
Definition: primitives/LineString.h:33
lanelet::traits::Dimensions
Dimensions
Definition: Traits.h:129
lanelet
Definition: Attribute.h:13
lanelet::ConstHybridLineString3d::ConstHybridLineString3d
ConstHybridLineString3d(const LineString3d &ls)
Definition: primitives/LineString.h:598
Point.h
lanelet::LineStringImpl::resize
void resize(size_t num)
Definition: primitives/LineString.h:458
lanelet::BasicPoint3d
Eigen::Vector3d BasicPoint3d
a simple 3d-point
Definition: primitives/Point.h:19
lanelet::ConstPrimitive< LineStringData >::attributes
const AttributeMap & attributes() const
get the attributes of this primitive
Definition: Primitive.h:89
lanelet::ConstHybridLineString3d::segment
SegmentType 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:624
lanelet::ConstLineStringImpl::basicEnd
BasicIterator basicEnd() const noexcept
returns a normal iterator for the internal point type at end
Definition: primitives/LineString.h:319
lanelet::IfLS
std::enable_if_t< traits::isLinestringT< T >(), RetT > IfLS
Definition: primitives/LineString.h:771
lanelet::traits::toHybrid
constexpr auto toHybrid(const LineStringT ls)
Definition: primitives/LineString.h:765
lanelet::traits::detail::HybridType< T, std::enable_if_t<!traits::isLinestringT< T >(), void > >::Type
typename LineStringTraits< T >::HybridType Type
Definition: primitives/LineString.h:758
lanelet::AttributeMap
HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map > AttributeMap
Definition: Attribute.h:371
lanelet::utils::invert
Container invert(const Container &cont)
Definition: Utilities.h:169
lanelet::LineStringImpl::LineStringImpl
LineStringImpl()=default
lanelet::LineStringImpl::SegmentType
typename Base::SegmentType SegmentType
Definition: primitives/LineString.h:375
lanelet::internal::SelectLsIteratorT
typename SelectLsIterator< T >::Iterator SelectLsIteratorT
Definition: primitives/LineString.h:105
lanelet::traits::LineStringTraits< BasicLineString2d >::PointType
BasicPoint2d PointType
Definition: primitives/LineString.h:38
lanelet::BasicSegment3d
Segment< BasicPoint3d > BasicSegment3d
Definition: primitives/LineString.h:25
lanelet::LineStringImpl
Implementation template class that is common to all non-const types.
Definition: primitives/LineString.h:364
lanelet::traits::toBasicPoint
auto toBasicPoint(const PointT &point) -> std::enable_if_t< PointTraits< PointT >::IsPrimitive, BasicPointT< PointT >>
Definition: Traits.h:165
lanelet::Point2d
A mutable 2d point.
Definition: primitives/Point.h:230
lanelet::operator==
bool operator==(const Attribute &lhs, const Attribute &rhs)
Definition: Attribute.h:179
lanelet::traits::MutablePointT
typename PointTraits< PointT >::MutablePoint MutablePointT
Definition: Traits.h:162
lanelet::LineStringData::begin
IteratorT begin(bool inverted) noexcept
Definition: primitives/LineString.h:162
lanelet::ConstHybridLineString2d::begin
BasicIterator begin() const noexcept
BasicPoint2d Iterator to begin.
Definition: primitives/LineString.h:655
lanelet::ConstHybridLineString2d::front
const BasicPointType & front() const noexcept
Get first BasicPoint2d.
Definition: primitives/LineString.h:661
lanelet::LineStringImpl::operator=
LineStringImpl & operator=(std::vector< Point3d > &&rhs)
Move assign from a normal vector. Id and attributes stay unchanged.
Definition: primitives/LineString.h:398
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::utils::transform
auto transform(Iterator begin, Iterator end, const Func f)
Definition: Utilities.h:176
lanelet::Segment
std::pair< PointT, PointT > Segment
Definition: primitives/LineString.h:18
lanelet::traits::detail::HybridType
Definition: primitives/LineString.h:750
lanelet::LineStringImpl::push_back
void push_back(const PointType &point)
inserts a new element at the end
Definition: primitives/LineString.h:434
lanelet::ConstLineStringImpl< Point3d >::ConstSegmentType
traits::ConstPrimitiveType< SegmentType > ConstSegmentType
Definition: primitives/LineString.h:239
lanelet::ConstLineStringImpl::back
const ConstPointType & back() const noexcept
returns the last point (if it exist)
Definition: primitives/LineString.h:295
lanelet::traits::LineStringTag
Identifies bounding boxes.
Definition: Traits.h:8
lanelet::ConstLineStringImpl::inverted
bool inverted() const noexcept
Returns whether this is an inverted linestring.
Definition: primitives/LineString.h:257
lanelet::traits::LineStringTraits
Specialization of traits for linestrings.
Definition: Traits.h:143
lanelet::ConstHybridLineString2d
A Linestring that returns BasicPoint2d instead of Point2d.
Definition: primitives/LineString.h:636
TransformIterator.h
lanelet::Segment3d
Segment< Point3d > Segment3d
Definition: primitives/LineString.h:22
lanelet::LineStringImpl::~LineStringImpl
~LineStringImpl() noexcept=default
lanelet::ConstHybridLineString2d::ConstHybridLineString2d
ConstHybridLineString2d(const LineString2d &ls)
Definition: primitives/LineString.h:649
lanelet::traits::PrimitiveTraits< Segment< PointT > >::ThreeDType
Segment< ThreeD< PointT > > ThreeDType
Definition: primitives/LineString.h:59
lanelet::traits::PrimitiveTraits< BasicLineString3d >::ConstType
BasicLineString3d ConstType
Definition: primitives/LineString.h:43
lanelet::traits::PrimitiveTraits< BasicLineString2d >::MutableType
BasicLineString2d MutableType
Definition: primitives/LineString.h:31
lanelet::LineStringImpl::reserve
void reserve(size_t num)
request a change in capacity
Definition: primitives/LineString.h:454
lanelet::ConstLineStringImpl< Point3d >::BasicIterator
internal::TransformIterator< const_iterator, const BasicPointType > BasicIterator
Definition: primitives/LineString.h:236
lanelet::traits::PrimitiveTraits< BasicLineString2d >::ConstType
BasicLineString2d ConstType
Definition: primitives/LineString.h:30
lanelet::ConstHybridLineString3d::operator[]
const BasicPointType & operator[](size_t idx) const noexcept
access BasicPoint3d at specific position
Definition: primitives/LineString.h:616
lanelet::ConstSegment2d
Segment< ConstPoint2d > ConstSegment2d
Definition: primitives/LineString.h:21
lanelet::ConstLineString2d
A normal 2d linestring with immutable data.
Definition: primitives/LineString.h:552
lanelet::ConstHybridLineString3d::SegmentType
Segment< BasicPointType > SegmentType
Definition: primitives/LineString.h:593
lanelet::LineStringData::front
const ConstPoint3d & front(bool inverted) const noexcept
Definition: primitives/LineString.h:179
lanelet::LineStringData::iterator
internal::ReverseAndForwardIterator< Points3d::iterator > iterator
Definition: primitives/LineString.h:145
lanelet::LineStringData::begin
IteratorT begin(bool inverted) const noexcept
Definition: primitives/LineString.h:157
lanelet::ConstHybridLineString3d::ConstHybridLineString3d
ConstHybridLineString3d(const ConstLineString3d &ls)
Definition: primitives/LineString.h:597
lanelet::LineString2d
A normal 2d linestring with mutable data.
Definition: primitives/LineString.h:569
lanelet::LineStringImpl::operator=
LineStringImpl & operator=(std::vector< PointType > rhs)
Copy assign from a normal vector. The Id of this object is unchanged.
Definition: primitives/LineString.h:388
lanelet::ConstPrimitive< LineStringData >::constData
const std::shared_ptr< const LineStringData > & constData() const
get the internal data of this primitive
Definition: Primitive.h:178
lanelet::traits::LineStringTraits< Segment< PointT > >::HybridType
Segment< traits::BasicPointT< PointT > > HybridType
Definition: primitives/LineString.h:65
lanelet::traits::to2D< BasicLineString3d >
BasicLineString2d to2D< BasicLineString3d >(const BasicLineString3d &primitive)
Definition: primitives/LineString.h:68
lanelet::ConstLineStringImpl< Point3d >::size_type
size_t size_type
Definition: primitives/LineString.h:233
lanelet::ConstLineStringImpl< Point3d >::BasicPointType
traits::BasicPointT< Point3d > BasicPointType
Definition: primitives/LineString.h:223
lanelet::traits::PrimitiveTraits< BasicLineString3d >::ThreeDType
BasicLineString3d ThreeDType
Definition: primitives/LineString.h:46
lanelet::ConstPoint3d
An immutable 3d point.
Definition: primitives/Point.h:202
Primitive.h
lanelet::LineStringData
Definition: primitives/LineString.h:139
lanelet::utils::detail::transform
auto transform(Container &&c, Func f)
Definition: Utilities.h:120
lanelet::ConstLineStringImpl
Implementation template class that is common to all LineStrings.
Definition: primitives/LineString.h:220
lanelet::ConstLineStringImpl::ConstLineStringImpl
ConstLineStringImpl(const std::shared_ptr< const LineStringData > &data, bool inverted=false)
Constructs a linestring from the data object of another linestring.
Definition: primitives/LineString.h:248
lanelet::traits::PrimitiveTraits< Segment< PointT > >::ConstType
Segment< ConstPrimitiveType< PointT > > ConstType
Definition: primitives/LineString.h:56
lanelet::LineStringImpl::clear
void clear()
Definition: primitives/LineString.h:470
lanelet::internal::TransformIterator
Definition: TransformIterator.h:54
lanelet::LineStringImpl::segment
SegmentType segment(size_t idx) noexcept
returns the n-th segment. If n equals size() -1, the segment from back() to front() is returned.
Definition: primitives/LineString.h:502
lanelet::PrimitiveData::attributes
AttributeMap attributes
attributes of this primitive
Definition: Primitive.h:45
lanelet::ConstLineStringImpl::numSegments
size_t numSegments() const noexcept
Returns the number of (geometrically valid) segments.
Definition: primitives/LineString.h:333
lanelet::traits::LineStringTraits< BasicLineString3d >::PointType
BasicPoint3d PointType
Definition: primitives/LineString.h:51
lanelet::Points3d
std::vector< Point3d > Points3d
Definition: Forward.h:34
lanelet::ConstHybridLineString3d::PointType
BasicPointType PointType
Definition: primitives/LineString.h:587
lanelet::traits::isLinestringT
constexpr bool isLinestringT()
Definition: primitives/LineString.h:744
lanelet::traits::LineStringTraits< Segment< PointT > >::PointType
PointT PointType
Definition: primitives/LineString.h:64
lanelet::LineString3d::invert
LineString3d invert() const noexcept
create a new, inverted linestring from this one
Definition: primitives/LineString.h:546
lanelet::BasicLineString2d
BasicPoints2d BasicLineString2d
Definition: primitives/LineString.h:14
lanelet::ConstLineString3d::invert
ConstLineString3d invert() const noexcept
create a new, inverted linestring from this one
Definition: primitives/LineString.h:532
lanelet::LineStringImpl::front
PointType & front()
get a refernce to the first element (make sure it exists)
Definition: primitives/LineString.h:487
lanelet::ConstHybridLineString2d::SegmentType
Segment< BasicPointType > SegmentType
Definition: primitives/LineString.h:644
lanelet::ConstLineStringImpl< Point3d >::BasicLineString
internal::SelectBasicLineStringT< BasicPointType > BasicLineString
Definition: primitives/LineString.h:237
lanelet::traits::PrimitiveTraits< BasicLineString3d >::MutableType
BasicLineString3d MutableType
Definition: primitives/LineString.h:44
lanelet::internal::SelectBasicLineString< BasicPoint2d >::Type
BasicLineString2d Type
Definition: primitives/LineString.h:112
lanelet::operator!=
bool operator!=(const Attribute &lhs, const Attribute &rhs)
Definition: Attribute.h:180
lanelet::LineStringImpl::LineStringImpl
LineStringImpl(const std::shared_ptr< LineStringData > &data, bool inverted)
Construct from linestring data.
Definition: primitives/LineString.h:385
lanelet::internal::SelectBasicLineStringT
typename SelectBasicLineString< T >::Type SelectBasicLineStringT
Definition: primitives/LineString.h:121
lanelet::ConstHybridLineString3d::end
BasicIterator end() const noexcept
BasicPoint3d Iterator to past-the-end.
Definition: primitives/LineString.h:607
lanelet::ConstLineStringImpl::empty
bool empty() const noexcept
return if there are any points in this object
Definition: primitives/LineString.h:263
lanelet::LineStringImpl::begin
iterator begin()
mutable iterator for the elements of this vector.
Definition: primitives/LineString.h:481
ReverseAndForwardIterator.h
lanelet::ConstLineStringImpl::CompoundLineString
Definition: primitives/LineString.h:348
lanelet::traits::ConstPrimitiveType
typename PrimitiveTraits< PrimitiveT >::ConstType ConstPrimitiveType
Utility for determinig the matching const type for a primitive.
Definition: Traits.h:80
Utilities.h
lanelet::ConstHybridLineString2d::operator[]
const BasicPointType & operator[](size_t idx) const noexcept
access element at specific position
Definition: primitives/LineString.h:667
lanelet::ConstHybridLineString2d::invert
ConstHybridLineString2d invert() const noexcept
Returns an inverted linestring, O(0)
Definition: primitives/LineString.h:652
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::LineStringData::const_iterator
internal::ReverseAndForwardIterator< Points3d::const_iterator > const_iterator
Definition: primitives/LineString.h:147
lanelet::Point3d
A mutable 3d point.
Definition: primitives/Point.h:271
lanelet::LineStringData::end
IteratorT end(bool inverted) noexcept
Definition: primitives/LineString.h:171
lanelet::LineStringData::empty
auto empty() const noexcept
Definition: primitives/LineString.h:175
lanelet::LineString2d::invert
LineString2d invert() const noexcept
create a new, inverted linestring from this one
Definition: primitives/LineString.h:577
lanelet::LineStringData::at
const ConstPoint3d & at(bool inverted, size_t idx) const noexcept
Definition: primitives/LineString.h:176
lanelet::LineString2d::LineString2d
LineString2d()=default
lanelet::ConstHybridLineString3d::front
const BasicPointType & front() const noexcept
Get first BasicPoint3d.
Definition: primitives/LineString.h:610
lanelet::HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map >
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
lanelet::LineStringImpl::insert
iterator insert(iterator position, InIter start, InIter end)
Inserts an range of elements at a specific position.
Definition: primitives/LineString.h:421
lanelet::ConstLineStringImpl< Point3d >::MutablePointType
traits::MutablePointT< Point3d > MutablePointType
linestring will return this point type
Definition: primitives/LineString.h:226
lanelet::ConstLineStringImpl::~ConstLineStringImpl
~ConstLineStringImpl() noexcept=default
lanelet::ConstPrimitive
Basic Primitive class for all primitives of lanelet2.
Definition: Primitive.h:70
lanelet::LineStringImpl::end
iterator end()
mutable iterator to the end of the elements of this vector.
Definition: primitives/LineString.h:484
std
Definition: primitives/Area.h:369
lanelet::ConstHybridLineString3d::back
const BasicPointType & back() const noexcept
Get last BasicPoint3d.
Definition: primitives/LineString.h:613
lanelet::ConstLineStringImpl< Point3d >::const_iterator
internal::SelectLsIteratorT< const ConstPointType > const_iterator
Definition: primitives/LineString.h:230
lanelet::ConstLineStringImpl< Point3d >::difference_type
typename iterator::difference_type difference_type
Definition: primitives/LineString.h:234
lanelet::traits::HybridT
typename detail::HybridType< LineStringT >::Type HybridT
Definition: primitives/LineString.h:762
BoundingBox.h
lanelet::ConstHybridLineString3d::ConstHybridLineString3d
ConstHybridLineString3d()=default
lanelet::internal::pointIter
Points3d::const_iterator pointIter(internal::ReverseAndForwardIterator< Points3d::iterator > it)
Definition: primitives/LineString.h:123
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::LineStringData::points_
Points3d points_
Definition: primitives/LineString.h:183
lanelet::LineStringImpl::operator[]
PointType & operator[](size_t idx)
access element at specific position
Definition: primitives/LineString.h:493
lanelet::ConstLineString3d
A normal 3d linestring with immutable data.
Definition: primitives/LineString.h:521
lanelet::ConstLineString3d::ConstLineString3d
ConstLineString3d()=default
lanelet::traits::detail::HybridType< T, std::enable_if_t< traits::isLinestringT< T >(), void > >::Type
typename LineStringTraits< T >::HybridType Type
Definition: primitives/LineString.h:754
lanelet::LineStringImpl::back
PointType & back()
get a reference to the last element if it exists
Definition: primitives/LineString.h:490
lanelet::LineStringData::size
auto size() const noexcept
Definition: primitives/LineString.h:174
lanelet::LineStringData::points
Points3d & points()
returns a reference to the points
Definition: primitives/LineString.h:154
lanelet::ConstLineStringImpl< Point3d >::iterator
const_iterator iterator
Definition: primitives/LineString.h:231
lanelet::LineStringData::end
IteratorT end(bool inverted) const noexcept
Definition: primitives/LineString.h:167
lanelet::ConstLineStringImpl::operator=
ConstLineStringImpl & operator=(ConstLineStringImpl &&rhs) noexcept=default
lanelet::ConstHybridLineString3d
A Linestring that returns BasicPoint3d instead of Point3d.
Definition: primitives/LineString.h:585
lanelet::ConstLineStringImpl::inverted_
bool inverted_
Definition: primitives/LineString.h:359
lanelet::traits::LineStringTraits::HybridType
typename LineStringT::HybridType HybridType
Definition: Traits.h:145
lanelet::LineStringImpl::iterator
internal::SelectLsIteratorT< PointType > iterator
Definition: primitives/LineString.h:371
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::traits::PrimitiveTraits< Segment< PointT > >::TwoDType
Segment< TwoD< PointT > > TwoDType
Definition: primitives/LineString.h:58
lanelet::traits::PointTraits
Specialization of traits for points.
Definition: Traits.h:133
lanelet::ConstHybridLineString2d::end
BasicIterator end() const noexcept
BasicPoint2d Iterator to past-the-end.
Definition: primitives/LineString.h:658
lanelet::LineStringImpl::erase
iterator erase(iterator position)
Removes point, returns iterator to the next point.
Definition: primitives/LineString.h:439
lanelet::PrimitiveData::id
Id id
Id of this primitive (unique across one map)
Definition: Primitive.h:44
lanelet::LineStringImpl::points
Points3d & points()
Definition: primitives/LineString.h:515
lanelet::traits::BasicPointT
typename PointTraits< PointT >::BasicPoint BasicPointT
Definition: Traits.h:156
lanelet::traits::PrimitiveTraits
Identifies RegulatoryElementPrimitives.
Definition: Traits.h:20
lanelet::ConstLineString2d::ConstLineString2d
ConstLineString2d()=default
Forward.h
lanelet::LineStringData::back
const ConstPoint3d & back(bool inverted) const noexcept
Definition: primitives/LineString.h:180
lanelet::internal::SelectBasicLineString< BasicPoint3d >::Type
BasicLineString3d Type
Definition: primitives/LineString.h:117
lanelet::traits::LineStringTraits< BasicLineString3d >::HybridType
BasicLineString3d HybridType
Definition: primitives/LineString.h:52
lanelet::Primitive< ConstLineStringT >::data
std::shared_ptr< DataType > data() const
Definition: Primitive.h:287
lanelet::traits::ConstPointT
typename PointTraits< PointT >::ConstPoint ConstPointT
Definition: Traits.h:159
lanelet::ConstHybridLineString2d::back
const BasicPointType & back() const noexcept
Get last BasicPoint2d.
Definition: primitives/LineString.h:664
lanelet::internal::ReverseAndForwardIterator
Definition: ReverseAndForwardIterator.h:9
lanelet::internal::SelectInsertIterator
Definition: primitives/LineString.h:127
lanelet::LineStringImpl::insert
iterator insert(iterator position, const PointType &point)
Inserts an element at a specific position.
Definition: primitives/LineString.h:413
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::Segment2d
Segment< Point2d > Segment2d
Definition: primitives/LineString.h:20
lanelet::LineStringData::LineStringData
LineStringData(Id id)
Definition: primitives/LineString.h:141
lanelet::ConstLineStringImpl< Point3d >::value_type
ConstPointType value_type
Definition: primitives/LineString.h:232
lanelet::BasicSegment2d
Segment< BasicPoint2d > BasicSegment2d
Definition: primitives/LineString.h:24
lanelet::ConstLineStringImpl::ConstLineStringImpl
ConstLineStringImpl(Id id=InvalId, Points3d points=Points3d(), const AttributeMap &attributes=AttributeMap())
Constructs a LineString or similar from an Id and a list of points.
Definition: primitives/LineString.h:243
lanelet::BasicPoints2d
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > BasicPoints2d
multiple simple 2d-points
Definition: primitives/Point.h:22
lanelet::traits::LineStringTraits< BasicLineString2d >::HybridType
BasicLineString2d HybridType
Definition: primitives/LineString.h:39
lanelet::ConstLineStringImpl< Point3d >::SegmentType
Segment< Point3d > SegmentType
Definition: primitives/LineString.h:238
lanelet::ConstLineStringImpl< Point3d >::ConstPointType
traits::ConstPointT< Point3d > ConstPointType
Definition: primitives/LineString.h:224
lanelet::internal::SelectLsIterator
Definition: primitives/LineString.h:87
lanelet::traits::PrimitiveTraits< Segment< PointT > >::MutableType
Segment< MutablePrimitiveType< PointT > > MutableType
Definition: primitives/LineString.h:57
lanelet::ConstHybridLineString2d::ConstHybridLineString2d
ConstHybridLineString2d()=default
lanelet::ConstLineStringImpl::ConstLineStringImpl
ConstLineStringImpl(const ConstLineStringImpl< OtherT > &other)
construct from other ConstLineStrings
Definition: primitives/LineString.h:253
lanelet::BasicLineString3d
BasicPoints3d BasicLineString3d
Definition: primitives/LineString.h:15
lanelet::ConstHybridLineString2d::ConstHybridLineString2d
ConstHybridLineString2d(const ConstLineString2d &ls)
Definition: primitives/LineString.h:648


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