Ensures the endeffectors always lays on or above terrain height. More...
#include <terrain_constraint.h>
Public Types | |
using | Vector3d = Eigen::Vector3d |
Public Types inherited from ifopt::ConstraintSet | |
typedef std::shared_ptr< ConstraintSet > | Ptr |
typedef Composite::Ptr | VariablesPtr |
Public Types inherited from ifopt::Component | |
typedef Eigen::SparseMatrix< double, Eigen::RowMajor > | Jacobian |
typedef std::shared_ptr< Component > | Ptr |
typedef std::vector< Bounds > | VecBound |
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 |
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.
using towr::TerrainConstraint::Vector3d = Eigen::Vector3d |
Definition at line 53 of file terrain_constraint.h.
towr::TerrainConstraint::TerrainConstraint | ( | const HeightMap::Ptr & | terrain, |
std::string | ee_motion_id | ||
) |
Constructs a terrain constraint.
terrain | The terrain height value and slope for each position x,y. |
ee_motion_id | The name of the endeffector variable set. |
Definition at line 36 of file terrain_constraint.cc.
|
virtualdefault |
|
overridevirtual |
Implements ifopt::ConstraintSet.
Definition at line 91 of file terrain_constraint.cc.
|
overridevirtual |
Implements ifopt::Component.
Definition at line 73 of file terrain_constraint.cc.
|
overridevirtual |
Implements ifopt::Component.
Definition at line 58 of file terrain_constraint.cc.
|
override |
Definition at line 45 of file terrain_constraint.cc.
|
private |
the position of the endeffector.
Definition at line 70 of file terrain_constraint.h.
|
private |
the name of the endeffector variable set.
Definition at line 73 of file terrain_constraint.h.
|
private |
the indices of the nodes constrained.
Definition at line 74 of file terrain_constraint.h.
|
private |
the height map of the current terrain.
Definition at line 71 of file terrain_constraint.h.