5 #ifndef __pinocchio_algorithm_contact_inverse_dynamics__hpp__
6 #define __pinocchio_algorithm_contact_inverse_dynamics__hpp__
12 #include <boost/optional/optional.hpp>
17 #include <boost/optional.hpp>
46 template<
typename,
int>
class JointCollectionTpl,
48 class ConstraintModelAllocator,
49 class ConstraintDataAllocator,
50 class CoulombFrictionConelAllocator,
52 typename VectorLikeGamma,
53 typename VectorLikeImp>
59 const
Eigen::MatrixBase<VectorLikeC> & c_ref,
64 const
Eigen::MatrixBase<VectorLikeR> & R,
65 const
Eigen::MatrixBase<VectorLikeGamma> & constraint_correction,
67 const
boost::optional<VectorLikeImp> & impulse_guess =
boost::none)
70 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options>
MatrixXs;
71 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options>
VectorXs;
72 typedef Eigen::Matrix<Scalar, 3, 1, Options>
Vector3;
74 int problem_size =
R.size();
75 int n_contacts = (int)problem_size / 3;
80 check_expression_if_real<Scalar>(settings.mu >
Scalar(0)),
"mu has to be strictly positive");
83 VectorXs c_ref_cor, desaxce_correction, R_prox, impulse_c_prev, dimpulse_c;
84 R_prox =
R + VectorXs::Constant(problem_size, settings.mu);
85 c_ref_cor = c_ref + constraint_correction;
88 data.impulse_c = impulse_guess.get();
93 data.impulse_c.setZero();
95 Scalar impulse_c_prev_norm_inf =
data.impulse_c.template lpNorm<Eigen::Infinity>();
96 Scalar complementarity, dual_feasibility;
97 bool abs_prec_reached =
false, rel_prec_reached =
false;
98 const size_t nc = cones.size();
100 for (; settings.iter <= settings.max_iter; ++settings.iter)
102 impulse_c_prev =
data.impulse_c;
103 for (
size_t cone_id = 0; cone_id < nc; ++cone_id)
105 const Eigen::DenseIndex row_id = 3 * cone_id;
106 const auto & cone = cones[cone_id];
107 auto impulse_segment =
data.impulse_c.template segment<3>(row_id);
108 auto impulse_prev_segment = impulse_c_prev.template segment<3>(row_id);
109 auto R_prox_segment = R_prox.template segment<3>(row_id);
112 auto c_ref_segment = c_ref.template segment<3>(row_id);
113 Vector3 desaxce_segment = cone.computeNormalCorrection(
115 + (
R.template segment<3>(row_id).array() * impulse_segment.array()).matrix());
117 -((c_ref_segment + desaxce_segment - settings.mu * impulse_prev_segment).array()
118 / R_prox_segment.array())
120 impulse_segment = cone.weightedProject(impulse_segment, R_prox_segment);
122 dimpulse_c =
data.impulse_c - impulse_c_prev;
123 settings.relative_residual = dimpulse_c.template lpNorm<Eigen::Infinity>();
133 const Scalar impulse_c_norm_inf =
data.impulse_c.template lpNorm<Eigen::Infinity>();
134 if (check_expression_if_real<Scalar, false>(
135 settings.relative_residual
136 <= settings.relative_accuracy *
math::max(impulse_c_norm_inf, impulse_c_prev_norm_inf)))
137 rel_prec_reached =
true;
139 rel_prec_reached =
false;
141 if (abs_prec_reached || rel_prec_reached)
144 impulse_c_prev_norm_inf = impulse_c_norm_inf;
146 return data.impulse_c;
178 template<
typename,
int>
class JointCollectionTpl,
179 typename ConfigVectorType,
180 typename TangentVectorType1,
181 typename TangentVectorType2,
182 class ConstraintModelAllocator,
183 class ConstraintDataAllocator,
184 class CoulombFrictionConelAllocator,
185 typename VectorLikeR,
186 typename VectorLikeGamma,
187 typename VectorLikeLam>
189 const typename DataTpl<
Scalar,
Options, JointCollectionTpl>::
193 const
Eigen::MatrixBase<ConfigVectorType> &
q,
194 const
Eigen::MatrixBase<TangentVectorType1> &
v,
195 const
Eigen::MatrixBase<TangentVectorType2> &
a,
201 const
Eigen::MatrixBase<VectorLikeR> & R,
202 const
Eigen::MatrixBase<VectorLikeGamma> & constraint_correction,
204 const
boost::optional<VectorLikeLam> & lambda_guess =
boost::none)
207 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options>
MatrixXs;
208 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options>
VectorXs;
212 int problem_size =
R.size();
213 int n_contacts = (int)problem_size / 3;
218 c_ref.noalias() =
J *
v_ref;
219 boost::optional<VectorXs> impulse_guess = boost::none;
222 data.impulse_c = lambda_guess.get();
224 impulse_guess = boost::make_optional(
data.impulse_c);
231 for (
int i = 0;
i <
model.njoints;
i++)
235 for (
int i = 0;
i < n_contacts;
i++)
238 const Eigen::DenseIndex row_id = 3 *
i;
239 auto lambda_segment =
data.lambda_c.template segment<3>(row_id);
240 typename RigidConstraintData::Matrix6 actInv_transpose1 =
241 cmodel.joint1_placement.toActionMatrixInverse();
242 actInv_transpose1.transposeInPlace();
243 fext[
cmodel.joint1_id] +=
Force(actInv_transpose1.template leftCols<3>() * lambda_segment);
244 typename RigidConstraintData::Matrix6 actInv_transpose2 =
245 cmodel.joint2_placement.toActionMatrixInverse();
246 actInv_transpose2.transposeInPlace();
247 fext[
cmodel.joint2_id] +=
Force(actInv_transpose2.template leftCols<3>() * lambda_segment);
259 #endif // ifndef __pinocchio_algorithm_contact_inverse_dynamics_hpp__