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

An immutable clockwise oriented, open (ie start point != end point) polygon in 2d. More...

#include <Polygon.h>

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

Public Types

using Category = traits::PolygonTag
 
using ConstType = ConstPolygon2d
 
using HybridType = ConstHybridPolygon2d
 
using MutableType = Polygon2d
 
using ThreeDType = ConstPolygon3d
 
using TwoDType = ConstPolygon2d
 
- 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

BasicPolygon2d basicPolygon () const
 create a simple 2d 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...
 
 ConstPolygon2d ()=default
 
 ConstPolygon2d (const ConstLineString2d &other)
 Conversion from/to ConstLineString2d. More...
 
size_t numSegments () const noexcept
 Returns the number of (geometrically valid) segments. More...
 
 operator BasicPolygon2d () const
 implicit conversion to a basic polygon in 2d More...
 
 operator ConstLineString2d () const
 
- 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

An immutable clockwise oriented, open (ie start point != end point) polygon in 2d.

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

Member Typedef Documentation

◆ Category

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

◆ ConstType

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

◆ HybridType

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

◆ MutableType

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

◆ ThreeDType

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

◆ TwoDType

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

Constructor & Destructor Documentation

◆ ConstPolygon2d() [1/2]

lanelet::ConstPolygon2d::ConstPolygon2d ( const ConstLineString2d other)
inlineexplicit

Conversion from/to ConstLineString2d.

This does not make sure that the polygon is valid and not self-intersecting! If you want to ensure this, use boost::polygon's is_valid.

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

◆ ConstPolygon2d() [2/2]

lanelet::ConstPolygon2d::ConstPolygon2d ( )
default

Member Function Documentation

◆ basicPolygon()

BasicPolygon2d lanelet::ConstPolygon2d::basicPolygon ( ) const
inline

create a simple 2d polygon from this (just a vector)

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

◆ ConstLineStringImpl() [1/5]

◆ ConstLineStringImpl() [2/5]

template<typename OtherT >
lanelet::ConstLineStringImpl< PointT >::ConstLineStringImpl ( typename OtherT  )
inlineexplicit

construct from other ConstLineStrings

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

◆ ConstLineStringImpl() [3/5]

Constructs a linestring from the data object of another linestring.

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

◆ ConstLineStringImpl() [4/5]

◆ ConstLineStringImpl() [5/5]

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

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

◆ numSegments()

size_t lanelet::ConstPolygon2d::numSegments ( ) const
inlinenoexcept

Returns the number of (geometrically valid) segments.

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

◆ operator BasicPolygon2d()

lanelet::ConstPolygon2d::operator BasicPolygon2d ( ) const
inline

implicit conversion to a basic polygon in 2d

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

◆ operator ConstLineString2d()

lanelet::ConstPolygon2d::operator ConstLineString2d ( ) const
inlineexplicit

Definition at line 100 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