CompoundLineString.h
Go to the documentation of this file.
1 #pragma once
2 #include <boost/noncopyable.hpp>
3 #include <utility>
4 
7 
8 namespace lanelet {
9 namespace internal {
13 template <typename PointT>
17 };
18 
19 template <>
23 };
24 
25 template <typename T>
27 } // namespace internal
28 
38 class CompoundLineStringData : boost::noncopyable {
40  using Reverse = std::reverse_iterator<BaseIter>;
41 
42  public:
44  explicit CompoundLineStringData(ConstLineStrings3d lineStrings) : ls_{std::move(lineStrings)} {}
45  ConstPoints3d points() const { return ConstPoints3d(BaseIter::begin(ls_), BaseIter::end(ls_)); }
46  const ConstLineStrings3d& lineStrings() const { return ls_; }
47  RFIter pointsBegin(bool inverted) const {
48  return inverted ? RFIter(Reverse(BaseIter::end(ls_))) : RFIter(BaseIter::begin(ls_));
49  }
50  RFIter pointsEnd(bool inverted) const {
51  return inverted ? RFIter(Reverse(BaseIter::begin(ls_))) : RFIter(BaseIter::end(ls_));
52  }
53 
54  private:
55  const ConstLineStrings3d ls_; // NOLINT
56 };
57 
68 template <typename PointT>
71 
72  public:
73  // using declarations
75  using PointType = PointT;
81  using const_iterator = // NOLINT
83  using iterator = const_iterator; // NOLINT
92  : data_{std::make_shared<CompoundLineStringData>(ls)} {}
93 
95  template <typename OtherT, typename = IfLS<OtherT, void>>
96  explicit CompoundLineStringImpl(const std::vector<OtherT>& lss)
97  : data_{std::make_shared<CompoundLineStringData>(
98  utils::transform(lss, [](const auto& e) { return traits::to3D(traits::toConst(e)); }))} {}
99 
102  : data_(std::move(data)), inverted_{inverted} {}
103 
105  template <typename OtherT>
107  : data_(other.constData()), inverted_{other.inverted()} {}
108 
109  // default the rest (constructor above deletes copy constructors)
110  CompoundLineStringImpl(CompoundLineStringImpl&& rhs) noexcept = default;
111  CompoundLineStringImpl& operator=(CompoundLineStringImpl&& rhs) noexcept = default;
112  CompoundLineStringImpl(const CompoundLineStringImpl& rhs) = default;
113  CompoundLineStringImpl& operator=(const CompoundLineStringImpl& rhs) = default;
114  ~CompoundLineStringImpl() noexcept = default;
115 
122  bool inverted() const noexcept { return inverted_; }
123 
130  size_t size() const noexcept { return std::distance(begin(), end()); }
131 
137  bool empty() const noexcept { return size() == 0; }
138 
147  const_iterator begin() const noexcept { return constData()->pointsBegin(inverted()); }
154  const_iterator end() const noexcept { return constData()->pointsEnd(inverted()); }
155 
163  const PointType& front() const noexcept { return *begin(); }
164 
172  const PointType& back() const noexcept { return *std::prev(end()); }
173 
183  const PointType& operator[](size_t idx) const {
184  assert(idx < size());
185  return *std::next(begin(), idx);
186  }
187 
195  SegmentType segment(size_t idx) const noexcept {
196  assert(idx < size());
197  const auto first = std::next(begin(), idx);
198  const auto second = idx + 1 == size() ? begin() : std::next(first);
199  return SegmentType(*first, *second);
200  }
201 
203  size_t numSegments() const noexcept { return std::max(size_t(1), size()) - 1; }
204 
209  BasicIterator basicBegin() const { return constData()->pointsBegin(inverted()); }
210 
215  BasicIterator basicEnd() const { return constData()->pointsEnd(inverted()); }
227  BasicLineString basicLineString() const { return {basicBegin(), basicEnd()}; }
228 
233  std::shared_ptr<const CompoundLineStringData> constData() const noexcept { return data_; }
234 
236  return inverted()
237  ? utils::invert(utils::transform(data_->lineStrings(), [](const auto& ls) { return ls.invert(); }))
238  : data_->lineStrings();
239  }
240 
245  Ids ids() const {
246  auto ids = utils::transform(data_->lineStrings(), [](const auto& ls) { return ls.id(); });
247  if (inverted()) {
248  return utils::invert(ids);
249  }
250  return ids;
251  }
252 
253  private:
255  bool inverted_{false};
256 };
257 
263 class CompoundLineString2d : public CompoundLineStringImpl<ConstPoint2d> {
264  public:
269  using MutableType = void;
271 
273  : CompoundLineString2d(utils::concatenate(other, [](auto& cls) { return cls.lineStrings(); })) {}
274  CompoundLineString2d() = default; // Not inherited from base class
275 
277  CompoundLineString2d invert() const noexcept { return CompoundLineString2d{constData(), !inverted()}; }
278 };
279 
285 class CompoundLineString3d : public CompoundLineStringImpl<ConstPoint3d> {
286  public:
291  using MutableType = void;
294  : CompoundLineString3d(utils::concatenate(other, [](auto& cls) { return cls.lineStrings(); })) {}
295  CompoundLineString3d() = default; // Not inherited from base class
296 
298  CompoundLineString3d invert() const noexcept { return CompoundLineString3d{constData(), !inverted()}; }
299 };
300 
307  public:
312  using MutableType = void;
315  : CompoundHybridLineString2d(utils::concatenate(other, [](auto& cls) { return cls.lineStrings(); })) {}
316  CompoundHybridLineString2d() = default; // Not inherited from base class
317 
319  CompoundHybridLineString2d invert() const noexcept { return CompoundHybridLineString2d{constData(), !inverted()}; }
320 };
321 
328  public:
333  using MutableType = void;
336  : CompoundHybridLineString3d(utils::concatenate(other, [](auto& cls) { return cls.lineStrings(); })) {}
337  CompoundHybridLineString3d() = default; // Not inherited from base class
338 
340  CompoundHybridLineString3d invert() const noexcept { return CompoundHybridLineString3d{constData(), !inverted()}; }
341 };
342 
343 namespace utils {
354 template <typename PointT>
355 bool has(const CompoundLineStringImpl<PointT>& ls, Id id) {
356  return std::any_of(ls.begin(), ls.end(), [&id](const auto& elem) { return elem.id() == id; });
357 }
358 } // namespace utils
359 
360 template <typename Point1T, typename Point2T>
362  return lhs.lineStrings() == rhs.lineStrings();
363 }
364 
365 template <typename Point1T, typename Point2T>
367  return !(rhs == lhs);
368 }
369 template <typename Point1T, typename Point2T>
370 bool operator==(const CompoundLineStringImpl<Point1T>& lhs, const std::vector<Point2T>& rhs) {
371  return lhs.size() == rhs.size() && std::equal(lhs.begin(), lhs.end(), rhs.begin());
372 }
373 
374 template <typename Point1T, typename Point2T>
375 bool operator==(const std::vector<Point1T>& lhs, const CompoundLineStringImpl<Point2T>& rhs) {
376  return rhs == lhs;
377 }
378 
379 template <typename Point1T, typename Point2T>
380 bool operator!=(const CompoundLineStringImpl<Point1T>& lhs, const std::vector<Point2T>& rhs) {
381  return !(lhs == rhs);
382 }
383 
384 template <typename Point1T, typename Point2T>
385 bool operator!=(const std::vector<Point1T>& lhs, const CompoundLineStringImpl<Point2T>& rhs) {
386  return !(lhs == rhs);
387 }
388 
389 template <typename PointT>
390 inline std::ostream& operator<<(std::ostream& stream, const CompoundLineStringImpl<PointT>& obj) {
391  auto ids = obj.ids();
392  stream << "[";
393  if (!ids.empty()) {
394  stream << "ids: ";
395  std::copy(ids.begin(), ids.end(), std::ostream_iterator<Id>(stream, " "));
396  }
397  if (obj.inverted()) {
398  stream << ", inverted";
399  }
400  return stream << "]";
401 }
402 } // namespace lanelet
std::vector< CompoundLineString2d > CompoundLineStrings2d
Definition: Forward.h:76
CompoundLineStringData(ConstLineStrings3d lineStrings)
CompoundHybridLineString2d(const CompoundHybridLineStrings2d &other)
traits::ConstPointT< ConstPoint2d > ConstPointType
internal::SelectCompoundLsIteratorT< ConstPoint3d > RFIter
const ConstLineStrings3d & lineStrings() const
std::vector< ConstLineString3d > ConstLineStrings3d
Definition: Forward.h:58
std::shared_ptr< const CompoundLineStringData > CompoundLineStringDataConstPtr
Definition: Forward.h:67
typename PointTraits< PointT >::BasicPoint BasicPointT
Definition: Traits.h:156
CompoundLineStringImpl(const ConstLineStrings3d &ls=ConstLineStrings3d())
Construct from a vector of ConstLineString3d.
A Compound linestring in 3d (returns Point3d)
typename SelectCompoundLsIterator< T >::Iterator SelectCompoundLsIteratorT
internal::SelectBasicLineStringT< BasicPointType > BasicLineString
RFIter pointsBegin(bool inverted) const
BasicLineString basicLineString() const
create a basic linestring from this linestring
traits::BasicPointT< ConstPoint2d > BasicPointType
CompoundHybridLineString2d invert() const noexcept
create a new, inverted linestring from this one
ConstPrimitiveType< PrimitiveT > toConst(const PrimitiveT &primitive)
Converts a primitive to its matching const type.
Definition: Traits.h:108
const_iterator end() const noexcept
returns an iterator to end of the points
int64_t Id
Definition: Forward.h:198
typename internal::SelectCompoundLsIterator< ConstPoint3d >::BaseIterator BaseIter
auto transform(Iterator begin, Iterator end, const Func f)
Definition: Utilities.h:176
std::vector< Id > Ids
Definition: Forward.h:200
std::pair< PointT, PointT > Segment
typename PointTraits< PointT >::ConstPoint ConstPointT
Definition: Traits.h:159
VectorT concatenate(ContainerT &&c)
Definition: Utilities.h:63
bool operator==(const Attribute &lhs, const Attribute &rhs)
Definition: Attribute.h:179
A hybrid compound linestring in 2d (returns BasicPoint2d)
size_t numSegments() const noexcept
Returns the number of (geometrically valid) segments.
std::vector< CompoundLineString3d > CompoundLineStrings3d
Definition: Forward.h:77
CompoundLineStringDataConstPtr data_
CompoundHybridLineString3d invert() const noexcept
create a new, inverted linestring from this one
An immutable 2d point.
Ids ids() const
returns the ids of all linestrings in order
Identifies bounding boxes.
Definition: Traits.h:8
internal::SelectCompoundLsIteratorT< ConstPointType > const_iterator
BasicIterator basicBegin() const
returns a normal iterator to the internal point type at begin
CompoundHybridLineString3d(const CompoundHybridLineStrings3d &other)
CompoundLineString3d invert() const noexcept
create a new, inverted linestring from this one
std::shared_ptr< const CompoundLineStringData > constData() const noexcept
returns the internal data on the linestrings managed by this object
const_iterator begin() const noexcept
returns an iterator to the start of the points
CompoundLineString2d(const CompoundLineStrings2d &other)
bool inverted() const noexcept
returns whether this is an inverted CompoundLineString
CompoundLineStringImpl(const CompoundLineStringImpl< OtherT > &other)
construct from other CompoundLineString
RFIter pointsEnd(bool inverted) const
std::reverse_iterator< BaseIter > Reverse
bool operator!=(const Attribute &lhs, const Attribute &rhs)
Definition: Attribute.h:180
bool empty() const noexcept
return whether this contains any points
Common data object for all CompoundLineStrings.
A Compound linestring in 2d (returns Point2d)
This iterator iterates over a container of containers as if it was one single container. Succeeding elements that are equal are ignored.
const PointType & front() const noexcept
returns the first point of the first linestring
bool has(const CompoundLineStringImpl< PointT > &ls, Id id)
returns true if element of a primitive has a matching Id
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...
const ConstLineStrings3d ls_
Optional< double > distance
typename SelectBasicLineString< T >::Type SelectBasicLineStringT
const PointType & operator[](size_t idx) const
returns the point at this position
CompoundLineStringImpl(CompoundLineStringDataConstPtr data, bool inverted)
Internal construction from data pointer.
ConstLineStrings3d lineStrings() const
A hybrid compound linestring in 3d (returns BasicPoint3d)
BasicIterator basicEnd() const
returns a normal iterator for the internal point type at end
Id id
Definition: LaneletMap.cpp:63
An immutable 3d point.
const PointType & back() const noexcept
returns the last point of the last linestring
CompoundLineString3d(const CompoundLineStrings3d &other)
A collection of lineStrings that act as one line string.
CompoundLineStringImpl(const std::vector< OtherT > &lss)
Construct from a vector of LineStrings or CompoundLineStrings.
BoundingBox3d to3D(const BoundingBox2d &primitive)
Container invert(const Container &cont)
Definition: Utilities.h:169
CompoundLineString2d invert() const noexcept
create a new, inverted linestring from this one
size_t size() const noexcept
return the total number of unique points
std::vector< ConstPoint3d > ConstPoints3d
Definition: Forward.h:35
This class selects which iterator CompoundLineStringImpl needs.
Specialization of traits for points.
Definition: Traits.h:133
std::vector< CompoundHybridLineString3d > CompoundHybridLineStrings3d
Definition: Forward.h:79
std::vector< CompoundHybridLineString2d > CompoundHybridLineStrings2d
Definition: Forward.h:78


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Tue Jun 6 2023 02:23:32