Public Types | Public Member Functions | Private Attributes | List of all members
towr::TerrainConstraint Class Reference

Ensures the endeffectors always lays on or above terrain height. More...

#include <terrain_constraint.h>

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

Public Types

using Vector3d = Eigen::Vector3d
 
- Public Types inherited from ifopt::ConstraintSet
typedef std::shared_ptr< ConstraintSetPtr
 
typedef Composite::Ptr VariablesPtr
 
- Public Types inherited from ifopt::Component
typedef Eigen::SparseMatrix< double, Eigen::RowMajor > Jacobian
 
typedef std::shared_ptr< ComponentPtr
 
typedef std::vector< BoundsVecBound
 
typedef Eigen::VectorXd VectorXd
 

Public Member Functions

void FillJacobianBlock (std::string var_set, Jacobian &) const override
 
VecBound GetBounds () const override
 
VectorXd GetValues () const override
 
void InitVariableDependedQuantities (const VariablesPtr &x) override
 
 TerrainConstraint (const HeightMap::Ptr &terrain, std::string ee_motion_id)
 Constructs a terrain constraint. More...
 
virtual ~TerrainConstraint ()=default
 
- Public Member Functions inherited from ifopt::ConstraintSet
 ConstraintSet (int n_constraints, const std::string &name)
 
Jacobian GetJacobian () const final
 
void LinkWithVariables (const VariablesPtr &x)
 
virtual ~ConstraintSet ()=default
 
- Public Member Functions inherited from ifopt::Component
 Component (int num_rows, const std::string &name)
 
std::string GetName () const
 
int GetRows () const
 
virtual void Print (double tolerance, int &index_start) const
 
void SetRows (int num_rows)
 
virtual ~Component ()=default
 

Private Attributes

NodesVariablesPhaseBased::Ptr ee_motion_
 the position of the endeffector. More...
 
std::string ee_motion_id_
 the name of the endeffector variable set. More...
 
std::vector< int > node_ids_
 the indices of the nodes constrained. More...
 
HeightMap::Ptr terrain_
 the height map of the current terrain. More...
 

Additional Inherited Members

- Static Public Attributes inherited from ifopt::Component
static const int kSpecifyLater
 
- Protected Member Functions inherited from ifopt::ConstraintSet
const VariablesPtr GetVariables () const
 

Detailed Description

Ensures the endeffectors always lays on or above terrain height.

When using interior point solvers such as IPOPT to solve the problem, this constraint also keeps the foot nodes far from the terrain, causing a leg lifting during swing-phase. This is convenient.

Attention: This is enforced only at the spline nodes.

Definition at line 51 of file terrain_constraint.h.

Member Typedef Documentation

using towr::TerrainConstraint::Vector3d = Eigen::Vector3d

Definition at line 53 of file terrain_constraint.h.

Constructor & Destructor Documentation

towr::TerrainConstraint::TerrainConstraint ( const HeightMap::Ptr terrain,
std::string  ee_motion_id 
)

Constructs a terrain constraint.

Parameters
terrainThe terrain height value and slope for each position x,y.
ee_motion_idThe name of the endeffector variable set.

Definition at line 36 of file terrain_constraint.cc.

virtual towr::TerrainConstraint::~TerrainConstraint ( )
virtualdefault

Member Function Documentation

void towr::TerrainConstraint::FillJacobianBlock ( std::string  var_set,
Jacobian jac 
) const
overridevirtual

Implements ifopt::ConstraintSet.

Definition at line 91 of file terrain_constraint.cc.

TerrainConstraint::VecBound towr::TerrainConstraint::GetBounds ( ) const
overridevirtual

Implements ifopt::Component.

Definition at line 73 of file terrain_constraint.cc.

Eigen::VectorXd towr::TerrainConstraint::GetValues ( ) const
overridevirtual

Implements ifopt::Component.

Definition at line 58 of file terrain_constraint.cc.

void towr::TerrainConstraint::InitVariableDependedQuantities ( const VariablesPtr x)
override

Definition at line 45 of file terrain_constraint.cc.

Member Data Documentation

NodesVariablesPhaseBased::Ptr towr::TerrainConstraint::ee_motion_
private

the position of the endeffector.

Definition at line 70 of file terrain_constraint.h.

std::string towr::TerrainConstraint::ee_motion_id_
private

the name of the endeffector variable set.

Definition at line 73 of file terrain_constraint.h.

std::vector<int> towr::TerrainConstraint::node_ids_
private

the indices of the nodes constrained.

Definition at line 74 of file terrain_constraint.h.

HeightMap::Ptr towr::TerrainConstraint::terrain_
private

the height map of the current terrain.

Definition at line 71 of file terrain_constraint.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