30 #ifndef TOWR_CONSTRAINTS_FORCE_CONSTRAINT_H_ 31 #define TOWR_CONSTRAINTS_FORCE_CONSTRAINT_H_ 67 double force_limit_in_normal_direction,
std::vector< int > pure_stance_force_node_ids_
double mu_
friction coeff between robot feet and terrain.
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.
Composite::Ptr VariablesPtr
void InitVariableDependedQuantities(const VariablesPtr &x) override
virtual ~ForceConstraint()=default
std::shared_ptr< NodesVariablesPhaseBased > Ptr
double fn_max_
force limit in normal direction.
VecBound GetBounds() const override
EE ee_
The endeffector force to be constrained.
int n_constraints_per_node_
number of constraint for each node.
NodesVariablesPhaseBased::Ptr ee_force_
the current xyz foot forces.
Eigen::SparseMatrix< double, Eigen::RowMajor > Jacobian
VectorXd GetValues() const override
Ensures foot force that is unilateral and inside friction cone.
HeightMap::Ptr terrain_
gradient information at every position (x,y).
NodesVariablesPhaseBased::Ptr ee_motion_
the current xyz foot positions.
std::vector< Bounds > VecBound
std::shared_ptr< HeightMap > Ptr