Template Class CompoundLineStringImpl

Class Documentation

template<typename PointT>
class CompoundLineStringImpl

A collection of lineStrings that act as one line string.

A CompoundLineString has the same interface as a LineString2d/LineString3d, but internally accesses the points of multiple linestrings. Because it just provides an interface to the points, the internal data can not be modified. If adjacent linestrings share the same points, one of them is discarded.

Template Parameters:

PointT – the point type that the linestring returns

Public Types

using DataType = CompoundLineStringData
using PointType = PointT
using BasicPointType = traits::BasicPointT<PointT>
using ConstPointType = traits::ConstPointT<PointT>
using Category = traits::LineStringTag
using BasicIterator = internal::TransformIterator<RFIter, const BasicPointType>
using const_iterator = internal::SelectCompoundLsIteratorT<ConstPointType>
using iterator = const_iterator
using BasicLineString = internal::SelectBasicLineStringT<BasicPointType>
using SegmentType = Segment<ConstPointType>

Public Functions

inline explicit CompoundLineStringImpl(const ConstLineStrings3d &ls = ConstLineStrings3d())

Construct from a vector of ConstLineString3d.

Parameters:

ls – objects to construct from. The order will also be the order of the linestrings.

template<typename OtherT, typename = IfLS<OtherT, void>>
inline explicit CompoundLineStringImpl(const std::vector<OtherT> &lss)

Construct from a vector of LineStrings or CompoundLineStrings.

inline CompoundLineStringImpl(CompoundLineStringDataConstPtr data, bool inverted)

Internal construction from data pointer.

template<typename OtherT>
inline explicit CompoundLineStringImpl(const CompoundLineStringImpl<OtherT> &other)

construct from other CompoundLineString

CompoundLineStringImpl(CompoundLineStringImpl &&rhs) noexcept = default
CompoundLineStringImpl &operator=(CompoundLineStringImpl &&rhs) noexcept = default
CompoundLineStringImpl(const CompoundLineStringImpl &rhs) = default
CompoundLineStringImpl &operator=(const CompoundLineStringImpl &rhs) = default
~CompoundLineStringImpl() noexcept = default
inline bool inverted() const noexcept

returns whether this is an inverted CompoundLineString

Inverted linestrings behave just as normal linestrings but provide access to the points in inverted order.

inline size_t size() const noexcept

return the total number of unique points

Unique means that adjacent points with the same id are not counted. Note that this O(n) in the number of points, not O(0).

inline bool empty() const noexcept

return whether this contains any points

Note this is O(n) in the number of points.

inline const_iterator begin() const noexcept

returns an iterator to the start of the points

Dereferencing the iterator will convert the point from the internal Point3d to PointT. It will return the first point of the first linestring.

See also

end, basicBegin

inline const_iterator end() const noexcept

returns an iterator to end of the points

See also

begin, basicEnd Dereferencing the iterator will convert the point from the internal Point3d to PointType

inline const PointType &front() const noexcept

returns the first point of the first linestring

See also

back, at The internal point type is a different one, but because all points inherit from the internal point type, no slicing is possible. It will return the first point of the first linestring.

inline const PointType &back() const noexcept

returns the last point of the last linestring

The internal point type is a different one, but because all points inherit from the internal point type, no slicing is possible.

See also

front, at

inline const PointType &operator[](size_t idx) const

returns the point at this position

The internal point type is a different one, but because all points inherit from the internal point type, no slicing is possible.

See also

front

Note this is O(n) in the number of points, not O(0)

inline 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.

It is not a good idea to use this in a loop, because this has O(n) for every iteration. Use helper::forEachSegment instead.

inline size_t numSegments() const noexcept

Returns the number of (geometrically valid) segments.

inline BasicIterator basicBegin() const

returns a normal iterator to the internal point type at begin

See also

basicEnd, begin

inline BasicIterator basicEnd() const

returns a normal iterator for the internal point type at end

See also

basicBegin, end

inline BasicLineString basicLineString() const

create a basic linestring from this linestring

A basic linestring is a simple vector with eigen points. You can do what you want with these points, because changes to them will not affect lanelet objects.

BasicLineString is registered with boost::geometry, therefore you can use it for geometry calculations.

Returns:

the basic linestring

inline std::shared_ptr<const CompoundLineStringData> constData() const noexcept

returns the internal data on the linestrings managed by this object

inline ConstLineStrings3d lineStrings() const
inline Ids ids() const

returns the ids of all linestrings in order

Returns:

list of ids

Public Static Attributes

static constexpr traits::Dimensions Dimension = traits::PointTraits<PointT>::Dimension