Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | List of all members
hpp::fcl::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 hpp::fcl::HeightField< BV >:
Inheritance graph
[legend]

Public Types

typedef CollisionGeometry Base
 
typedef std::vector< NodeBVS
 
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...
 
const HFNode< BV > & getBV (unsigned int i) const
 Access the bv giving the its index. More...
 
HFNode< BV > & getBV (unsigned int i)
 Access the bv giving the its index. More...
 
const MatrixXfgetHeights () const
 Returns a const reference of the heights. More...
 
FCL_REAL getMaxHeight () const
 Returns the maximal height value of the Height Field. More...
 
FCL_REAL getMinHeight () const
 Returns the minimal height value of the Height Field. More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
NODE_TYPE getNodeType () const
 Get the BV type: default is unknown. More...
 
template<>
NODE_TYPE getNodeType () const
 Specialization of getNodeType() for HeightField with different BV types. More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
template<>
NODE_TYPE getNodeType () const
 get the node type More...
 
FCL_REAL getXDim () const
 Returns the dimension of the Height Field along the X direction. More...
 
const VecXfgetXGrid () const
 Returns a const reference of the grid along the X direction. More...
 
FCL_REAL getYDim () const
 Returns the dimension of the Height Field along the Y direction. More...
 
const VecXfgetYGrid () const
 Returns a const reference of the grid along the Y direction. More...
 
 HeightField ()
 Constructing an empty HeightField. More...
 
 HeightField (const FCL_REAL x_dim, const FCL_REAL y_dim, const MatrixXf &heights, const FCL_REAL min_height=(FCL_REAL) 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 MatrixXf &new_heights)
 Update Height Field height. More...
 
virtual ~HeightField ()
 deconstruction, delete mesh data related. More...
 
- Public Member Functions inherited from hpp::fcl::CollisionGeometry
 CollisionGeometry ()
 
 CollisionGeometry (const CollisionGeometry &other)=default
 Copy constructor. More...
 
virtual Matrix3f 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 ()
 

Protected Member Functions

int buildTree ()
 Build the bounding volume hierarchy. More...
 
Vec3f computeCOM () const
 compute center of mass More...
 
Matrix3f computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
FCL_REAL computeVolume () const
 compute the volume More...
 
OBJECT_TYPE getObjectType () const
 Get the object type: it is a HFIELD. More...
 
void init (const FCL_REAL x_dim, const FCL_REAL y_dim, const MatrixXf &heights, const FCL_REAL min_height)
 
FCL_REAL 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)
 
FCL_REAL recursiveUpdateHeight (const size_t bv_id)
 

Protected Attributes

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

Private Member Functions

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

Additional Inherited Members

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

Detailed Description

template<typename BV>
class hpp::fcl::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 182 of file hfield.h.

Member Typedef Documentation

◆ Base

template<typename BV>
typedef CollisionGeometry hpp::fcl::HeightField< BV >::Base

Definition at line 184 of file hfield.h.

◆ BVS

template<typename BV>
typedef std::vector<Node> hpp::fcl::HeightField< BV >::BVS

Definition at line 187 of file hfield.h.

◆ Node

template<typename BV>
typedef HFNode<BV> hpp::fcl::HeightField< BV >::Node

Definition at line 186 of file hfield.h.

Constructor & Destructor Documentation

◆ HeightField() [1/3]

template<typename BV>
hpp::fcl::HeightField< BV >::HeightField ( )
inline

Constructing an empty HeightField.

Definition at line 190 of file hfield.h.

◆ HeightField() [2/3]

template<typename BV>
hpp::fcl::HeightField< BV >::HeightField ( const FCL_REAL  x_dim,
const FCL_REAL  y_dim,
const MatrixXf heights,
const FCL_REAL  min_height = (FCL_REAL)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 206 of file hfield.h.

◆ HeightField() [3/3]

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

Copy contructor from another HeightField.

Parameters
[in]otherto copy.

Definition at line 216 of file hfield.h.

◆ ~HeightField()

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

deconstruction, delete mesh data related.

Definition at line 249 of file hfield.h.

Member Function Documentation

◆ buildTree()

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

Build the bounding volume hierarchy.

Definition at line 337 of file hfield.h.

◆ clone()

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

Clone *this into a new CollisionGeometry.

Implements hpp::fcl::CollisionGeometry.

Definition at line 246 of file hfield.h.

◆ computeCOM()

template<typename BV>
Vec3f hpp::fcl::HeightField< BV >::computeCOM ( ) const
inlineprotectedvirtual

compute center of mass

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 311 of file hfield.h.

◆ computeLocalAABB()

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

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

Implements hpp::fcl::CollisionGeometry.

Definition at line 253 of file hfield.h.

◆ computeMomentofInertia()

template<typename BV>
Matrix3f hpp::fcl::HeightField< BV >::computeMomentofInertia ( ) const
inlineprotectedvirtual

compute the inertia matrix, related to the origin

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 315 of file hfield.h.

◆ computeVolume()

template<typename BV>
FCL_REAL hpp::fcl::HeightField< BV >::computeVolume ( ) const
inlineprotectedvirtual

compute the volume

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 313 of file hfield.h.

◆ getBV() [1/2]

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

Access the bv giving the its index.

Definition at line 440 of file hfield.h.

◆ getBV() [2/2]

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

Access the bv giving the its index.

Definition at line 447 of file hfield.h.

◆ getHeights()

template<typename BV>
const MatrixXf& hpp::fcl::HeightField< BV >::getHeights ( ) const
inline

Returns a const reference of the heights.

Definition at line 234 of file hfield.h.

◆ getMaxHeight()

template<typename BV>
FCL_REAL hpp::fcl::HeightField< BV >::getMaxHeight ( ) const
inline

Returns the maximal height value of the Height Field.

Definition at line 244 of file hfield.h.

◆ getMinHeight()

template<typename BV>
FCL_REAL hpp::fcl::HeightField< BV >::getMinHeight ( ) const
inline

Returns the minimal height value of the Height Field.

Definition at line 242 of file hfield.h.

◆ getNodeType() [1/17]

template<>
NODE_TYPE hpp::fcl::HeightField< AABB >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 52 of file hfield.cpp.

◆ getNodeType() [2/17]

template<>
NODE_TYPE hpp::fcl::HeightField< OBB >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 57 of file hfield.cpp.

◆ getNodeType() [3/17]

template<>
NODE_TYPE hpp::fcl::HeightField< RSS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 62 of file hfield.cpp.

◆ getNodeType() [4/17]

template<>
NODE_TYPE hpp::fcl::HeightField< kIOS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 67 of file hfield.cpp.

◆ getNodeType() [5/17]

template<>
NODE_TYPE hpp::fcl::HeightField< OBBRSS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 72 of file hfield.cpp.

◆ getNodeType() [6/17]

template<>
NODE_TYPE hpp::fcl::HeightField< KDOP< 16 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 77 of file hfield.cpp.

◆ getNodeType() [7/17]

template<>
NODE_TYPE hpp::fcl::HeightField< KDOP< 18 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 82 of file hfield.cpp.

◆ getNodeType() [8/17]

template<>
NODE_TYPE hpp::fcl::HeightField< KDOP< 24 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 87 of file hfield.cpp.

◆ getNodeType() [9/17]

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

Get the BV type: default is unknown.

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 454 of file hfield.h.

◆ getNodeType() [10/17]

template<>
NODE_TYPE hpp::fcl::HeightField< AABB >::getNodeType ( ) const
virtual

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

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getNodeType() [11/17]

template<>
NODE_TYPE hpp::fcl::HeightField< OBB >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getNodeType() [12/17]

template<>
NODE_TYPE hpp::fcl::HeightField< RSS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getNodeType() [13/17]

template<>
NODE_TYPE hpp::fcl::HeightField< kIOS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getNodeType() [14/17]

template<>
NODE_TYPE hpp::fcl::HeightField< OBBRSS >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getNodeType() [15/17]

template<>
NODE_TYPE hpp::fcl::HeightField< KDOP< 16 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getNodeType() [16/17]

template<>
NODE_TYPE hpp::fcl::HeightField< KDOP< 18 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getNodeType() [17/17]

template<>
NODE_TYPE hpp::fcl::HeightField< KDOP< 24 > >::getNodeType ( ) const
virtual

get the node type

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getObjectType()

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

Get the object type: it is a HFIELD.

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 309 of file hfield.h.

◆ getXDim()

template<typename BV>
FCL_REAL hpp::fcl::HeightField< BV >::getXDim ( ) const
inline

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

Definition at line 237 of file hfield.h.

◆ getXGrid()

template<typename BV>
const VecXf& hpp::fcl::HeightField< BV >::getXGrid ( ) const
inline

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

Definition at line 229 of file hfield.h.

◆ getYDim()

template<typename BV>
FCL_REAL hpp::fcl::HeightField< BV >::getYDim ( ) const
inline

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

Definition at line 239 of file hfield.h.

◆ getYGrid()

template<typename BV>
const VecXf& hpp::fcl::HeightField< BV >::getYGrid ( ) const
inline

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

Definition at line 231 of file hfield.h.

◆ init()

template<typename BV>
void hpp::fcl::HeightField< BV >::init ( const FCL_REAL  x_dim,
const FCL_REAL  y_dim,
const MatrixXf heights,
const FCL_REAL  min_height 
)
inlineprotected

Definition at line 283 of file hfield.h.

◆ isEqual()

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

equal operator with another object of derived type.

Implements hpp::fcl::CollisionGeometry.

Definition at line 457 of file hfield.h.

◆ recursiveBuildTree()

template<typename BV>
FCL_REAL hpp::fcl::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 374 of file hfield.h.

◆ recursiveUpdateHeight()

template<typename BV>
FCL_REAL hpp::fcl::HeightField< BV >::recursiveUpdateHeight ( const size_t  bv_id)
inlineprotected

Definition at line 349 of file hfield.h.

◆ updateHeights()

template<typename BV>
void hpp::fcl::HeightField< BV >::updateHeights ( const MatrixXf new_heights)
inline

Update Height Field height.

Definition at line 265 of file hfield.h.

Member Data Documentation

◆ bvs

template<typename BV>
BVS hpp::fcl::HeightField< BV >::bvs
protected

Bounding volume hierarchy.

Definition at line 333 of file hfield.h.

◆ heights

template<typename BV>
MatrixXf hpp::fcl::HeightField< BV >::heights
protected

Elevation values in meters of the Height Field.

Definition at line 322 of file hfield.h.

◆ max_height

template<typename BV>
FCL_REAL hpp::fcl::HeightField< BV >::max_height
protected

Definition at line 326 of file hfield.h.

◆ min_height

template<typename BV>
FCL_REAL hpp::fcl::HeightField< BV >::min_height
protected

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

Definition at line 326 of file hfield.h.

◆ num_bvs

template<typename BV>
unsigned int hpp::fcl::HeightField< BV >::num_bvs
protected

Definition at line 334 of file hfield.h.

◆ x_dim

template<typename BV>
FCL_REAL hpp::fcl::HeightField< BV >::x_dim
protected

Dimensions in meters along X and Y directions.

Definition at line 319 of file hfield.h.

◆ x_grid

template<typename BV>
VecXf hpp::fcl::HeightField< BV >::x_grid
protected

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

Definition at line 330 of file hfield.h.

◆ y_dim

template<typename BV>
FCL_REAL hpp::fcl::HeightField< BV >::y_dim
protected

Definition at line 319 of file hfield.h.

◆ y_grid

template<typename BV>
VecXf hpp::fcl::HeightField< BV >::y_grid
protected

Definition at line 330 of file hfield.h.


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


hpp-fcl
Author(s):
autogenerated on Fri Jun 2 2023 02:39:03