Template Class ConstLineStringImpl

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

template<typename PointT>
class ConstLineStringImpl : public lanelet::ConstPrimitive<LineStringData>

Implementation template class that is common to all LineStrings.

Public Types

using BasicPointType = traits::BasicPointT<PointT>
using ConstPointType = traits::ConstPointT<PointT>
using PointType = ConstPointType
using MutablePointType = traits::MutablePointT<PointT>

linestring will return this point type

using Category = traits::LineStringTag
using const_iterator = internal::SelectLsIteratorT<const ConstPointType>
using iterator = const_iterator
using value_type = ConstPointType
using size_type = size_t
using difference_type = typename iterator::difference_type
using BasicIterator = internal::TransformIterator<const_iterator, const BasicPointType>
using BasicLineString = internal::SelectBasicLineStringT<BasicPointType>
using SegmentType = Segment<PointT>
using ConstSegmentType = traits::ConstPrimitiveType<SegmentType>

Public Functions

inline explicit ConstLineStringImpl(Id id = InvalId, Points3d points = Points3d(), const AttributeMap &attributes = AttributeMap())

Constructs a LineString or similar from an Id and a list of points.

inline explicit ConstLineStringImpl(const std::shared_ptr<const LineStringData> &data, bool inverted = false)

Constructs a linestring from the data object of another linestring.

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

construct from other ConstLineStrings

inline bool inverted() const noexcept

Returns whether this is an inverted linestring.

inline size_t size() const noexcept

Return the number of points in this linestring.

inline bool empty() const noexcept

return if there are any points in this object

inline const_iterator begin() const noexcept

Returns an iterator to the start of the points.

See also

end, basicBegin Dereferencing the iterator will convert the point from the internal Point3d to PointType

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 ConstPointType &front() const noexcept

returns the first point (if it exist)

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.

inline const ConstPointType &back() const noexcept

returns the last point (if it exist)

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, operator[]

inline const ConstPointType &operator[](size_t idx) const noexcept

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, operator[]

inline BasicIterator basicBegin() const noexcept

returns a normal iterator to the internal point type at begin

See also

basicEnd, begin

inline BasicIterator basicEnd() const noexcept

returns a normal iterator for the internal point type at end

See also

basicBegin, end

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

inline size_t numSegments() const noexcept

Returns the number of (geometrically valid) segments.

inline BasicLineString basicLineString() const noexcept

Create a basic linestring (ie a vector of Eigen Points)

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.

Public Static Attributes

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

Protected Functions

ConstLineStringImpl(ConstLineStringImpl &&rhs) noexcept = default
ConstLineStringImpl &operator=(ConstLineStringImpl &&rhs) noexcept = default
ConstLineStringImpl(const ConstLineStringImpl &rhs) = default
ConstLineStringImpl &operator=(const ConstLineStringImpl &rhs) = default
~ConstLineStringImpl() noexcept = default
template<typename LineStringT>
class CompoundLineString