Class BoundingBox2d

Class Documentation

class BoundingBox2d

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.

Public Types

Values:

enumerator AmbientDimAtCompileTime
enum CornerType

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

Values:

enumerator Min

1D names

enumerator Max
enumerator BottomLeft

Identifier for 2D corner

enumerator BottomRight
enumerator TopLeft
enumerator TopRight
enumerator BottomLeftFloor

Identifier for 3D corner

enumerator BottomRightFloor
enumerator TopLeftFloor
enumerator TopRightFloor
enumerator BottomLeftCeil
enumerator BottomRightCeil
enumerator TopLeftCeil
enumerator TopRightCeil
using Scalar = double
using ScalarTraits = Eigen::NumTraits<Scalar>
using Index = Eigen::Index
using RealScalar = ScalarTraits::Real
using NonInteger = ScalarTraits::NonInteger
using VectorType = BasicPoint2d

Public Functions

inline BoundingBox2d()

Default constructor initializing a null box.

inline explicit BoundingBox2d(Index dim)

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

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

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.

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

Constructs a box containing a single point p.

inline BoundingBox2d(const Eigen::AlignedBox<double, 2> &other)
inline Index dim() const
Returns:

the dimension in which the box holds

inline bool isNull() const

Deprecated:

use isEmpty()

inline void setNull()

Deprecated:

use setEmpty()

inline bool isEmpty() const

See also

setEmpty

Returns:

true if the box is empty.

inline void setEmpty()

Makes *this an empty box.

See also

isEmpty

inline const VectorType &() min () const
Returns:

the minimal corner

inline VectorType &() min ()
Returns:

a non const reference to the minimal corner

inline const VectorType &() max () const
Returns:

the maximal corner

inline VectorType &() max ()
Returns:

a non const reference to the maximal corner

inline BasicPoint2d center() const
Returns:

the center of the box

inline BasicPoint2d sizes() const
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

inline Scalar volume() const
Returns:

the volume of the bounding box

inline BasicPoint2d diagonal() const
Returns:

an expression for the bounding box diagonal vector if the length of the diagonal is needed: diagonal().norm() will provide it.

inline VectorType corner(CornerType corner) const
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.

inline VectorType sample() const
Returns:

a random point inside the bounding box sampled with a uniform distribution

template<typename Derived>
inline bool contains(const Eigen::MatrixBase<Derived> &p) const
Returns:

true if the point p is inside the box *this.

inline bool contains(const BoundingBox2d &b) const
Returns:

true if the box b is entirely inside the box *this.

inline bool intersects(const BoundingBox2d &b) const

See also

intersection, clamp

Returns:

true if the box b is intersecting the box *this.

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

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

See also

extend(const BoundingBox&)

inline BoundingBox2d &extend(const BoundingBox2d &b)

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

See also

merged, extend(const MatrixBase&)

inline BoundingBox2d &clamp(const BoundingBox2d &b)

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

See also

intersection(), intersects()

Note

If the boxes don’t intersect, the resulting box is empty.

inline BoundingBox2d intersection(const BoundingBox2d &b) const

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

See also

intersects(), clamp, contains()

Note

If the boxes don’t intersect, the resulting box is empty.

inline BoundingBox2d merged(const BoundingBox2d &b) const

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.

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

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

template<typename Derived>
inline Scalar squaredExteriorDistance(const Eigen::MatrixBase<Derived> &p) const

See also

exteriorDistance(const MatrixBase&), squaredExteriorDistance(const BoundingBox2d&)

Returns:

the squared distance between the point p and the box *this, and zero if p is inside the box.

inline Scalar squaredExteriorDistance(const BoundingBox2d &b) const

See also

exteriorDistance(const BoundingBox2d&), squaredExteriorDistance(const MatrixBase&)

Returns:

the squared distance between the boxes b and *this, and zero if the boxes intersect.

template<typename Derived>
inline NonInteger exteriorDistance(const Eigen::MatrixBase<Derived> &p) const

See also

squaredExteriorDistance(const MatrixBase&), exteriorDistance(const BoundingBox2d&)

Returns:

the distance between the point p and the box *this, and zero if p is inside the box.

inline NonInteger exteriorDistance(const BoundingBox2d &b) const

See also

squaredExteriorDistance(const BoundingBox2d&), exteriorDistance(const MatrixBase&)

Returns:

the distance between the boxes b and *this, and zero if the boxes intersect.

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

Copy constructor with scalar type conversion

inline bool isApprox(const BoundingBox2d &other, const RealScalar &prec = ScalarTraits::dummy_precision()) const

See also

MatrixBase::isApprox()

Returns:

true if *this is approximately equal to other, within the precision determined by prec.