Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Private Member Functions | List of all members
coal::HeightField< BV > Class Template Reference

Data structure depicting a height field given by the base grid dimensions and the elevation along the grid. More...

#include <hfield.h>

Inheritance diagram for coal::HeightField< BV >:
Inheritance graph
[legend]

Public Types

typedef std::vector< Node, Eigen::aligned_allocator< Node > > BVS
 
typedef HFNode< BV > Node
 

Public Member Functions

virtual HeightField< BV > * clone () const
 Clone *this into a new CollisionGeometry. More...
 
void computeLocalAABB ()
 Compute the AABB for the HeightField, used for broad-phase collision. More...
 
HFNode< BV > & getBV (unsigned int i)
 Access the bv giving the its index. More...
 
const HFNode< BV > & getBV (unsigned int i) const
 Access the bv giving the its index. More...
 
const MatrixXsgetHeights () const
 Returns a const reference of the heights. More...
 
CoalScalar getMaxHeight () const
 Returns the maximal height value of the Height Field. More...
 
CoalScalar getMinHeight () const
 Returns the minimal height value of the Height Field. More...
 
const BVSgetNodes () const
 
NODE_TYPE getNodeType () const
 get the node type More...
 
NODE_TYPE getNodeType () const
 get the node type More...
 
NODE_TYPE getNodeType () const
 get the node type More...
 
NODE_TYPE getNodeType () const
 get the node type More...
 
NODE_TYPE getNodeType () const
 get the node type More...
 
NODE_TYPE getNodeType () const
 get the node type More...
 
NODE_TYPE getNodeType () const
 get the node type More...
 
NODE_TYPE getNodeType () const
 get the node type More...
 
NODE_TYPE getNodeType () const
 Get the BV type: default is unknown. More...
 
NODE_TYPE getNodeType () const
 Specialization of getNodeType() for HeightField with different BV types. More...
 
NODE_TYPE getNodeType () const
 get the node type More...
 
NODE_TYPE getNodeType () const
 get the node type More...
 
NODE_TYPE getNodeType () const
 get the node type More...
 
NODE_TYPE getNodeType () const
 get the node type More...
 
NODE_TYPE getNodeType () const
 get the node type More...
 
NODE_TYPE getNodeType () const
 get the node type More...
 
NODE_TYPE getNodeType () const
 get the node type More...
 
CoalScalar getXDim () const
 Returns the dimension of the Height Field along the X direction. More...
 
const VecXsgetXGrid () const
 Returns a const reference of the grid along the X direction. More...
 
CoalScalar getYDim () const
 Returns the dimension of the Height Field along the Y direction. More...
 
const VecXsgetYGrid () const
 Returns a const reference of the grid along the Y direction. More...
 
 HeightField ()
 Constructing an empty HeightField. More...
 
 HeightField (const CoalScalar x_dim, const CoalScalar y_dim, const MatrixXs &heights, const CoalScalar min_height=(CoalScalar) 0)
 Constructing an HeightField from its base dimensions and the set of heights points. The granularity of the height field along X and Y direction is extraded from the Z grid. More...
 
 HeightField (const HeightField &other)
 Copy contructor from another HeightField. More...
 
void updateHeights (const MatrixXs &new_heights)
 Update Height Field height. More...
 
virtual ~HeightField ()
 deconstruction, delete mesh data related. More...
 
- Public Member Functions inherited from coal::CollisionGeometry
 CollisionGeometry ()
 
 CollisionGeometry (const CollisionGeometry &other)=default
 Copy constructor. More...
 
virtual Matrix3s computeMomentofInertiaRelatedToCOM () const
 compute the inertia matrix, related to the com More...
 
void * getUserData () const
 get user data in geometry More...
 
bool isFree () const
 whether the object is completely free More...
 
bool isOccupied () const
 whether the object is completely occupied More...
 
bool isUncertain () const
 whether the object has some uncertainty More...
 
bool operator!= (const CollisionGeometry &other) const
 Difference operator. More...
 
bool operator== (const CollisionGeometry &other) const
 Equality operator. More...
 
void setUserData (void *data)
 set user data in geometry More...
 
virtual ~CollisionGeometry ()
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef CollisionGeometry Base
 
- Public Attributes inherited from coal::CollisionGeometry
Vec3s aabb_center
 AABB center in local coordinate. More...
 
AABB aabb_local
 AABB in local coordinate, used for tight AABB when only translation transform. More...
 
CoalScalar aabb_radius
 AABB radius. More...
 
CoalScalar cost_density
 collision cost for unit volume More...
 
CoalScalar threshold_free
 threshold for free (<= is free) More...
 
CoalScalar threshold_occupied
 threshold for occupied ( >= is occupied) More...
 
void * user_data
 pointer to user defined data specific to this object More...
 

Protected Member Functions

int buildTree ()
 Build the bounding volume hierarchy. More...
 
Vec3s computeCOM () const
 compute center of mass More...
 
Matrix3s computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
CoalScalar computeVolume () const
 compute the volume More...
 
OBJECT_TYPE getObjectType () const
 Get the object type: it is a HFIELD. More...
 
void init (const CoalScalar x_dim, const CoalScalar y_dim, const MatrixXs &heights, const CoalScalar min_height)
 
CoalScalar recursiveBuildTree (const size_t bv_id, const Eigen::DenseIndex x_id, const Eigen::DenseIndex x_size, const Eigen::DenseIndex y_id, const Eigen::DenseIndex y_size)
 
CoalScalar recursiveUpdateHeight (const size_t bv_id)
 

Protected Attributes

BVS bvs
 Bounding volume hierarchy. More...
 
MatrixXs heights
 Elevation values in meters of the Height Field. More...
 
CoalScalar max_height
 
CoalScalar min_height
 Minimal height of the Height Field: all values bellow min_height will be discarded. More...
 
unsigned int num_bvs
 
CoalScalar x_dim
 Dimensions in meters along X and Y directions. More...
 
VecXs x_grid
 Grids along the X and Y directions. Useful for plotting or other related things. More...
 
CoalScalar y_dim
 
VecXs y_grid
 

Private Member Functions

virtual bool isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 

Detailed Description

template<typename BV>
class coal::HeightField< BV >

Data structure depicting a height field given by the base grid dimensions and the elevation along the grid.

Template Parameters
BVone of the bounding volume class in Bounding volumes.

An height field is defined by its base dimensions along the X and Y axes and a set ofpoints defined by their altitude, regularly dispatched on the grid. The height field is centered at the origin and the corners of the geometry correspond to the following coordinates [± x_dim/2; ± y_dim/2].

Definition at line 202 of file coal/hfield.h.

Member Typedef Documentation

◆ BVS

template<typename BV >
typedef std::vector<Node, Eigen::aligned_allocator<Node> > coal::HeightField< BV >::BVS

Definition at line 209 of file coal/hfield.h.

◆ Node

template<typename BV >
typedef HFNode<BV> coal::HeightField< BV >::Node

Definition at line 208 of file coal/hfield.h.

Constructor & Destructor Documentation

◆ HeightField() [1/3]

template<typename BV >
coal::HeightField< BV >::HeightField ( )
inline

Constructing an empty HeightField.

Definition at line 212 of file coal/hfield.h.

◆ HeightField() [2/3]

template<typename BV >
coal::HeightField< BV >::HeightField ( const CoalScalar  x_dim,
const CoalScalar  y_dim,
const MatrixXs heights,
const CoalScalar  min_height = (CoalScalar)0 
)
inline

Constructing an HeightField from its base dimensions and the set of heights points. The granularity of the height field along X and Y direction is extraded from the Z grid.

Parameters
[in]x_dimDimension along the X axis
[in]y_dimDimension along the Y axis
[in]heightsMatrix containing the altitude of each point compositng the height field
[in]min_heightMinimal height of the height field

Definition at line 228 of file coal/hfield.h.

◆ HeightField() [3/3]

template<typename BV >
coal::HeightField< BV >::HeightField ( const HeightField< BV > &  other)
inline

Copy contructor from another HeightField.

Parameters
[in]otherto copy.

Definition at line 239 of file coal/hfield.h.

◆ ~HeightField()

template<typename BV >
virtual coal::HeightField< BV >::~HeightField ( )
inlinevirtual

deconstruction, delete mesh data related.

Definition at line 274 of file coal/hfield.h.

Member Function Documentation

◆ buildTree()

template<typename BV >
int coal::HeightField< BV >::buildTree ( )
inlineprotected

Build the bounding volume hierarchy.

Definition at line 362 of file coal/hfield.h.

◆ clone()

template<typename BV >
virtual HeightField<BV>* coal::HeightField< BV >::clone ( ) const
inlinevirtual

Clone *this into a new CollisionGeometry.

Implements coal::CollisionGeometry.

Definition at line 269 of file coal/hfield.h.

◆ computeCOM()

template<typename BV >
Vec3s coal::HeightField< BV >::computeCOM ( ) const
inlineprotectedvirtual

compute center of mass

Reimplemented from coal::CollisionGeometry.

Definition at line 336 of file coal/hfield.h.

◆ computeLocalAABB()

template<typename BV >
void coal::HeightField< BV >::computeLocalAABB ( )
inlinevirtual

Compute the AABB for the HeightField, used for broad-phase collision.

Implements coal::CollisionGeometry.

Definition at line 278 of file coal/hfield.h.

◆ computeMomentofInertia()

template<typename BV >
Matrix3s coal::HeightField< BV >::computeMomentofInertia ( ) const
inlineprotectedvirtual

compute the inertia matrix, related to the origin

Reimplemented from coal::CollisionGeometry.

Definition at line 340 of file coal/hfield.h.

◆ computeVolume()

template<typename BV >
CoalScalar coal::HeightField< BV >::computeVolume ( ) const
inlineprotectedvirtual

compute the volume

Reimplemented from coal::CollisionGeometry.

Definition at line 338 of file coal/hfield.h.

◆ getBV() [1/2]

template<typename BV >
HFNode<BV>& coal::HeightField< BV >::getBV ( unsigned int  i)
inline

Access the bv giving the its index.

Definition at line 490 of file coal/hfield.h.

◆ getBV() [2/2]

template<typename BV >
const HFNode<BV>& coal::HeightField< BV >::getBV ( unsigned int  i) const
inline

Access the bv giving the its index.

Definition at line 483 of file coal/hfield.h.

◆ getHeights()

template<typename BV >
const MatrixXs& coal::HeightField< BV >::getHeights ( ) const
inline

Returns a const reference of the heights.

Definition at line 257 of file coal/hfield.h.

◆ getMaxHeight()

template<typename BV >
CoalScalar coal::HeightField< BV >::getMaxHeight ( ) const
inline

Returns the maximal height value of the Height Field.

Definition at line 267 of file coal/hfield.h.

◆ getMinHeight()

template<typename BV >
CoalScalar coal::HeightField< BV >::getMinHeight ( ) const
inline

Returns the minimal height value of the Height Field.

Definition at line 265 of file coal/hfield.h.

◆ getNodes()

template<typename BV >
const BVS& coal::HeightField< BV >::getNodes ( ) const
inline

Definition at line 271 of file coal/hfield.h.

◆ getNodeType() [1/17]

NODE_TYPE coal::HeightField< AABB >::getNodeType ( ) const
virtual

get the node type

Reimplemented from coal::CollisionGeometry.

Definition at line 51 of file hfield.cpp.

◆ getNodeType() [2/17]

NODE_TYPE coal::HeightField< OBB >::getNodeType ( ) const
virtual

get the node type

Reimplemented from coal::CollisionGeometry.

Definition at line 56 of file hfield.cpp.

◆ getNodeType() [3/17]

NODE_TYPE coal::HeightField< RSS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from coal::CollisionGeometry.

Definition at line 61 of file hfield.cpp.

◆ getNodeType() [4/17]

NODE_TYPE coal::HeightField< kIOS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from coal::CollisionGeometry.

Definition at line 66 of file hfield.cpp.

◆ getNodeType() [5/17]

NODE_TYPE coal::HeightField< OBBRSS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from coal::CollisionGeometry.

Definition at line 71 of file hfield.cpp.

◆ getNodeType() [6/17]

NODE_TYPE coal::HeightField< KDOP< 16 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from coal::CollisionGeometry.

Definition at line 76 of file hfield.cpp.

◆ getNodeType() [7/17]

NODE_TYPE coal::HeightField< KDOP< 18 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from coal::CollisionGeometry.

Definition at line 81 of file hfield.cpp.

◆ getNodeType() [8/17]

NODE_TYPE coal::HeightField< KDOP< 24 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from coal::CollisionGeometry.

Definition at line 86 of file hfield.cpp.

◆ getNodeType() [9/17]

template<typename BV >
NODE_TYPE coal::HeightField< BV >::getNodeType ( ) const
inlinevirtual

Get the BV type: default is unknown.

Reimplemented from coal::CollisionGeometry.

Definition at line 497 of file coal/hfield.h.

◆ getNodeType() [10/17]

NODE_TYPE coal::HeightField< AABB >::getNodeType ( ) const
virtual

Specialization of getNodeType() for HeightField with different BV types.

Reimplemented from coal::CollisionGeometry.

◆ getNodeType() [11/17]

NODE_TYPE coal::HeightField< OBB >::getNodeType ( ) const
virtual

get the node type

Reimplemented from coal::CollisionGeometry.

◆ getNodeType() [12/17]

NODE_TYPE coal::HeightField< RSS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from coal::CollisionGeometry.

◆ getNodeType() [13/17]

NODE_TYPE coal::HeightField< kIOS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from coal::CollisionGeometry.

◆ getNodeType() [14/17]

NODE_TYPE coal::HeightField< OBBRSS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from coal::CollisionGeometry.

◆ getNodeType() [15/17]

NODE_TYPE coal::HeightField< KDOP< 16 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from coal::CollisionGeometry.

◆ getNodeType() [16/17]

NODE_TYPE coal::HeightField< KDOP< 18 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from coal::CollisionGeometry.

◆ getNodeType() [17/17]

NODE_TYPE coal::HeightField< KDOP< 24 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from coal::CollisionGeometry.

◆ getObjectType()

template<typename BV >
OBJECT_TYPE coal::HeightField< BV >::getObjectType ( ) const
inlineprotectedvirtual

Get the object type: it is a HFIELD.

Reimplemented from coal::CollisionGeometry.

Definition at line 334 of file coal/hfield.h.

◆ getXDim()

template<typename BV >
CoalScalar coal::HeightField< BV >::getXDim ( ) const
inline

Returns the dimension of the Height Field along the X direction.

Definition at line 260 of file coal/hfield.h.

◆ getXGrid()

template<typename BV >
const VecXs& coal::HeightField< BV >::getXGrid ( ) const
inline

Returns a const reference of the grid along the X direction.

Definition at line 252 of file coal/hfield.h.

◆ getYDim()

template<typename BV >
CoalScalar coal::HeightField< BV >::getYDim ( ) const
inline

Returns the dimension of the Height Field along the Y direction.

Definition at line 262 of file coal/hfield.h.

◆ getYGrid()

template<typename BV >
const VecXs& coal::HeightField< BV >::getYGrid ( ) const
inline

Returns a const reference of the grid along the Y direction.

Definition at line 254 of file coal/hfield.h.

◆ init()

template<typename BV >
void coal::HeightField< BV >::init ( const CoalScalar  x_dim,
const CoalScalar  y_dim,
const MatrixXs heights,
const CoalScalar  min_height 
)
inlineprotected

Definition at line 308 of file coal/hfield.h.

◆ isEqual()

template<typename BV >
virtual bool coal::HeightField< BV >::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements coal::CollisionGeometry.

Definition at line 500 of file coal/hfield.h.

◆ recursiveBuildTree()

template<typename BV >
CoalScalar coal::HeightField< BV >::recursiveBuildTree ( const size_t  bv_id,
const Eigen::DenseIndex  x_id,
const Eigen::DenseIndex  x_size,
const Eigen::DenseIndex  y_id,
const Eigen::DenseIndex  y_size 
)
inlineprotected

Definition at line 398 of file coal/hfield.h.

◆ recursiveUpdateHeight()

template<typename BV >
CoalScalar coal::HeightField< BV >::recursiveUpdateHeight ( const size_t  bv_id)
inlineprotected

Definition at line 374 of file coal/hfield.h.

◆ updateHeights()

template<typename BV >
void coal::HeightField< BV >::updateHeights ( const MatrixXs new_heights)
inline

Update Height Field height.

Definition at line 290 of file coal/hfield.h.

Member Data Documentation

◆ Base

template<typename BV >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef CollisionGeometry coal::HeightField< BV >::Base

Definition at line 206 of file coal/hfield.h.

◆ bvs

template<typename BV >
BVS coal::HeightField< BV >::bvs
protected

Bounding volume hierarchy.

Definition at line 358 of file coal/hfield.h.

◆ heights

template<typename BV >
MatrixXs coal::HeightField< BV >::heights
protected

Elevation values in meters of the Height Field.

Definition at line 347 of file coal/hfield.h.

◆ max_height

template<typename BV >
CoalScalar coal::HeightField< BV >::max_height
protected

Definition at line 351 of file coal/hfield.h.

◆ min_height

template<typename BV >
CoalScalar coal::HeightField< BV >::min_height
protected

Minimal height of the Height Field: all values bellow min_height will be discarded.

Definition at line 351 of file coal/hfield.h.

◆ num_bvs

template<typename BV >
unsigned int coal::HeightField< BV >::num_bvs
protected

Definition at line 359 of file coal/hfield.h.

◆ x_dim

template<typename BV >
CoalScalar coal::HeightField< BV >::x_dim
protected

Dimensions in meters along X and Y directions.

Definition at line 344 of file coal/hfield.h.

◆ x_grid

template<typename BV >
VecXs coal::HeightField< BV >::x_grid
protected

Grids along the X and Y directions. Useful for plotting or other related things.

Definition at line 355 of file coal/hfield.h.

◆ y_dim

template<typename BV >
CoalScalar coal::HeightField< BV >::y_dim
protected

Definition at line 344 of file coal/hfield.h.

◆ y_grid

template<typename BV >
VecXs coal::HeightField< BV >::y_grid
protected

Definition at line 355 of file coal/hfield.h.


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


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:45:00