Public Types | Public Member Functions | Static Public Member Functions | Protected Attributes | Private Types | Private Member Functions | List of all members
towr::HeightMap Class Referenceabstract

Holds the height and slope information of the terrain. More...

#include <height_map.h>

Inheritance diagram for towr::HeightMap:
Inheritance graph
[legend]

Public Types

enum  Direction { Normal, Tangent1, Tangent2 }
 
using Ptr = std::shared_ptr< HeightMap >
 
enum  TerrainID {
  FlatID, BlockID, StairsID, GapID,
  SlopeID, ChimneyID, ChimneyLRID, TERRAIN_COUNT
}
 Terrains IDs corresponding for factory method. More...
 
using Vector3d = Eigen::Vector3d
 

Public Member Functions

double GetDerivativeOfHeightWrt (Dim2D dim, double x, double y) const
 How the height value changes at a 2D position in direction dim. More...
 
Vector3d GetDerivativeOfNormalizedBasisWrt (Direction direction, Dim2D dim, double x, double y) const
 How the terrain normal/tangent vectors change when moving in x or y. More...
 
double GetFrictionCoeff () const
 
virtual double GetHeight (double x, double y) const =0
 
Vector3d GetNormalizedBasis (Direction direction, double x, double y) const
 Returns either the vector normal or tangent to the terrain patch. More...
 
 HeightMap ()=default
 
virtual ~HeightMap ()=default
 

Static Public Member Functions

static HeightMap::Ptr MakeTerrain (TerrainID type)
 

Protected Attributes

double friction_coeff_ = 0.5
 

Private Types

using DimDerivs = std::vector< Dim2D >
 dimensional derivatives More...
 

Private Member Functions

Vector3d GetBasis (Direction direction, double x, double y, const DimDerivs &dim_deriv={}) const
 returns either the terrain normal/tangent or its derivative. More...
 
Vector3d GetDerivativeOfNormalizedVectorWrtNonNormalizedIndex (const Vector3d &non_normalized, int index) const
 
virtual double GetHeightDerivWrtX (double x, double y) const
 
virtual double GetHeightDerivWrtXX (double x, double y) const
 
virtual double GetHeightDerivWrtXY (double x, double y) const
 
virtual double GetHeightDerivWrtY (double x, double y) const
 
virtual double GetHeightDerivWrtYX (double x, double y) const
 
virtual double GetHeightDerivWrtYY (double x, double y) const
 
Vector3d GetNormal (double x, double y, const DimDerivs &={}) const
 
double GetSecondDerivativeOfHeightWrt (Dim2D dim1, Dim2D dim2, double x, double y) const
 
Vector3d GetTangent1 (double x, double y, const DimDerivs &={}) const
 
Vector3d GetTangent2 (double x, double y, const DimDerivs &={}) const
 

Detailed Description

Holds the height and slope information of the terrain.

This class is responsible for providing the height values and slope at each position (x,y). Examples of various height map examples can be found in height_map_examples.h.

If a height map of the terrain already exists, e.g. Octomap/Gridmap, then a simple adapter for these can be written to comply to this minimal interface and to be used with towr.

The height map is used to formulate constraints such as "foot must be touching terrain during stance phase".

See also
TerrainConstraint

Definition at line 71 of file height_map.h.

Member Typedef Documentation

using towr::HeightMap::DimDerivs = std::vector<Dim2D>
private

dimensional derivatives

Definition at line 139 of file height_map.h.

using towr::HeightMap::Ptr = std::shared_ptr<HeightMap>

Definition at line 73 of file height_map.h.

using towr::HeightMap::Vector3d = Eigen::Vector3d

Definition at line 74 of file height_map.h.

Member Enumeration Documentation

Enumerator
Normal 
Tangent1 
Tangent2 

Definition at line 90 of file height_map.h.

Terrains IDs corresponding for factory method.

Enumerator
FlatID 
BlockID 
StairsID 
GapID 
SlopeID 
ChimneyID 
ChimneyLRID 
TERRAIN_COUNT 

Definition at line 79 of file height_map.h.

Constructor & Destructor Documentation

towr::HeightMap::HeightMap ( )
default
virtual towr::HeightMap::~HeightMap ( )
virtualdefault

Member Function Documentation

HeightMap::Vector3d towr::HeightMap::GetBasis ( Direction  direction,
double  x,
double  y,
const DimDerivs dim_deriv = {} 
) const
private

returns either the terrain normal/tangent or its derivative.

Parameters
directionTerrain normal or tangent vector.
xThe x position on the terrain.
yThe y position on the terrain.
dim_derivIf empty, the vector is returned, if e.g. X_ is set, the derivative of the vector w.r.t. x is returned.
Returns
the 3D not-normalized vector.

Definition at line 69 of file height_map.cc.

double towr::HeightMap::GetDerivativeOfHeightWrt ( Dim2D  dim,
double  x,
double  y 
) const

How the height value changes at a 2D position in direction dim.

Parameters
dimThe direction (x,y) w.r.t. which the height change is desired.
xThe x position on the terrain.
yThe y position on the terrain.
Returns
The derivative of the height with respect to the dimension.

Definition at line 53 of file height_map.cc.

HeightMap::Vector3d towr::HeightMap::GetDerivativeOfNormalizedBasisWrt ( Direction  direction,
Dim2D  dim,
double  x,
double  y 
) const

How the terrain normal/tangent vectors change when moving in x or y.

Parameters
directionThe terrain normal or tangent vectors.
dimThe dimension w.r.t which the change is searched for.
xThe x position on the terrain.
yThe y position on the terrain.
Returns
The normalized 3D derivative w.r.t dimension dim.

Definition at line 81 of file height_map.cc.

HeightMap::Vector3d towr::HeightMap::GetDerivativeOfNormalizedVectorWrtNonNormalizedIndex ( const Vector3d non_normalized,
int  index 
) const
private

Definition at line 142 of file height_map.cc.

double towr::HeightMap::GetFrictionCoeff ( ) const
inline
Returns
The constant friction coefficient over the whole terrain.

Definition at line 133 of file height_map.h.

virtual double towr::HeightMap::GetHeight ( double  x,
double  y 
) const
pure virtual
Returns
The height of the terrain [m] at a specific 2D position.
Parameters
xThe x position.
yThe y position.

Implemented in towr::ChimneyLR, towr::Chimney, towr::Slope, towr::Gap, towr::Stairs, towr::Block, and towr::FlatGround.

virtual double towr::HeightMap::GetHeightDerivWrtX ( double  x,
double  y 
) const
inlineprivatevirtual

Reimplemented in towr::Slope, towr::Gap, and towr::Block.

Definition at line 163 of file height_map.h.

virtual double towr::HeightMap::GetHeightDerivWrtXX ( double  x,
double  y 
) const
inlineprivatevirtual

Reimplemented in towr::Gap.

Definition at line 167 of file height_map.h.

virtual double towr::HeightMap::GetHeightDerivWrtXY ( double  x,
double  y 
) const
inlineprivatevirtual

Definition at line 168 of file height_map.h.

virtual double towr::HeightMap::GetHeightDerivWrtY ( double  x,
double  y 
) const
inlineprivatevirtual

Reimplemented in towr::ChimneyLR, and towr::Chimney.

Definition at line 164 of file height_map.h.

virtual double towr::HeightMap::GetHeightDerivWrtYX ( double  x,
double  y 
) const
inlineprivatevirtual

Definition at line 169 of file height_map.h.

virtual double towr::HeightMap::GetHeightDerivWrtYY ( double  x,
double  y 
) const
inlineprivatevirtual

Definition at line 170 of file height_map.h.

HeightMap::Vector3d towr::HeightMap::GetNormal ( double  x,
double  y,
const DimDerivs deriv = {} 
) const
private

Definition at line 94 of file height_map.cc.

HeightMap::Vector3d towr::HeightMap::GetNormalizedBasis ( Direction  direction,
double  x,
double  y 
) const

Returns either the vector normal or tangent to the terrain patch.

Parameters
directionThe terrain normal or tangent vectors.
xThe x position on the terrain.
yThe y position on the terrain.
Returns
The normalized 3D vector in the specified direction.

Definition at line 63 of file height_map.cc.

double towr::HeightMap::GetSecondDerivativeOfHeightWrt ( Dim2D  dim1,
Dim2D  dim2,
double  x,
double  y 
) const
private

Definition at line 151 of file height_map.cc.

HeightMap::Vector3d towr::HeightMap::GetTangent1 ( double  x,
double  y,
const DimDerivs deriv = {} 
) const
private

Definition at line 113 of file height_map.cc.

HeightMap::Vector3d towr::HeightMap::GetTangent2 ( double  x,
double  y,
const DimDerivs deriv = {} 
) const
private

Definition at line 128 of file height_map.cc.

HeightMap::Ptr towr::HeightMap::MakeTerrain ( TerrainID  type)
static

Definition at line 38 of file height_map.cc.

Member Data Documentation

double towr::HeightMap::friction_coeff_ = 0.5
protected

Definition at line 136 of file height_map.h.


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


towr
Author(s): Alexander W. Winkler
autogenerated on Fri Apr 2 2021 02:14:16