Ensures foot force that is unilateral and inside friction cone. More...
#include <force_constraint.h>
Public Types | |
using | EE = uint |
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 |
ForceConstraint (const HeightMap::Ptr &terrain, double force_limit_in_normal_direction, EE endeffector_id) | |
Constructs a force contraint. More... | |
VecBound | GetBounds () const override |
VectorXd | GetValues () const override |
void | InitVariableDependedQuantities (const VariablesPtr &x) override |
virtual | ~ForceConstraint ()=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 | |
EE | ee_ |
The endeffector force to be constrained. More... | |
NodesVariablesPhaseBased::Ptr | ee_force_ |
the current xyz foot forces. More... | |
NodesVariablesPhaseBased::Ptr | ee_motion_ |
the current xyz foot positions. More... | |
double | fn_max_ |
force limit in normal direction. More... | |
double | mu_ |
friction coeff between robot feet and terrain. More... | |
int | n_constraints_per_node_ |
number of constraint for each node. More... | |
std::vector< int > | pure_stance_force_node_ids_ |
HeightMap::Ptr | terrain_ |
gradient information at every position (x,y). 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 foot force that is unilateral and inside friction cone.
This class is responsible for constraining the endeffector xyz-forces to only push into the terrain and additionally stay inside the friction cone according to the current slope.
In order to keep the constraint linear and simple for the solver to solve, we approximate the friction cone by a 4-sided pyramid.
Attention: Constraint is enforced only at the spline nodes. In between violations of this constraint can occur.
Definition at line 55 of file force_constraint.h.
using towr::ForceConstraint::EE = uint |
Definition at line 58 of file force_constraint.h.
using towr::ForceConstraint::Vector3d = Eigen::Vector3d |
Definition at line 57 of file force_constraint.h.
towr::ForceConstraint::ForceConstraint | ( | const HeightMap::Ptr & | terrain, |
double | force_limit_in_normal_direction, | ||
EE | endeffector_id | ||
) |
Constructs a force contraint.
terrain | The gradient information of the terrain for friction cone. |
force_limit_in_normal_direction | Maximum pushing force [N]. |
endeffector_id | Which endeffector force should be constrained. |
Definition at line 37 of file force_constraint.cc.
|
virtualdefault |
|
overridevirtual |
Implements ifopt::ConstraintSet.
Definition at line 108 of file force_constraint.cc.
|
overridevirtual |
Implements ifopt::Component.
Definition at line 92 of file force_constraint.cc.
|
overridevirtual |
Implements ifopt::Component.
Definition at line 63 of file force_constraint.cc.
|
override |
Definition at line 51 of file force_constraint.cc.
|
private |
The endeffector force to be constrained.
Definition at line 85 of file force_constraint.h.
|
private |
the current xyz foot forces.
Definition at line 78 of file force_constraint.h.
|
private |
the current xyz foot positions.
Definition at line 79 of file force_constraint.h.
|
private |
force limit in normal direction.
Definition at line 82 of file force_constraint.h.
|
private |
friction coeff between robot feet and terrain.
Definition at line 83 of file force_constraint.h.
|
private |
number of constraint for each node.
Definition at line 84 of file force_constraint.h.
|
private |
The are those Hermite-nodes that shape the polynomial during the stance phases, while all the others are already set to zero force (swing)
Definition at line 91 of file force_constraint.h.
|
private |
gradient information at every position (x,y).
Definition at line 81 of file force_constraint.h.