contact-inverse-dynamics.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2024 INRIA
3 //
4 
5 #ifndef __pinocchio_algorithm_contact_inverse_dynamics__hpp__
6 #define __pinocchio_algorithm_contact_inverse_dynamics__hpp__
7 
12 #include <boost/optional/optional.hpp>
16 
17 #include <boost/optional.hpp>
18 
19 namespace pinocchio
20 {
21 
43  template<
44  typename Scalar,
45  int Options,
46  template<typename, int>
47  class JointCollectionTpl,
48  typename VectorLikeC,
49  class ConstraintModelAllocator,
50  class ConstraintDataAllocator,
51  class CoulombFrictionConelAllocator,
52  typename VectorLikeR,
53  typename VectorLikeGamma,
54  typename VectorLikeImp>
55  PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility")
56  const typename DataTpl<Scalar, Options, JointCollectionTpl>::
57  TangentVectorType & computeContactImpulses(
58  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
59  DataTpl<Scalar, Options, JointCollectionTpl> & data,
60  const Eigen::MatrixBase<VectorLikeC> & c_ref,
61  const std::vector<RigidConstraintModelTpl<Scalar, Options>, ConstraintModelAllocator> &
63  std::vector<RigidConstraintDataTpl<Scalar, Options>, ConstraintDataAllocator> & contact_datas,
64  const std::vector<CoulombFrictionConeTpl<Scalar>, CoulombFrictionConelAllocator> & cones,
65  const Eigen::MatrixBase<VectorLikeR> & R,
66  const Eigen::MatrixBase<VectorLikeGamma> & constraint_correction,
67  ProximalSettingsTpl<Scalar> & settings,
68  const boost::optional<VectorLikeImp> & impulse_guess = boost::none)
69  {
70 
71  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options> MatrixXs;
72  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options> VectorXs;
73  typedef Eigen::Matrix<Scalar, 3, 1, Options> Vector3;
74 
75  int problem_size = R.size();
76  int n_contacts = (int)problem_size / 3;
77  PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_correction.size(), problem_size);
79  PINOCCHIO_CHECK_ARGUMENT_SIZE(contact_datas.size(), n_contacts);
81  check_expression_if_real<Scalar>(settings.mu > Scalar(0)), "mu has to be strictly positive");
82  MatrixXs J = MatrixXs::Zero(problem_size, model.nv); // TODO: malloc
84  VectorXs c_ref_cor, desaxce_correction, R_prox, impulse_c_prev, dimpulse_c; // TODO: malloc
85  R_prox = R + VectorXs::Constant(problem_size, settings.mu);
86  c_ref_cor = c_ref + constraint_correction;
87  if (impulse_guess)
88  {
89  data.impulse_c = impulse_guess.get();
90  PINOCCHIO_CHECK_ARGUMENT_SIZE(data.impulse_c.size(), problem_size);
91  }
92  else
93  {
94  data.impulse_c.setZero();
95  }
96  Scalar impulse_c_prev_norm_inf = data.impulse_c.template lpNorm<Eigen::Infinity>();
97  Scalar complementarity, dual_feasibility;
98  bool abs_prec_reached = false, rel_prec_reached = false;
99  const size_t nc = cones.size(); // num constraints
100  settings.iter = 1;
101  for (; settings.iter <= settings.max_iter; ++settings.iter)
102  {
103  impulse_c_prev = data.impulse_c;
104  for (size_t cone_id = 0; cone_id < nc; ++cone_id)
105  {
106  const Eigen::DenseIndex row_id = 3 * cone_id;
107  const auto & cone = cones[cone_id];
108  auto impulse_segment = data.impulse_c.template segment<3>(row_id);
109  auto impulse_prev_segment = impulse_c_prev.template segment<3>(row_id);
110  auto R_prox_segment = R_prox.template segment<3>(row_id);
111  // Vector3 desaxce_segment;
112  // auto desaxce_segment = desaxce_correction.template segment<3>(row_id);
113  auto c_ref_segment = c_ref.template segment<3>(row_id);
114  Vector3 desaxce_segment = cone.computeNormalCorrection(
115  c_ref_segment
116  + (R.template segment<3>(row_id).array() * impulse_segment.array()).matrix());
117  impulse_segment =
118  -((c_ref_segment + desaxce_segment - settings.mu * impulse_prev_segment).array()
119  / R_prox_segment.array())
120  .matrix();
121  impulse_segment = cone.weightedProject(impulse_segment, R_prox_segment);
122  }
123  dimpulse_c = data.impulse_c - impulse_c_prev;
124  settings.relative_residual = dimpulse_c.template lpNorm<Eigen::Infinity>();
125 
126  // if( check_expression_if_real<Scalar,false>(complementarity <= this->absolute_precision)
127  // && check_expression_if_real<Scalar,false>(dual_feasibility <= this->absolute_precision)
128  // && check_expression_if_real<Scalar,false>(primal_feasibility <=
129  // this->absolute_precision))
130  // abs_prec_reached = true;
131  // else
132  // abs_prec_reached = false;
133 
134  const Scalar impulse_c_norm_inf = data.impulse_c.template lpNorm<Eigen::Infinity>();
135  if (check_expression_if_real<Scalar, false>(
136  settings.relative_residual
137  <= settings.relative_accuracy * math::max(impulse_c_norm_inf, impulse_c_prev_norm_inf)))
138  rel_prec_reached = true;
139  else
140  rel_prec_reached = false;
141 
142  if (abs_prec_reached || rel_prec_reached)
143  break;
144 
145  impulse_c_prev_norm_inf = impulse_c_norm_inf;
146  }
147  return data.impulse_c;
148  }
149 
176  template<
177  typename Scalar,
178  int Options,
179  template<typename, int>
180  class JointCollectionTpl,
181  typename ConfigVectorType,
182  typename TangentVectorType1,
183  typename TangentVectorType2,
184  class ConstraintModelAllocator,
185  class ConstraintDataAllocator,
186  class CoulombFrictionConelAllocator,
187  typename VectorLikeR,
188  typename VectorLikeGamma,
189  typename VectorLikeLam>
190  PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility")
191  const typename DataTpl<Scalar, Options, JointCollectionTpl>::
192  TangentVectorType & contactInverseDynamics(
193  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
194  DataTpl<Scalar, Options, JointCollectionTpl> & data,
195  const Eigen::MatrixBase<ConfigVectorType> & q,
196  const Eigen::MatrixBase<TangentVectorType1> & v,
197  const Eigen::MatrixBase<TangentVectorType2> & a,
198  Scalar dt,
199  const std::vector<RigidConstraintModelTpl<Scalar, Options>, ConstraintModelAllocator> &
201  std::vector<RigidConstraintDataTpl<Scalar, Options>, ConstraintDataAllocator> & contact_datas,
202  const std::vector<CoulombFrictionConeTpl<Scalar>, CoulombFrictionConelAllocator> & cones,
203  const Eigen::MatrixBase<VectorLikeR> & R,
204  const Eigen::MatrixBase<VectorLikeGamma> & constraint_correction,
205  ProximalSettingsTpl<Scalar> & settings,
206  const boost::optional<VectorLikeLam> & lambda_guess = boost::none)
207  {
208 
209  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options> MatrixXs;
210  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options> VectorXs;
213 
214  int problem_size = R.size();
215  int n_contacts = (int)problem_size / 3;
216  MatrixXs J = MatrixXs::Zero(problem_size, model.nv); // TODO: malloc
218  VectorXs v_ref, c_ref, tau_c;
219  v_ref = v + dt * a;
220  c_ref.noalias() = J * v_ref; // TODO should rather use the displacement
221  boost::optional<VectorXs> impulse_guess = boost::none;
222  if (lambda_guess)
223  {
224  data.impulse_c = lambda_guess.get();
225  data.impulse_c *= dt;
226  impulse_guess = boost::make_optional(data.impulse_c);
227  }
229  model, data, c_ref, contact_models, contact_datas, cones, R, constraint_correction, settings,
230  impulse_guess);
231  data.lambda_c = data.impulse_c / dt;
233  for (int i = 0; i < model.njoints; i++)
234  {
235  fext[i] = Force::Zero();
236  }
237  for (int i = 0; i < n_contacts; i++)
238  {
239  const auto & cmodel = contact_models[i];
240  const Eigen::DenseIndex row_id = 3 * i;
241  auto lambda_segment = data.lambda_c.template segment<3>(row_id);
242  typename RigidConstraintData::Matrix6 actInv_transpose1 =
243  cmodel.joint1_placement.toActionMatrixInverse();
244  actInv_transpose1.transposeInPlace();
245  fext[cmodel.joint1_id] += Force(actInv_transpose1.template leftCols<3>() * lambda_segment);
246  typename RigidConstraintData::Matrix6 actInv_transpose2 =
247  cmodel.joint2_placement.toActionMatrixInverse();
248  actInv_transpose2.transposeInPlace();
249  fext[cmodel.joint2_id] += Force(actInv_transpose2.template leftCols<3>() * lambda_segment);
250  }
251  rnea(model, data, q, v, a, fext);
252  return data.tau;
253  }
254 
255 } // namespace pinocchio
256 
257 // #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
258 // #include "pinocchio/algorithm/contact-inverse-dynamics.txx"
259 // #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
260 
261 #endif // ifndef __pinocchio_algorithm_contact_inverse_dynamics_hpp__
pinocchio::RigidConstraintData
RigidConstraintDataTpl< context::Scalar, context::Options > RigidConstraintData
Definition: algorithm/fwd.hpp:27
PINOCCHIO_CHECK_ARGUMENT_SIZE
#define PINOCCHIO_CHECK_ARGUMENT_SIZE(...)
Macro to check if the size of an element is equal to the expected size.
Definition: include/pinocchio/macros.hpp:217
Eigen
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::CoulombFrictionConeTpl
&#160;
Definition: algorithm/constraints/coulomb-friction-cone.hpp:20
contact-cholesky.hpp
PINOCCHIO_CHECK_INPUT_ARGUMENT
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
Macro to check an assert-like condition and throw a std::invalid_argument exception (with a message) ...
Definition: include/pinocchio/macros.hpp:193
pinocchio::Options
Options
Definition: joint-configuration.hpp:1116
inverse-kinematics.J
J
Definition: inverse-kinematics.py:31
inverse-kinematics.i
int i
Definition: inverse-kinematics.py:20
model.hpp
coulomb-friction-cone.hpp
pinocchio::contactInverseDynamics
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & contactInverseDynamics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a, Scalar dt, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_datas, const std::vector< CoulombFrictionConeTpl< Scalar >, CoulombFrictionConelAllocator > &cones, const Eigen::MatrixBase< VectorLikeR > &R, const Eigen::MatrixBase< VectorLikeGamma > &constraint_correction, ProximalSettingsTpl< Scalar > &settings, const boost::optional< VectorLikeLam > &lambda_guess=boost::none)
The Contact Inverse Dynamics algorithm. It computes the inverse dynamics in the presence of contacts,...
Definition: contact-inverse-dynamics.hpp:192
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::PINOCCHIO_UNSUPPORTED_MESSAGE
struct PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") ContactCholeskyDecompositionTpl
Contact Cholesky decomposition structure. This structure allows to compute in a efficient and parsimo...
Definition: algorithm/contact-cholesky.hpp:55
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
boost
contact-cholesky.cmodel
cmodel
Definition: contact-cholesky.py:28
R
R
pinocchio::python::VectorXs
context::VectorXs VectorXs
Definition: admm-solver.cpp:30
rnea.hpp
simulation-contact-dynamics.contact_datas
list contact_datas
Definition: simulation-contact-dynamics.py:65
proximal.hpp
pinocchio::ProximalSettingsTpl
Structure containing all the settings paramters for the proximal algorithms.
Definition: algorithm/fwd.hpp:13
pinocchio::RigidConstraintModelTpl
Definition: algorithm/constraints/fwd.hpp:14
pinocchio::context::MatrixXs
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
Definition: context/generic.hpp:49
pinocchio::RigidConstraintDataTpl
Definition: algorithm/constraints/fwd.hpp:16
data.hpp
pinocchio::ForceTpl< Scalar, Options >
pinocchio::context::Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Definition: context/generic.hpp:53
contact-jacobian.hpp
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1117
a
Vec3f a
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:1118
pinocchio::container::aligned_vector
std::vector< T, Eigen::aligned_allocator< T > > aligned_vector
Definition: container/aligned-vector.hpp:21
pinocchio::Force
ForceTpl< context::Scalar, context::Options > Force
Definition: spatial/fwd.hpp:64
pinocchio::rnea
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & rnea(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a)
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques accordi...
std
Definition: autodiff/casadi/utils/static-if.hpp:64
pinocchio::getConstraintsJacobian
void getConstraintsJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintDataAllocator > &constraint_model, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &constraint_data, const Eigen::MatrixBase< DynamicMatrixLike > &J)
Computes the kinematic Jacobian associatied to a given set of constraint models.
simulation-contact-dynamics.v_ref
v_ref
Definition: simulation-contact-dynamics.py:60
pinocchio::computeContactImpulses
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & computeContactImpulses(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< VectorLikeC > &c_ref, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_datas, const std::vector< CoulombFrictionConeTpl< Scalar >, CoulombFrictionConelAllocator > &cones, const Eigen::MatrixBase< VectorLikeR > &R, const Eigen::MatrixBase< VectorLikeGamma > &constraint_correction, ProximalSettingsTpl< Scalar > &settings, const boost::optional< VectorLikeImp > &impulse_guess=boost::none)
Compute the contact impulses given a target velocity of contact points.
Definition: contact-inverse-dynamics.hpp:57
contact-cholesky.contact_models
list contact_models
Definition: contact-cholesky.py:25
pinocchio::ForceTpl::Zero
static ForceTpl Zero()
Definition: force-tpl.hpp:110
cartpole-casadi.dt
float dt
Definition: cartpole-casadi.py:186
pinocchio::ModelTpl
Definition: context/generic.hpp:20
CppAD::max
AD< Scalar > max(const AD< Scalar > &x, const AD< Scalar > &y)
Definition: autodiff/cppad.hpp:180
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Sat Jun 22 2024 02:41:45