Public Types | Public Member Functions | List of all members
lanelet::ConstHybridLineString2d Class Reference

A Linestring that returns BasicPoint2d instead of Point2d. More...

#include <LineString.h>

Inheritance diagram for lanelet::ConstHybridLineString2d:
Inheritance graph
[legend]

Public Types

using const_iterator = BasicIterator
 
using ConstType = ConstHybridLineString2d
 
using iterator = BasicIterator
 
using PointType = BasicPointType
 
using SegmentType = Segment< BasicPointType >
 
using ThreeDType = ConstHybridLineString3d
 
using TwoDType = ConstHybridLineString2d
 
- Public Types inherited from lanelet::ConstLineString2d
using ConstType = ConstLineString2d
 
using HybridType = ConstHybridLineString2d
 
using MutableType = LineString2d
 
using ThreeDType = ConstLineString3d
 
using TwoDType = ConstLineString2d
 
- Public Types inherited from lanelet::ConstLineStringImpl< Point2d >
using BasicIterator = internal::TransformIterator< const_iterator, const BasicPointType >
 
using BasicLineString = internal::SelectBasicLineStringT< BasicPointType >
 
using BasicPointType = traits::BasicPointT< Point2d >
 
using Category = traits::LineStringTag
 
using const_iterator = internal::SelectLsIteratorT< const ConstPointType >
 
using ConstPointType = traits::ConstPointT< Point2d >
 
using ConstSegmentType = traits::ConstPrimitiveType< SegmentType >
 
using difference_type = typename iterator::difference_type
 
using iterator = const_iterator
 
using MutablePointType = traits::MutablePointT< Point2d >
 linestring will return this point type More...
 
using PointType = ConstPointType
 
using SegmentType = Segment< Point2d >
 
using size_type = size_t
 
using value_type = ConstPointType
 
- Public Types inherited from lanelet::ConstPrimitive< LineStringData >
using DataType = LineStringData
 

Public Member Functions

const BasicPointTypeback () const noexcept
 Get last BasicPoint2d. More...
 
BasicIterator begin () const noexcept
 BasicPoint2d Iterator to begin. More...
 
 ConstHybridLineString2d ()=default
 
 ConstHybridLineString2d (const ConstLineString2d &ls)
 
 ConstHybridLineString2d (const LineString2d &ls)
 
 ConstLineString2d ()=default
 
BasicIterator end () const noexcept
 BasicPoint2d Iterator to past-the-end. More...
 
const BasicPointTypefront () const noexcept
 Get first BasicPoint2d. More...
 
ConstHybridLineString2d invert () const noexcept
 Returns an inverted linestring, O(0) More...
 
const BasicPointTypeoperator[] (size_t idx) const noexcept
 access element at specific 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...
 
- Public Member Functions inherited from lanelet::ConstLineString2d
 ConstLineString2d ()=default
 
 ConstLineStringImpl (const ConstLineStringImpl &rhs)=default
 
template<typename OtherT >
 ConstLineStringImpl (const ConstLineStringImpl< OtherT > &other)
 construct from other ConstLineStrings More...
 
 ConstLineStringImpl (const std::shared_ptr< const LineStringData > &data, bool inverted=false)
 Constructs a linestring from the data object of another linestring. More...
 
 ConstLineStringImpl (ConstLineStringImpl &&rhs) noexcept=default
 
 ConstLineStringImpl (Id id=InvalId, Points3d points=Points3d(), const AttributeMap &attributes=AttributeMap())
 Constructs a LineString or similar from an Id and a list of points. More...
 
ConstLineString2d invert () const noexcept
 create a new, inverted linestring from this one More...
 
- Public Member Functions inherited from lanelet::ConstLineStringImpl< Point2d >
const ConstPointTypeback () const noexcept
 returns the last point (if it exist) More...
 
BasicIterator basicBegin () const noexcept
 returns a normal iterator to the internal point type at begin More...
 
BasicIterator basicEnd () const noexcept
 returns a normal iterator for the internal point type at end More...
 
BasicLineString basicLineString () const noexcept
 Create a basic linestring (ie a vector of Eigen Points) More...
 
const_iterator begin () const noexcept
 Returns an iterator to the start of the points. More...
 
 ConstLineStringImpl (const ConstLineStringImpl< OtherT > &other)
 construct from other ConstLineStrings More...
 
 ConstLineStringImpl (const std::shared_ptr< const LineStringData > &data, bool inverted=false)
 Constructs a linestring from the data object of another linestring. More...
 
 ConstLineStringImpl (Id id=InvalId, Points3d points=Points3d(), const AttributeMap &attributes=AttributeMap())
 Constructs a LineString or similar from an Id and a list of points. More...
 
bool empty () const noexcept
 return if there are any points in this object More...
 
const_iterator end () const noexcept
 Returns an iterator to end of the points. More...
 
const ConstPointTypefront () const noexcept
 returns the first point (if it exist) More...
 
bool inverted () const noexcept
 Returns whether this is an inverted linestring. More...
 
size_t numSegments () const noexcept
 Returns the number of (geometrically valid) segments. More...
 
const ConstPointTypeoperator[] (size_t idx) const noexcept
 returns the point at this position More...
 
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. More...
 
size_t size () const noexcept
 Return the number of points in this linestring. More...
 
- Public Member Functions inherited from lanelet::ConstPrimitive< LineStringData >
const Attributeattribute (AttributeName name) const
 retrieve an attribute (enum version) More...
 
const Attributeattribute (const std::string &name) const
 retrieve an attribute More...
 
attributeOr (AttributeName name, T defaultVal) const
 retrieve an attribute (enum version) More...
 
attributeOr (const std::string &name, T defaultVal) const noexcept
 retrieve an attribute (string version) More...
 
const AttributeMapattributes () const
 get the attributes of this primitive More...
 
const std::shared_ptr< const LineStringData > & constData () const
 get the internal data of this primitive More...
 
 ConstPrimitive (const std::shared_ptr< const LineStringData > &data)
 Construct from a pointer to the data. More...
 
bool hasAttribute (AttributeName name) const noexcept
 check for an attribute (enum version) More...
 
bool hasAttribute (const std::string &name) const noexcept
 check whether this primitive has a specific attribute More...
 
Id id () const noexcept
 get the unique id of this primitive More...
 
bool operator!= (const ConstPrimitive &rhs) const
 
bool operator== (const ConstPrimitive &rhs) const
 

Additional Inherited Members

- Static Public Attributes inherited from lanelet::ConstLineStringImpl< Point2d >
static constexpr traits::Dimensions Dimension
 
- Static Public Attributes inherited from lanelet::ConstPrimitive< LineStringData >
static constexpr bool IsConst
 
- Protected Member Functions inherited from lanelet::ConstLineStringImpl< Point2d >
 ConstLineStringImpl (const ConstLineStringImpl &rhs)=default
 
 ConstLineStringImpl (ConstLineStringImpl &&rhs) noexcept=default
 
ConstLineStringImploperator= (const ConstLineStringImpl &rhs)=default
 
ConstLineStringImploperator= (ConstLineStringImpl &&rhs) noexcept=default
 
 ~ConstLineStringImpl () noexcept=default
 
- Protected Member Functions inherited from lanelet::ConstPrimitive< LineStringData >
 ConstPrimitive (const ConstPrimitive &rhs)=default
 
 ConstPrimitive (ConstPrimitive &&rhs) noexcept=default
 
ConstPrimitiveoperator= (const ConstPrimitive &rhs)=default
 
ConstPrimitiveoperator= (ConstPrimitive &&rhs) noexcept=default
 
 ~ConstPrimitive () noexcept=default
 

Detailed Description

A Linestring that returns BasicPoint2d instead of Point2d.

For usage with boost::geometry. Has no mutable version.

Definition at line 636 of file primitives/LineString.h.

Member Typedef Documentation

◆ const_iterator

Definition at line 639 of file primitives/LineString.h.

◆ ConstType

Definition at line 641 of file primitives/LineString.h.

◆ iterator

Definition at line 640 of file primitives/LineString.h.

◆ PointType

Definition at line 638 of file primitives/LineString.h.

◆ SegmentType

Definition at line 644 of file primitives/LineString.h.

◆ ThreeDType

Definition at line 643 of file primitives/LineString.h.

◆ TwoDType

Definition at line 642 of file primitives/LineString.h.

Constructor & Destructor Documentation

◆ ConstHybridLineString2d() [1/3]

lanelet::ConstHybridLineString2d::ConstHybridLineString2d ( )
default

◆ ConstHybridLineString2d() [2/3]

lanelet::ConstHybridLineString2d::ConstHybridLineString2d ( const ConstLineString2d ls)
inlineexplicit

Definition at line 648 of file primitives/LineString.h.

◆ ConstHybridLineString2d() [3/3]

lanelet::ConstHybridLineString2d::ConstHybridLineString2d ( const LineString2d ls)
inlineexplicit

Definition at line 649 of file primitives/LineString.h.

Member Function Documentation

◆ back()

const BasicPointType& lanelet::ConstHybridLineString2d::back ( ) const
inlinenoexcept

Get last BasicPoint2d.

Definition at line 664 of file primitives/LineString.h.

◆ begin()

BasicIterator lanelet::ConstHybridLineString2d::begin ( ) const
inlinenoexcept

BasicPoint2d Iterator to begin.

Definition at line 655 of file primitives/LineString.h.

◆ ConstLineString2d()

lanelet::ConstLineString2d::ConstLineString2d
default

◆ end()

BasicIterator lanelet::ConstHybridLineString2d::end ( ) const
inlinenoexcept

BasicPoint2d Iterator to past-the-end.

Definition at line 658 of file primitives/LineString.h.

◆ front()

const BasicPointType& lanelet::ConstHybridLineString2d::front ( ) const
inlinenoexcept

Get first BasicPoint2d.

Definition at line 661 of file primitives/LineString.h.

◆ invert()

ConstHybridLineString2d lanelet::ConstHybridLineString2d::invert ( ) const
inlinenoexcept

Returns an inverted linestring, O(0)

Definition at line 652 of file primitives/LineString.h.

◆ operator[]()

const BasicPointType& lanelet::ConstHybridLineString2d::operator[] ( size_t  idx) const
inlinenoexcept

access element at specific position

Definition at line 667 of file primitives/LineString.h.

◆ segment()

SegmentType lanelet::ConstHybridLineString2d::segment ( size_t  idx) const
inlinenoexcept

returns the n-th segment. If n equals size() -1, the segment from back() to front() is returned.

Definition at line 675 of file primitives/LineString.h.


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


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52