Go to the documentation of this file.
2 #include <boost/noncopyable.hpp>
13 template <
typename Po
intT>
40 using Reverse = std::reverse_iterator<BaseIter>;
68 template <
typename Po
intT>
92 :
data_{std::make_shared<CompoundLineStringData>(ls)} {}
95 template <
typename OtherT,
typename = IfLS<OtherT,
void>>
97 :
data_{std::make_shared<CompoundLineStringData>(
105 template <
typename OtherT>
184 assert(idx <
size());
185 return *std::next(
begin(), idx);
196 assert(idx <
size());
197 const auto first = std::next(
begin(), idx);
198 const auto second = idx + 1 ==
size() ?
begin() : std::next(first);
233 std::shared_ptr<const CompoundLineStringData>
constData() const noexcept {
return data_; }
238 :
data_->lineStrings();
354 template <
typename Po
intT>
356 return std::any_of(ls.
begin(), ls.
end(), [&
id](
const auto& elem) { return elem.id() == id; });
360 template <
typename Po
int1T,
typename Po
int2T>
365 template <
typename Po
int1T,
typename Po
int2T>
367 return !(rhs == lhs);
369 template <
typename Po
int1T,
typename Po
int2T>
371 return lhs.
size() == rhs.size() && std::equal(lhs.
begin(), lhs.
end(), rhs.begin());
374 template <
typename Po
int1T,
typename Po
int2T>
379 template <
typename Po
int1T,
typename Po
int2T>
381 return !(lhs == rhs);
384 template <
typename Po
int1T,
typename Po
int2T>
386 return !(lhs == rhs);
389 template <
typename Po
intT>
391 auto ids = obj.
ids();
395 std::copy(ids.begin(), ids.end(), std::ostream_iterator<Id>(stream,
" "));
398 stream <<
", inverted";
400 return stream <<
"]";
CompoundHybridLineString3d(const CompoundHybridLineStrings3d &other)
CompoundLineString2d()=default
std::vector< ConstLineString3d > ConstLineStrings3d
CompoundLineStringImpl(CompoundLineStringDataConstPtr data, bool inverted)
Internal construction from data pointer.
internal::SelectCompoundLsIteratorT< ConstPoint3d > RFIter
std::reverse_iterator< BaseIter > Reverse
A hybrid compound linestring in 2d (returns BasicPoint2d)
CompoundLineString3d()=default
typename SelectCompoundLsIterator< T >::Iterator SelectCompoundLsIteratorT
std::shared_ptr< const CompoundLineStringData > CompoundLineStringDataConstPtr
CompoundLineStringDataConstPtr data_
CompoundHybridLineString2d()=default
Container invert(const Container &cont)
ConstPoints3d points() const
bool operator==(const Attribute &lhs, const Attribute &rhs)
std::ostream & operator<<(std::ostream &stream, const Attribute &obj)
const PointType & operator[](size_t idx) const
returns the point at this position
auto transform(Iterator begin, Iterator end, const Func f)
std::pair< PointT, PointT > Segment
CompoundHybridLineString2d invert() const noexcept
create a new, inverted linestring from this one
RFIter pointsEnd(bool inverted) const
bool inverted() const noexcept
returns whether this is an inverted CompoundLineString
Identifies bounding boxes.
A Compound linestring in 3d (returns Point3d)
CompoundLineStringImpl(const CompoundLineStringImpl< OtherT > &other)
construct from other CompoundLineString
internal::SelectBasicLineStringT< BasicPointType > BasicLineString
CompoundHybridLineString3d invert() const noexcept
create a new, inverted linestring from this one
std::vector< CompoundLineString3d > CompoundLineStrings3d
CompoundHybridLineString2d(const CompoundHybridLineStrings2d &other)
BasicIterator basicEnd() const
returns a normal iterator for the internal point type at end
CompoundLineStringData::RFIter RFIter
std::shared_ptr< const CompoundLineStringData > constData() const noexcept
returns the internal data on the linestrings managed by this object
CompoundLineString3d invert() const noexcept
create a new, inverted linestring from this one
typename internal::SelectCompoundLsIterator< ConstPoint3d >::BaseIterator BaseIter
Segment< ConstPointType > SegmentType
size_t numSegments() const noexcept
Returns the number of (geometrically valid) segments.
static constexpr traits::Dimensions Dimension
BasicIterator basicBegin() const
returns a normal iterator to the internal point type at begin
~CompoundLineStringImpl() noexcept=default
A hybrid compound linestring in 3d (returns BasicPoint3d)
BasicLineString basicLineString() const
create a basic linestring from this linestring
const ConstLineStrings3d & lineStrings() const
Ids ids() const
returns the ids of all linestrings in order
internal::SelectCompoundLsIteratorT< ConstPointType > const_iterator
CompoundLineStringImpl(const ConstLineStrings3d &ls=ConstLineStrings3d())
Construct from a vector of ConstLineString3d.
bool operator!=(const Attribute &lhs, const Attribute &rhs)
typename SelectBasicLineString< T >::Type SelectBasicLineStringT
Common data object for all CompoundLineStrings.
CompoundLineStringImpl & operator=(CompoundLineStringImpl &&rhs) noexcept=default
ConstPrimitiveType< PrimitiveT > toConst(const PrimitiveT &primitive)
Converts a primitive to its matching const type.
traits::ConstPointT< ConstPoint2d > ConstPointType
CompoundHybridLineString3d()=default
This iterator iterates over a container of containers as if it was one single container....
RFIter pointsBegin(bool inverted) const
CompoundLineString3d(const CompoundLineStrings3d &other)
bool has(const ConstArea &ll, Id id)
returns true if element of a regulatory element has a matching Id
traits::BasicPointT< ConstPoint2d > BasicPointType
const PointType & front() const noexcept
returns the first point of the first linestring
A Compound linestring in 2d (returns Point2d)
CompoundLineString2d invert() const noexcept
create a new, inverted linestring from this one
const_iterator end() const noexcept
returns an iterator to end of the points
size_t size() const noexcept
return the total number of unique points
std::vector< ConstPoint3d > ConstPoints3d
const PointType & back() const noexcept
returns the last point of the last linestring
VectorT concatenate(ContainerT &&c)
Optional< double > distance
A collection of lineStrings that act as one line string.
Specialization of traits for points.
ConstLineStrings3d lineStrings() const
typename PointTraits< PointT >::BasicPoint BasicPointT
bool empty() const noexcept
return whether this contains any points
std::vector< CompoundHybridLineString3d > CompoundHybridLineStrings3d
typename PointTraits< PointT >::ConstPoint ConstPointT
std::vector< CompoundHybridLineString2d > CompoundHybridLineStrings2d
CompoundLineString2d(const CompoundLineStrings2d &other)
This class selects which iterator CompoundLineStringImpl needs.
std::vector< CompoundLineString2d > CompoundLineStrings2d
const_iterator begin() const noexcept
returns an iterator to the start of the points
BoundingBox3d to3D(const BoundingBox2d &primitive)
CompoundLineStringData(ConstLineStrings3d lineStrings)
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_
CompoundLineStringImpl(const std::vector< OtherT > &lss)
Construct from a vector of LineStrings or CompoundLineStrings.
lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52