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

Constrains the foot position during the swing-phase. More...

#include <swing_constraint.h>

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

Public Types

using Vector2d = Eigen::Vector2d
 
- 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
 
 SwingConstraint (std::string ee_motion_id)
 Links the swing constraint with current foot variables. More...
 
virtual ~SwingConstraint ()=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_
 
std::string ee_motion_id_
 
std::vector< int > pure_swing_node_ids_
 
double t_swing_avg_ = 0.3
 

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

Constrains the foot position during the swing-phase.

This avoids very quick swinging of the feet, where the polynomial then leaves the e.g. range-of-motion in between nodes. This constraint can also be used to force a leg lift. However, it is cleanest if the optimization can be performed without this heuristic constraint.

Definition at line 49 of file swing_constraint.h.

Member Typedef Documentation

using towr::SwingConstraint::Vector2d = Eigen::Vector2d

Definition at line 51 of file swing_constraint.h.

Constructor & Destructor Documentation

towr::SwingConstraint::SwingConstraint ( std::string  ee_motion_id)

Links the swing constraint with current foot variables.

Parameters
ee_motion_idThe name of the foot variables in the optimization.

Definition at line 35 of file swing_constraint.cc.

virtual towr::SwingConstraint::~SwingConstraint ( )
virtualdefault

Member Function Documentation

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

Implements ifopt::ConstraintSet.

Definition at line 87 of file swing_constraint.cc.

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

Implements ifopt::Component.

Definition at line 81 of file swing_constraint.cc.

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

Implements ifopt::Component.

Definition at line 55 of file swing_constraint.cc.

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

Definition at line 42 of file swing_constraint.cc.

Member Data Documentation

NodesVariablesPhaseBased::Ptr towr::SwingConstraint::ee_motion_
private

Definition at line 67 of file swing_constraint.h.

std::string towr::SwingConstraint::ee_motion_id_
private

Definition at line 69 of file swing_constraint.h.

std::vector<int> towr::SwingConstraint::pure_swing_node_ids_
private

Definition at line 71 of file swing_constraint.h.

double towr::SwingConstraint::t_swing_avg_ = 0.3
private

Definition at line 68 of file swing_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