Public Types | Public Member Functions | Private Attributes | List of all members
lanelet::BoundingBox2d Class Reference

Axis-Aligned bounding box in 2d. More...

#include <BoundingBox.h>

Public Types

enum  { AmbientDimAtCompileTime = 2 }
 
enum  CornerType {
  Min = 0, Max = 1, BottomLeft = 0, BottomRight = 1,
  TopLeft = 2, TopRight = 3, BottomLeftFloor = 0, BottomRightFloor = 1,
  TopLeftFloor = 2, TopRightFloor = 3, BottomLeftCeil = 4, BottomRightCeil = 5,
  TopLeftCeil = 6, TopRightCeil = 7
}
 
using Index = Eigen::Index
 
using NonInteger = ScalarTraits::NonInteger
 
using RealScalar = ScalarTraits::Real
 
using Scalar = double
 
using ScalarTraits = Eigen::NumTraits< Scalar >
 
using VectorType = BasicPoint2d
 

Public Member Functions

 BoundingBox2d ()
 
 BoundingBox2d (const Eigen::AlignedBox< double, 2 > &other)
 
template<typename OtherScalarType >
 BoundingBox2d (const Eigen::AlignedBox< OtherScalarType, AmbientDimAtCompileTime > &other)
 
template<typename Derived >
 BoundingBox2d (const Eigen::MatrixBase< Derived > &p)
 
 BoundingBox2d (Index dim)
 
template<typename OtherVectorType1 , typename OtherVectorType2 >
 BoundingBox2d (OtherVectorType1 min, OtherVectorType2 max)
 
BasicPoint2d center () const
 
BoundingBox2dclamp (const BoundingBox2d &b)
 
bool contains (const BoundingBox2d &b) const
 
template<typename Derived >
bool contains (const Eigen::MatrixBase< Derived > &p) const
 
VectorType corner (CornerType corner) const
 
BasicPoint2d diagonal () const
 
Index dim () const
 
BoundingBox2dextend (const BoundingBox2d &b)
 
template<typename Derived >
BoundingBox2dextend (const Eigen::MatrixBase< Derived > &p)
 
NonInteger exteriorDistance (const BoundingBox2d &b) const
 
template<typename Derived >
NonInteger exteriorDistance (const Eigen::MatrixBase< Derived > &p) const
 
BoundingBox2d intersection (const BoundingBox2d &b) const
 
bool intersects (const BoundingBox2d &b) const
 
bool isApprox (const BoundingBox2d &other, const RealScalar &prec=ScalarTraits::dummy_precision()) const
 
bool isEmpty () const
 
bool isNull () const
 
VectorType &() max ()
 
const VectorType &() max () const
 
BoundingBox2d merged (const BoundingBox2d &b) const
 
VectorType &() min ()
 
const VectorType &() min () const
 
VectorType sample () const
 
void setEmpty ()
 
void setNull ()
 
BasicPoint2d sizes () const
 
Scalar squaredExteriorDistance (const BoundingBox2d &b) const
 
template<typename Derived >
Scalar squaredExteriorDistance (const Eigen::MatrixBase< Derived > &p) const
 
template<typename Derived >
BoundingBox2dtranslate (const Eigen::MatrixBase< Derived > &aT)
 
Scalar volume () const
 

Private Attributes

VectorType max_
 
VectorType min_
 

Detailed Description

Axis-Aligned bounding box in 2d.

Eigens aligned bounding box does not work for us in 2d, because of its memory alignment reqiurements. This is basically the same implementation, but without the memory alginment. We don't have to do that for the 3d case, because the 3d case does not use memory alignment in Eigen.

Definition at line 23 of file primitives/BoundingBox.h.

Member Typedef Documentation

◆ Index

using lanelet::BoundingBox2d::Index = Eigen::Index

Definition at line 28 of file primitives/BoundingBox.h.

◆ NonInteger

using lanelet::BoundingBox2d::NonInteger = ScalarTraits::NonInteger

Definition at line 30 of file primitives/BoundingBox.h.

◆ RealScalar

using lanelet::BoundingBox2d::RealScalar = ScalarTraits::Real

Definition at line 29 of file primitives/BoundingBox.h.

◆ Scalar

Definition at line 26 of file primitives/BoundingBox.h.

◆ ScalarTraits

using lanelet::BoundingBox2d::ScalarTraits = Eigen::NumTraits<Scalar>

Definition at line 27 of file primitives/BoundingBox.h.

◆ VectorType

Definition at line 31 of file primitives/BoundingBox.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
AmbientDimAtCompileTime 

Definition at line 25 of file primitives/BoundingBox.h.

◆ CornerType

Define constants to name the corners of a 1D, 2D or 3D axis aligned bounding box

Enumerator
Min 

1D names

Max 
BottomLeft 

Identifier for 2D corner

BottomRight 
TopLeft 
TopRight 
BottomLeftFloor 

Identifier for 3D corner

BottomRightFloor 
TopLeftFloor 
TopRightFloor 
BottomLeftCeil 
BottomRightCeil 
TopLeftCeil 
TopRightCeil 

Definition at line 34 of file primitives/BoundingBox.h.

Constructor & Destructor Documentation

◆ BoundingBox2d() [1/6]

lanelet::BoundingBox2d::BoundingBox2d ( )
inline

Default constructor initializing a null box.

Definition at line 60 of file primitives/BoundingBox.h.

◆ BoundingBox2d() [2/6]

lanelet::BoundingBox2d::BoundingBox2d ( Index  dim)
inlineexplicit

Constructs a null box with _dim the dimension of the ambient space.

Definition at line 67 of file primitives/BoundingBox.h.

◆ BoundingBox2d() [3/6]

template<typename OtherVectorType1 , typename OtherVectorType2 >
lanelet::BoundingBox2d::BoundingBox2d ( OtherVectorType1  min,
OtherVectorType2  max 
)
inline

Constructs a box with extremities _min and _max.

Warning
If either component of _min is larger than the same component of _max, the constructed box is empty.

Definition at line 73 of file primitives/BoundingBox.h.

◆ BoundingBox2d() [4/6]

template<typename Derived >
lanelet::BoundingBox2d::BoundingBox2d ( const Eigen::MatrixBase< Derived > &  p)
inlineexplicit

Constructs a box containing a single point p.

Definition at line 77 of file primitives/BoundingBox.h.

◆ BoundingBox2d() [5/6]

lanelet::BoundingBox2d::BoundingBox2d ( const Eigen::AlignedBox< double, 2 > &  other)
inline

Definition at line 79 of file primitives/BoundingBox.h.

◆ BoundingBox2d() [6/6]

template<typename OtherScalarType >
lanelet::BoundingBox2d::BoundingBox2d ( const Eigen::AlignedBox< OtherScalarType, AmbientDimAtCompileTime > &  other)
inlineexplicit

Copy constructor with scalar type conversion

Definition at line 261 of file primitives/BoundingBox.h.

Member Function Documentation

◆ center()

BasicPoint2d lanelet::BoundingBox2d::center ( ) const
inline
Returns
the center of the box

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

◆ clamp()

BoundingBox2d& lanelet::BoundingBox2d::clamp ( const BoundingBox2d b)
inline

Clamps *this by the box b and returns a reference to *this.

Note
If the boxes don't intersect, the resulting box is empty.
See also
intersection(), intersects()

Definition at line 196 of file primitives/BoundingBox.h.

◆ contains() [1/2]

bool lanelet::BoundingBox2d::contains ( const BoundingBox2d b) const
inline
Returns
true if the box b is entirely inside the box *this.

Definition at line 165 of file primitives/BoundingBox.h.

◆ contains() [2/2]

template<typename Derived >
bool lanelet::BoundingBox2d::contains ( const Eigen::MatrixBase< Derived > &  p) const
inline
Returns
true if the point p is inside the box *this.

Definition at line 160 of file primitives/BoundingBox.h.

◆ corner()

VectorType lanelet::BoundingBox2d::corner ( CornerType  corner) const
inline
Returns
the vertex of the bounding box at the corner defined by the corner-id corner. It works only for a 1D, 2D or 3D bounding box. For 1D bounding boxes corners are named by 2 enum constants: BottomLeft and BottomRight. For 2D bounding boxes, corners are named by 4 enum constants: BottomLeft, BottomRight, TopLeft, TopRight. For 3D bounding boxes, the following names are added: BottomLeftCeil, BottomRightCeil, TopLeftCeil, TopRightCeil.

Definition at line 139 of file primitives/BoundingBox.h.

◆ diagonal()

BasicPoint2d lanelet::BoundingBox2d::diagonal ( ) const
inline
Returns
an expression for the bounding box diagonal vector if the length of the diagonal is needed: diagonal().norm() will provide it.

Definition at line 128 of file primitives/BoundingBox.h.

◆ dim()

Index lanelet::BoundingBox2d::dim ( ) const
inline
Returns
the dimension in which the box holds

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

◆ extend() [1/2]

BoundingBox2d& lanelet::BoundingBox2d::extend ( const BoundingBox2d b)
inline

Extends *this such that it contains the box b and returns a reference to *this.

See also
merged, extend(const MatrixBase&)

Definition at line 187 of file primitives/BoundingBox.h.

◆ extend() [2/2]

template<typename Derived >
BoundingBox2d& lanelet::BoundingBox2d::extend ( const Eigen::MatrixBase< Derived > &  p)
inline

Extends *this such that it contains the point p and returns a reference to *this.

See also
extend(const BoundingBox&)

Definition at line 178 of file primitives/BoundingBox.h.

◆ exteriorDistance() [1/2]

NonInteger lanelet::BoundingBox2d::exteriorDistance ( const BoundingBox2d b) const
inline
Returns
the distance between the boxes b and *this, and zero if the boxes intersect.
See also
squaredExteriorDistance(const BoundingBox2d&), exteriorDistance(const MatrixBase&)

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

◆ exteriorDistance() [2/2]

template<typename Derived >
NonInteger lanelet::BoundingBox2d::exteriorDistance ( const Eigen::MatrixBase< Derived > &  p) const
inline
Returns
the distance between the point p and the box *this, and zero if p is inside the box.
See also
squaredExteriorDistance(const MatrixBase&), exteriorDistance(const BoundingBox2d&)

Definition at line 246 of file primitives/BoundingBox.h.

◆ intersection()

BoundingBox2d lanelet::BoundingBox2d::intersection ( const BoundingBox2d b) const
inline

Returns an BoundingBox2d that is the intersection of b and *this

Note
If the boxes don't intersect, the resulting box is empty.
See also
intersects(), clamp, contains()

Definition at line 205 of file primitives/BoundingBox.h.

◆ intersects()

bool lanelet::BoundingBox2d::intersects ( const BoundingBox2d b) const
inline
Returns
true if the box b is intersecting the box *this.
See also
intersection, clamp

Definition at line 171 of file primitives/BoundingBox.h.

◆ isApprox()

bool lanelet::BoundingBox2d::isApprox ( const BoundingBox2d other,
const RealScalar prec = ScalarTraits::dummy_precision() 
) const
inline
Returns
true if *this is approximately equal to other, within the precision determined by prec.
See also
MatrixBase::isApprox()

Definition at line 270 of file primitives/BoundingBox.h.

◆ isEmpty()

bool lanelet::BoundingBox2d::isEmpty ( ) const
inline
Returns
true if the box is empty.
See also
setEmpty

Definition at line 94 of file primitives/BoundingBox.h.

◆ isNull()

bool lanelet::BoundingBox2d::isNull ( ) const
inline
Deprecated:
use isEmpty()

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

◆ max() [1/2]

VectorType&() lanelet::BoundingBox2d::max ( )
inline
Returns
a non const reference to the maximal corner

Definition at line 110 of file primitives/BoundingBox.h.

◆ max() [2/2]

const VectorType&() lanelet::BoundingBox2d::max ( ) const
inline
Returns
the maximal corner

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

◆ merged()

BoundingBox2d lanelet::BoundingBox2d::merged ( const BoundingBox2d b) const
inline

Returns an BoundingBox2d that is the union of b and *this.

Note
Merging with an empty box may result in a box bigger than *this.
See also
extend(const BoundingBox2d&)

Definition at line 212 of file primitives/BoundingBox.h.

◆ min() [1/2]

VectorType&() lanelet::BoundingBox2d::min ( )
inline
Returns
a non const reference to the minimal corner

Definition at line 106 of file primitives/BoundingBox.h.

◆ min() [2/2]

const VectorType&() lanelet::BoundingBox2d::min ( ) const
inline
Returns
the minimal corner

Definition at line 104 of file primitives/BoundingBox.h.

◆ sample()

VectorType lanelet::BoundingBox2d::sample ( ) const
inline
Returns
a random point inside the bounding box sampled with a uniform distribution

Definition at line 156 of file primitives/BoundingBox.h.

◆ setEmpty()

void lanelet::BoundingBox2d::setEmpty ( )
inline

Makes *this an empty box.

See also
isEmpty

Definition at line 98 of file primitives/BoundingBox.h.

◆ setNull()

void lanelet::BoundingBox2d::setNull ( )
inline
Deprecated:
use setEmpty()

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

◆ sizes()

BasicPoint2d lanelet::BoundingBox2d::sizes ( ) const
inline
Returns
the lengths of the sides of the bounding box. Note that this function does not get the same result for integral or floating scalar types: see

Definition at line 119 of file primitives/BoundingBox.h.

◆ squaredExteriorDistance() [1/2]

Scalar lanelet::BoundingBox2d::squaredExteriorDistance ( const BoundingBox2d b) const
inline
Returns
the squared distance between the boxes b and *this, and zero if the boxes intersect.
See also
exteriorDistance(const BoundingBox2d&), squaredExteriorDistance(const MatrixBase&)

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

◆ squaredExteriorDistance() [2/2]

template<typename Derived >
Scalar lanelet::BoundingBox2d::squaredExteriorDistance ( const Eigen::MatrixBase< Derived > &  p) const
inline
Returns
the squared distance between the point p and the box *this, and zero if p is inside the box.
See also
exteriorDistance(const MatrixBase&), squaredExteriorDistance(const BoundingBox2d&)

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

◆ translate()

template<typename Derived >
BoundingBox2d& lanelet::BoundingBox2d::translate ( const Eigen::MatrixBase< Derived > &  aT)
inline

Translate *this by the vector t and returns a reference to *this.

Definition at line 216 of file primitives/BoundingBox.h.

◆ volume()

Scalar lanelet::BoundingBox2d::volume ( ) const
inline
Returns
the volume of the bounding box

Definition at line 122 of file primitives/BoundingBox.h.

Member Data Documentation

◆ max_

VectorType lanelet::BoundingBox2d::max_
private

Definition at line 275 of file primitives/BoundingBox.h.

◆ min_

VectorType lanelet::BoundingBox2d::min_
private

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