44 mu_ = terrain->GetFrictionCoeff();
70 int phase =
ee_force_->GetPhase(f_node_id);
73 Vector3d f = force_nodes.at(f_node_id).p();
76 g(row++) = f.transpose() * n;
80 g(row++) = f.transpose() * (t1 -
mu_*n);
81 g(row++) = f.transpose() * (t1 +
mu_*n);
84 g(row++) = f.transpose() * (t2 -
mu_*n);
85 g(row++) = f.transpose() * (t2 +
mu_*n);
115 int phase =
ee_force_->GetPhase(f_node_id);
121 for (
auto dim : {
X,
Y,
Z}) {
126 jac.coeffRef(row_reset++, idx) = n(dim);
127 jac.coeffRef(row_reset++, idx) = t1(dim)-
mu_*n(dim);
128 jac.coeffRef(row_reset++, idx) = t1(dim)+
mu_*n(dim);
129 jac.coeffRef(row_reset++, idx) = t2(dim)-
mu_*n(dim);
130 jac.coeffRef(row_reset++, idx) = t2(dim)+
mu_*n(dim);
140 auto force_nodes =
ee_force_->GetNodes();
142 int phase =
ee_force_->GetPhase(f_node_id);
143 int ee_node_id =
ee_motion_->GetNodeIDAtStartOfPhase(phase);
146 Vector3d f = force_nodes.at(f_node_id).p();
148 for (
auto dim : {
X_,
Y_}) {
157 jac.coeffRef(row_reset++, idx) = f.transpose()*dn;
160 jac.coeffRef(row_reset++, idx) = f.transpose()*(dt1-
mu_*dn);
161 jac.coeffRef(row_reset++, idx) = f.transpose()*(dt1+
mu_*dn);
164 jac.coeffRef(row_reset++, idx) = f.transpose()*(dt2-
mu_*dn);
165 jac.coeffRef(row_reset++, idx) = f.transpose()*(dt2+
mu_*dn);
std::vector< int > pure_stance_force_node_ids_
static const Bounds BoundGreaterZero
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
static const Bounds BoundSmallerZero
void InitVariableDependedQuantities(const VariablesPtr &x) override
double fn_max_
force limit in normal direction.
Semantic information associated with a scalar node value.
VecBound GetBounds() const override
EE ee_
The endeffector force to be constrained.
void SetRows(int num_rows)
int n_constraints_per_node_
number of constraint for each node.
static std::string EEMotionNodes(uint ee)
NodesVariablesPhaseBased::Ptr ee_force_
the current xyz foot forces.
Eigen::SparseMatrix< double, Eigen::RowMajor > Jacobian
VectorXd GetValues() const override
static std::string EEForceNodes(uint ee)
Nodes that are associated to either swing or stance phases.
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