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

Polygon with access to primitive points. More...

#include <Polygon.h>

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

Public Types

using const_iterator = BasicIterator
 
using ConstType = ConstHybridPolygon3d
 
using iterator = BasicIterator
 
using PointType = BasicPoint3d
 
using ThreeDType = ConstHybridPolygon3d
 
using TwoDType = ConstHybridPolygon2d
 
- Public Types inherited from lanelet::ConstPolygon3d
using Category = traits::PolygonTag
 
using ConstType = ConstPolygon3d
 
using HybridType = ConstHybridPolygon3d
 
using MutableType = Polygon3d
 
using ThreeDType = ConstPolygon3d
 
using TwoDType = ConstPolygon2d
 
- Public Types inherited from lanelet::ConstLineStringImpl< Point3d >
using BasicIterator = internal::TransformIterator< const_iterator, const BasicPointType >
 
using BasicLineString = internal::SelectBasicLineStringT< BasicPointType >
 
using BasicPointType = traits::BasicPointT< Point3d >
 
using Category = traits::LineStringTag
 
using const_iterator = internal::SelectLsIteratorT< const ConstPointType >
 
using ConstPointType = traits::ConstPointT< Point3d >
 
using ConstSegmentType = traits::ConstPrimitiveType< SegmentType >
 
using difference_type = typename iterator::difference_type
 
using iterator = const_iterator
 
using MutablePointType = traits::MutablePointT< Point3d >
 linestring will return this point type More...
 
using PointType = ConstPointType
 
using SegmentType = Segment< Point3d >
 
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 BasicPoint3d. More...
 
BasicIterator begin () const noexcept
 BasicPoint3d Iterator to begin. More...
 
 ConstHybridPolygon3d ()=default
 
 ConstHybridPolygon3d (const ConstPolygon3d &poly)
 Conversion from ConstPolygon3d. More...
 
 ConstPolygon3d ()=default
 
 ConstPolygon3d (const ConstLineString3d &other)
 
BasicIterator end () const noexcept
 BasicPoint3d Iterator to past-the-end. More...
 
const BasicPointTypefront () const noexcept
 Get first BasicPoint3d. More...
 
const BasicPointTypeoperator[] (size_t idx) const noexcept
 access BasicPoint3d at specific position More...
 
- Public Member Functions inherited from lanelet::ConstPolygon3d
BasicPolygon3d basicPolygon () const
 create a simple 3d polygon from this (just a vector) More...
 
 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...
 
 ConstPolygon3d ()=default
 
 ConstPolygon3d (const ConstLineString3d &other)
 
size_t numSegments () const noexcept
 Returns the number of (geometrically valid) segments. More...
 
 operator BasicPolygon3d () const
 implicit conversion to a basic polygon More...
 
 operator ConstLineString3d () const
 
- Public Member Functions inherited from lanelet::ConstLineStringImpl< Point3d >
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< Point3d >
static constexpr traits::Dimensions Dimension
 
- Static Public Attributes inherited from lanelet::ConstPrimitive< LineStringData >
static constexpr bool IsConst
 
- Protected Member Functions inherited from lanelet::ConstLineStringImpl< Point3d >
 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

Polygon with access to primitive points.

This polygon tries to behave as close to a BasicPolygon3d as possible while still keeping all properties (id, attributes) of a ConstPolygon. This is important as some functions of boost::geometry do not like our ConstPoint type.

As with all lanelet primitives, conversion from other primitives is cheap.

Definition at line 228 of file primitives/Polygon.h.

Member Typedef Documentation

◆ const_iterator

Definition at line 230 of file primitives/Polygon.h.

◆ ConstType

Definition at line 234 of file primitives/Polygon.h.

◆ iterator

Definition at line 231 of file primitives/Polygon.h.

◆ PointType

Definition at line 237 of file primitives/Polygon.h.

◆ ThreeDType

Definition at line 236 of file primitives/Polygon.h.

◆ TwoDType

Definition at line 235 of file primitives/Polygon.h.

Constructor & Destructor Documentation

◆ ConstHybridPolygon3d() [1/2]

lanelet::ConstHybridPolygon3d::ConstHybridPolygon3d ( )
default

◆ ConstHybridPolygon3d() [2/2]

lanelet::ConstHybridPolygon3d::ConstHybridPolygon3d ( const ConstPolygon3d poly)
inlineexplicit

Conversion from ConstPolygon3d.

Definition at line 242 of file primitives/Polygon.h.

Member Function Documentation

◆ back()

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

Get last BasicPoint3d.

Definition at line 254 of file primitives/Polygon.h.

◆ begin()

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

BasicPoint3d Iterator to begin.

Definition at line 245 of file primitives/Polygon.h.

◆ ConstPolygon3d() [1/2]

lanelet::ConstPolygon3d::ConstPolygon3d
default

◆ ConstPolygon3d() [2/2]

lanelet::ConstPolygon3d::ConstPolygon3d
inlineexplicit

Conversion from ConstLineString3d. Does not ensure validity of the polygon!

Definition at line 136 of file primitives/Polygon.h.

◆ end()

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

BasicPoint3d Iterator to past-the-end.

Definition at line 248 of file primitives/Polygon.h.

◆ front()

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

Get first BasicPoint3d.

Definition at line 251 of file primitives/Polygon.h.

◆ operator[]()

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

access BasicPoint3d at specific position

Definition at line 257 of file primitives/Polygon.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