Public Types | Public Member Functions | Static Public Attributes | Private Types | Private Attributes | List of all members
lanelet::CompoundLineStringImpl< PointT > Class Template Reference

A collection of lineStrings that act as one line string. More...

#include <CompoundLineString.h>

Public Types

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

Public Member Functions

const PointTypeback () const noexcept
 returns the last point of the last linestring More...
 
BasicIterator basicBegin () const
 returns a normal iterator to the internal point type at begin More...
 
BasicIterator basicEnd () const
 returns a normal iterator for the internal point type at end More...
 
BasicLineString basicLineString () const
 create a basic linestring from this linestring More...
 
const_iterator begin () const noexcept
 returns an iterator to the start of the points More...
 
 CompoundLineStringImpl (const ConstLineStrings3d &ls=ConstLineStrings3d())
 Construct from a vector of ConstLineString3d. More...
 
template<typename OtherT , typename = IfLS<OtherT, void>>
 CompoundLineStringImpl (const std::vector< OtherT > &lss)
 Construct from a vector of LineStrings or CompoundLineStrings. More...
 
 CompoundLineStringImpl (CompoundLineStringDataConstPtr data, bool inverted)
 Internal construction from data pointer. More...
 
template<typename OtherT >
 CompoundLineStringImpl (const CompoundLineStringImpl< OtherT > &other)
 construct from other CompoundLineString More...
 
 CompoundLineStringImpl (CompoundLineStringImpl &&rhs) noexcept=default
 
 CompoundLineStringImpl (const CompoundLineStringImpl &rhs)=default
 
std::shared_ptr< const CompoundLineStringDataconstData () const noexcept
 returns the internal data on the linestrings managed by this object More...
 
bool empty () const noexcept
 return whether this contains any points More...
 
const_iterator end () const noexcept
 returns an iterator to end of the points More...
 
const PointTypefront () const noexcept
 returns the first point of the first linestring More...
 
Ids ids () const
 returns the ids of all linestrings in order More...
 
bool inverted () const noexcept
 returns whether this is an inverted CompoundLineString More...
 
ConstLineStrings3d lineStrings () const
 
size_t numSegments () const noexcept
 Returns the number of (geometrically valid) segments. More...
 
CompoundLineStringImploperator= (CompoundLineStringImpl &&rhs) noexcept=default
 
CompoundLineStringImploperator= (const CompoundLineStringImpl &rhs)=default
 
const PointTypeoperator[] (size_t idx) const
 returns the point at this position More...
 
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. More...
 
size_t size () const noexcept
 return the total number of unique points More...
 
 ~CompoundLineStringImpl () noexcept=default
 

Static Public Attributes

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

Private Types

using RFIter = CompoundLineStringData::RFIter
 

Private Attributes

CompoundLineStringDataConstPtr data_
 
bool inverted_ {false}
 

Detailed Description

template<typename PointT>
class lanelet::CompoundLineStringImpl< PointT >

A collection of lineStrings that act as one line string.

Template Parameters
PointTthe point type that the linestring returns

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.

Definition at line 69 of file CompoundLineString.h.

Member Typedef Documentation

◆ BasicIterator

Definition at line 80 of file CompoundLineString.h.

◆ BasicLineString

Definition at line 84 of file CompoundLineString.h.

◆ BasicPointType

template<typename PointT>
using lanelet::CompoundLineStringImpl< PointT >::BasicPointType = traits::BasicPointT<PointT>

Definition at line 76 of file CompoundLineString.h.

◆ Category

template<typename PointT>
using lanelet::CompoundLineStringImpl< PointT >::Category = traits::LineStringTag

Definition at line 78 of file CompoundLineString.h.

◆ const_iterator

Definition at line 82 of file CompoundLineString.h.

◆ ConstPointType

template<typename PointT>
using lanelet::CompoundLineStringImpl< PointT >::ConstPointType = traits::ConstPointT<PointT>

Definition at line 77 of file CompoundLineString.h.

◆ DataType

template<typename PointT>
using lanelet::CompoundLineStringImpl< PointT >::DataType = CompoundLineStringData

Definition at line 74 of file CompoundLineString.h.

◆ iterator

template<typename PointT>
using lanelet::CompoundLineStringImpl< PointT >::iterator = const_iterator

Definition at line 83 of file CompoundLineString.h.

◆ PointType

template<typename PointT>
using lanelet::CompoundLineStringImpl< PointT >::PointType = PointT

Definition at line 75 of file CompoundLineString.h.

◆ RFIter

template<typename PointT>
using lanelet::CompoundLineStringImpl< PointT >::RFIter = CompoundLineStringData::RFIter
private

Definition at line 70 of file CompoundLineString.h.

◆ SegmentType

template<typename PointT>
using lanelet::CompoundLineStringImpl< PointT >::SegmentType = Segment<ConstPointType>

Definition at line 85 of file CompoundLineString.h.

Constructor & Destructor Documentation

◆ CompoundLineStringImpl() [1/6]

template<typename PointT>
lanelet::CompoundLineStringImpl< PointT >::CompoundLineStringImpl ( const ConstLineStrings3d ls = ConstLineStrings3d())
inlineexplicit

Construct from a vector of ConstLineString3d.

Parameters
lsobjects to construct from. The order will also be the order of the linestrings.

Definition at line 91 of file CompoundLineString.h.

◆ CompoundLineStringImpl() [2/6]

template<typename PointT>
template<typename OtherT , typename = IfLS<OtherT, void>>
lanelet::CompoundLineStringImpl< PointT >::CompoundLineStringImpl ( const std::vector< OtherT > &  lss)
inlineexplicit

Construct from a vector of LineStrings or CompoundLineStrings.

Definition at line 96 of file CompoundLineString.h.

◆ CompoundLineStringImpl() [3/6]

template<typename PointT>
lanelet::CompoundLineStringImpl< PointT >::CompoundLineStringImpl ( CompoundLineStringDataConstPtr  data,
bool  inverted 
)
inline

Internal construction from data pointer.

Definition at line 101 of file CompoundLineString.h.

◆ CompoundLineStringImpl() [4/6]

template<typename PointT>
template<typename OtherT >
lanelet::CompoundLineStringImpl< PointT >::CompoundLineStringImpl ( const CompoundLineStringImpl< OtherT > &  other)
inlineexplicit

construct from other CompoundLineString

Definition at line 106 of file CompoundLineString.h.

◆ CompoundLineStringImpl() [5/6]

template<typename PointT>
lanelet::CompoundLineStringImpl< PointT >::CompoundLineStringImpl ( CompoundLineStringImpl< PointT > &&  rhs)
defaultnoexcept

◆ CompoundLineStringImpl() [6/6]

template<typename PointT>
lanelet::CompoundLineStringImpl< PointT >::CompoundLineStringImpl ( const CompoundLineStringImpl< PointT > &  rhs)
default

◆ ~CompoundLineStringImpl()

template<typename PointT>
lanelet::CompoundLineStringImpl< PointT >::~CompoundLineStringImpl ( )
defaultnoexcept

Member Function Documentation

◆ back()

template<typename PointT>
const PointType& lanelet::CompoundLineStringImpl< PointT >::back ( ) const
inlinenoexcept

returns the last point of the last linestring

See also
front, at

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

Definition at line 172 of file CompoundLineString.h.

◆ basicBegin()

template<typename PointT>
BasicIterator lanelet::CompoundLineStringImpl< PointT >::basicBegin ( ) const
inline

returns a normal iterator to the internal point type at begin

See also
basicEnd, begin

Definition at line 209 of file CompoundLineString.h.

◆ basicEnd()

template<typename PointT>
BasicIterator lanelet::CompoundLineStringImpl< PointT >::basicEnd ( ) const
inline

returns a normal iterator for the internal point type at end

See also
basicBegin, end

Definition at line 215 of file CompoundLineString.h.

◆ basicLineString()

template<typename PointT>
BasicLineString lanelet::CompoundLineStringImpl< PointT >::basicLineString ( ) const
inline

create a basic linestring from this linestring

Returns
the basic 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.

Definition at line 227 of file CompoundLineString.h.

◆ begin()

template<typename PointT>
const_iterator lanelet::CompoundLineStringImpl< PointT >::begin ( ) const
inlinenoexcept

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 PointT. It will return the first point of the first linestring.

Definition at line 147 of file CompoundLineString.h.

◆ constData()

template<typename PointT>
std::shared_ptr<const CompoundLineStringData> lanelet::CompoundLineStringImpl< PointT >::constData ( ) const
inlinenoexcept

returns the internal data on the linestrings managed by this object

Definition at line 233 of file CompoundLineString.h.

◆ empty()

template<typename PointT>
bool lanelet::CompoundLineStringImpl< PointT >::empty ( ) const
inlinenoexcept

return whether this contains any points

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

Definition at line 137 of file CompoundLineString.h.

◆ end()

template<typename PointT>
const_iterator lanelet::CompoundLineStringImpl< PointT >::end ( ) const
inlinenoexcept

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

Definition at line 154 of file CompoundLineString.h.

◆ front()

template<typename PointT>
const PointType& lanelet::CompoundLineStringImpl< PointT >::front ( ) const
inlinenoexcept

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.

Definition at line 163 of file CompoundLineString.h.

◆ ids()

template<typename PointT>
Ids lanelet::CompoundLineStringImpl< PointT >::ids ( ) const
inline

returns the ids of all linestrings in order

Returns
list of ids

Definition at line 245 of file CompoundLineString.h.

◆ inverted()

template<typename PointT>
bool lanelet::CompoundLineStringImpl< PointT >::inverted ( ) const
inlinenoexcept

returns whether this is an inverted CompoundLineString

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

Definition at line 122 of file CompoundLineString.h.

◆ lineStrings()

template<typename PointT>
ConstLineStrings3d lanelet::CompoundLineStringImpl< PointT >::lineStrings ( ) const
inline

Definition at line 235 of file CompoundLineString.h.

◆ numSegments()

template<typename PointT>
size_t lanelet::CompoundLineStringImpl< PointT >::numSegments ( ) const
inlinenoexcept

Returns the number of (geometrically valid) segments.

Definition at line 203 of file CompoundLineString.h.

◆ operator=() [1/2]

template<typename PointT>
CompoundLineStringImpl& lanelet::CompoundLineStringImpl< PointT >::operator= ( CompoundLineStringImpl< PointT > &&  rhs)
defaultnoexcept

◆ operator=() [2/2]

template<typename PointT>
CompoundLineStringImpl& lanelet::CompoundLineStringImpl< PointT >::operator= ( const CompoundLineStringImpl< PointT > &  rhs)
default

◆ operator[]()

template<typename PointT>
const PointType& lanelet::CompoundLineStringImpl< PointT >::operator[] ( size_t  idx) const
inline

returns the point at this position

See also
front

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

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

Definition at line 183 of file CompoundLineString.h.

◆ segment()

template<typename PointT>
SegmentType lanelet::CompoundLineStringImpl< PointT >::segment ( size_t  idx) const
inlinenoexcept

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.

Definition at line 195 of file CompoundLineString.h.

◆ size()

template<typename PointT>
size_t lanelet::CompoundLineStringImpl< PointT >::size ( ) const
inlinenoexcept

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

Definition at line 130 of file CompoundLineString.h.

Member Data Documentation

◆ data_

template<typename PointT>
CompoundLineStringDataConstPtr lanelet::CompoundLineStringImpl< PointT >::data_
private

Definition at line 254 of file CompoundLineString.h.

◆ Dimension

template<typename PointT>
constexpr traits::Dimensions lanelet::CompoundLineStringImpl< PointT >::Dimension = traits::PointTraits<PointT>::Dimension
static

Definition at line 79 of file CompoundLineString.h.

◆ inverted_

template<typename PointT>
bool lanelet::CompoundLineStringImpl< PointT >::inverted_ {false}
private

Definition at line 255 of file CompoundLineString.h.


The documentation for this class was generated from the following file:


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