Crocoddyl
contact-invdyn.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2021-2024, Heriot-Watt University, University of Edinburgh
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
8 
9 #ifndef CROCODDYL_MULTIBODY_ACTIONS_CONTACT_INVDYN_HPP_
10 #define CROCODDYL_MULTIBODY_ACTIONS_CONTACT_INVDYN_HPP_
11 
12 #include "crocoddyl/core/actuation-base.hpp"
13 #include "crocoddyl/core/constraints/constraint-manager.hpp"
14 #include "crocoddyl/core/costs/cost-sum.hpp"
15 #include "crocoddyl/core/diff-action-base.hpp"
16 #include "crocoddyl/multibody/contacts/multiple-contacts.hpp"
17 #include "crocoddyl/multibody/data/contacts.hpp"
18 #include "crocoddyl/multibody/fwd.hpp"
19 #include "crocoddyl/multibody/states/multibody.hpp"
20 
21 namespace crocoddyl {
22 
43 template <typename _Scalar>
45  : public DifferentialActionModelAbstractTpl<_Scalar> {
46  public:
47  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
48 
49  typedef _Scalar Scalar;
62  typedef typename MathBase::VectorXs VectorXs;
63  typedef typename MathBase::MatrixXs MatrixXs;
64 
77  std::shared_ptr<StateMultibody> state,
78  std::shared_ptr<ActuationModelAbstract> actuation,
79  std::shared_ptr<ContactModelMultiple> contacts,
80  std::shared_ptr<CostModelSum> costs);
81 
92  std::shared_ptr<StateMultibody> state,
93  std::shared_ptr<ActuationModelAbstract> actuation,
94  std::shared_ptr<ContactModelMultiple> contacts,
95  std::shared_ptr<CostModelSum> costs,
96  std::shared_ptr<ConstraintModelManager> constraints);
98 
109  virtual void calc(const std::shared_ptr<DifferentialActionDataAbstract>& data,
110  const Eigen::Ref<const VectorXs>& x,
111  const Eigen::Ref<const VectorXs>& u);
112 
118  virtual void calc(const std::shared_ptr<DifferentialActionDataAbstract>& data,
119  const Eigen::Ref<const VectorXs>& x);
120 
134  virtual void calcDiff(
135  const std::shared_ptr<DifferentialActionDataAbstract>& data,
136  const Eigen::Ref<const VectorXs>& x, const Eigen::Ref<const VectorXs>& u);
137 
143  virtual void calcDiff(
144  const std::shared_ptr<DifferentialActionDataAbstract>& data,
145  const Eigen::Ref<const VectorXs>& x);
146 
152  virtual std::shared_ptr<DifferentialActionDataAbstract> createData();
153 
158  virtual bool checkData(
159  const std::shared_ptr<DifferentialActionDataAbstract>& data);
160 
174  virtual void quasiStatic(
175  const std::shared_ptr<DifferentialActionDataAbstract>& data,
176  Eigen::Ref<VectorXs> u, const Eigen::Ref<const VectorXs>& x,
177  const std::size_t maxiter = 100, const Scalar tol = Scalar(1e-9));
178 
182  virtual std::size_t get_ng() const;
183 
187  virtual std::size_t get_nh() const;
188 
192  virtual std::size_t get_ng_T() const;
193 
197  virtual std::size_t get_nh_T() const;
198 
202  virtual const VectorXs& get_g_lb() const;
203 
207  virtual const VectorXs& get_g_ub() const;
208 
212  const std::shared_ptr<ActuationModelAbstract>& get_actuation() const;
213 
217  const std::shared_ptr<ContactModelMultiple>& get_contacts() const;
218 
222  const std::shared_ptr<CostModelSum>& get_costs() const;
223 
227  const std::shared_ptr<ConstraintModelManager>& get_constraints() const;
228 
232  pinocchio::ModelTpl<Scalar>& get_pinocchio() const;
233 
238  virtual void print(std::ostream& os) const;
239 
240  protected:
241  using Base::g_lb_;
242  using Base::g_ub_;
243  using Base::ng_;
244  using Base::nh_;
245  using Base::nu_;
246  using Base::state_;
247 
248  private:
249  void init(const std::shared_ptr<StateMultibody>& state);
250  std::shared_ptr<ActuationModelAbstract> actuation_;
251  std::shared_ptr<ContactModelMultiple> contacts_;
252  std::shared_ptr<CostModelSum> costs_;
253  std::shared_ptr<ConstraintModelManager> constraints_;
254  pinocchio::ModelTpl<Scalar>& pinocchio_;
255 
256  public:
271  public:
272  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
273 
274  typedef _Scalar Scalar;
280  typedef typename MathBase::VectorXs VectorXs;
281 
289  ResidualModelActuation(std::shared_ptr<StateMultibody> state,
290  const std::size_t nu, const std::size_t nc)
291  : Base(state, state->get_nv() - nu, state->get_nv() + nc, true, true,
292  true),
293  na_(nu),
294  nc_(nc) {}
295  virtual ~ResidualModelActuation() {}
296 
304  virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
305  const Eigen::Ref<const VectorXs>&,
306  const Eigen::Ref<const VectorXs>&) {
307  typename Data::ResidualDataActuation* d =
308  static_cast<typename Data::ResidualDataActuation*>(data.get());
309  // Update the under-actuation set and residual
310  std::size_t nrow = 0;
311  for (std::size_t k = 0;
312  k < static_cast<std::size_t>(d->actuation->tau_set.size()); ++k) {
313  if (!d->actuation->tau_set[k]) {
314  data->r(nrow) = d->pinocchio->tau(k);
315  nrow += 1;
316  }
317  }
318  }
319 
324  virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
325  const Eigen::Ref<const VectorXs>&) {
326  data->r.setZero();
327  }
328 
336  virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
337  const Eigen::Ref<const VectorXs>&,
338  const Eigen::Ref<const VectorXs>&) {
339  typename Data::ResidualDataActuation* d =
340  static_cast<typename Data::ResidualDataActuation*>(data.get());
341  std::size_t nrow = 0;
342  const std::size_t nv = state_->get_nv();
343  d->dtau_dx.leftCols(nv) = d->pinocchio->dtau_dq;
344  d->dtau_dx.rightCols(nv) = d->pinocchio->dtau_dv;
345  d->dtau_dx -= d->actuation->dtau_dx;
346  d->dtau_du.leftCols(nv) = d->pinocchio->M;
347  d->dtau_du.rightCols(nc_) = -d->contact->Jc.transpose();
348  for (std::size_t k = 0;
349  k < static_cast<std::size_t>(d->actuation->tau_set.size()); ++k) {
350  if (!d->actuation->tau_set[k]) {
351  d->Rx.row(nrow) = d->dtau_dx.row(k);
352  d->Ru.row(nrow) = d->dtau_du.row(k);
353  nrow += 1;
354  }
355  }
356  }
357 
363  virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
364  const Eigen::Ref<const VectorXs>&) {
365  data->Rx.setZero();
366  data->Ru.setZero();
367  }
368 
374  virtual std::shared_ptr<ResidualDataAbstract> createData(
375  DataCollectorAbstract* const data) {
376  return std::allocate_shared<typename Data::ResidualDataActuation>(
377  Eigen::aligned_allocator<typename Data::ResidualDataActuation>(),
378  this, data);
379  }
380 
386  virtual void print(std::ostream& os) const {
387  os << "ResidualModelActuation {nx=" << state_->get_nx()
388  << ", ndx=" << state_->get_ndx() << ", nu=" << nu_ << ", na=" << na_
389  << "}";
390  }
391 
392  protected:
393  using Base::nu_;
394  using Base::state_;
395 
396  private:
397  std::size_t na_;
398  std::size_t nc_;
399  };
400 
401  public:
418  public:
419  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
420 
421  typedef _Scalar Scalar;
427  typedef typename MathBase::VectorXs VectorXs;
428  typedef typename MathBase::MatrixXs MatrixXs;
429 
438  ResidualModelContact(std::shared_ptr<StateMultibody> state,
439  const pinocchio::FrameIndex id, const std::size_t nr,
440  const std::size_t nc)
441  : Base(state, nr, state->get_nv() + nc, true, true, true),
442  id_(id),
443  frame_name_(state->get_pinocchio()->frames[id].name) {}
444  virtual ~ResidualModelContact() {}
445 
453  void calc(const std::shared_ptr<ResidualDataAbstract>& data,
454  const Eigen::Ref<const VectorXs>&,
455  const Eigen::Ref<const VectorXs>&) {
456  typename Data::ResidualDataContact* d =
457  static_cast<typename Data::ResidualDataContact*>(data.get());
458  d->r = d->contact->a0;
459  }
460 
465  virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
466  const Eigen::Ref<const VectorXs>&) {
467  data->r.setZero();
468  }
469 
477  void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
478  const Eigen::Ref<const VectorXs>&,
479  const Eigen::Ref<const VectorXs>&) {
480  typename Data::ResidualDataContact* d =
481  static_cast<typename Data::ResidualDataContact*>(data.get());
482  d->Rx = d->contact->da0_dx;
483  d->Ru.leftCols(state_->get_nv()) = d->contact->Jc;
484  }
485 
491  virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
492  const Eigen::Ref<const VectorXs>&) {
493  data->Rx.setZero();
494  data->Ru.setZero();
495  }
496 
502  virtual std::shared_ptr<ResidualDataAbstract> createData(
503  DataCollectorAbstract* const data) {
504  return std::allocate_shared<typename Data::ResidualDataContact>(
505  Eigen::aligned_allocator<typename Data::ResidualDataContact>(), this,
506  data, id_);
507  }
508 
515  virtual void print(std::ostream& os) const {
516  os << "ResidualModelContact {frame=" << frame_name_ << ", nr=" << nr_
517  << "}";
518  }
519 
520  protected:
521  using Base::nr_;
522  using Base::nu_;
523  using Base::state_;
524 
525  private:
526  pinocchio::FrameIndex id_;
527  std::string frame_name_;
528  };
529 };
530 template <typename _Scalar>
532  : public DifferentialActionDataAbstractTpl<_Scalar> {
533  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
534  typedef _Scalar Scalar;
543  typedef typename MathBase::VectorXs VectorXs;
544  typedef typename MathBase::MatrixXs MatrixXs;
545 
546  template <template <typename Scalar> class Model>
548  Model<Scalar>* const model)
549  : Base(model),
550  pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
551  multibody(
552  &pinocchio, model->get_actuation()->createData(),
553  std::make_shared<JointDataAbstract>(
554  model->get_state(), model->get_actuation(), model->get_nu()),
555  model->get_contacts()->createData(&pinocchio)),
556  tmp_xstatic(model->get_state()->get_nx()),
557  tmp_rstatic(model->get_actuation()->get_nu() +
558  model->get_contacts()->get_nc()),
559  tmp_Jstatic(model->get_state()->get_nv(),
560  model->get_actuation()->get_nu() +
561  model->get_contacts()->get_nc()) {
562  // Set constant values for Fu, df_dx, and df_du
563  const std::size_t nv = model->get_state()->get_nv();
564  const std::size_t nc = model->get_contacts()->get_nc_total();
565  Fu.leftCols(nv).diagonal().setOnes();
566  multibody.joint->da_du.leftCols(nv).diagonal().setOnes();
567  MatrixXs df_dx = MatrixXs::Zero(nc, model->get_state()->get_ndx());
568  MatrixXs df_du = MatrixXs::Zero(nc, model->get_nu());
569  std::size_t fid = 0;
570  for (typename ContactModelMultiple::ContactModelContainer::const_iterator
571  it = model->get_contacts()->get_contacts().begin();
572  it != model->get_contacts()->get_contacts().end(); ++it) {
573  const std::size_t nc = it->second->contact->get_nc();
574  df_du.block(fid, nv + fid, nc, nc).diagonal().setOnes();
575  fid += nc;
576  }
577  model->get_contacts()->updateForceDiff(multibody.contacts, df_dx, df_du);
578  costs = model->get_costs()->createData(&multibody);
579  constraints = model->get_constraints()->createData(&multibody);
580  costs->shareMemory(this);
581  constraints->shareMemory(this);
582 
583  tmp_xstatic.setZero();
584  tmp_rstatic.setZero();
585  tmp_Jstatic.setZero();
586  }
587 
588  pinocchio::DataTpl<Scalar> pinocchio;
590  std::shared_ptr<CostDataSum> costs;
591  std::shared_ptr<ConstraintDataManager> constraints;
592  VectorXs
594  VectorXs
596  MatrixXs tmp_Jstatic;
597 
598  using Base::cost;
599  using Base::Fu;
600  using Base::Fx;
601  using Base::Lu;
602  using Base::Luu;
603  using Base::Lx;
604  using Base::Lxu;
605  using Base::Lxx;
606  using Base::r;
607  using Base::xout;
608 
610  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
611 
612  typedef _Scalar Scalar;
620  typedef typename MathBase::MatrixXs MatrixXs;
621 
622  template <template <typename Scalar> class Model>
623  ResidualDataActuation(Model<Scalar>* const model,
624  DataCollectorAbstract* const data)
625  : Base(model, data),
626  dtau_dx(model->get_state()->get_nv(), model->get_state()->get_ndx()),
627  dtau_du(model->get_state()->get_nv(), model->get_nu()) {
628  // Check that proper shared data has been passed
631  if (d == NULL) {
632  throw_pretty(
633  "Invalid argument: the shared data should be derived from "
634  "DataCollectorActMultibodyInContact");
635  }
636  // Avoids data casting at runtime
637  pinocchio = d->pinocchio;
638  actuation = d->actuation;
639  contact = d->contacts;
640  dtau_dx.setZero();
641  dtau_du.setZero();
642  }
643 
644  pinocchio::DataTpl<Scalar>* pinocchio;
645  std::shared_ptr<ActuationDataAbstract> actuation;
646  std::shared_ptr<ContactDataMultiple> contact;
647  MatrixXs dtau_dx;
648  MatrixXs dtau_du;
649  using Base::r;
650  using Base::Ru;
651  using Base::Rx;
652  using Base::shared;
653  };
654 
655  struct ResidualDataContact : public ResidualDataAbstractTpl<_Scalar> {
656  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
657 
658  typedef _Scalar Scalar;
665 
666  template <template <typename Scalar> class Model>
667  ResidualDataContact(Model<Scalar>* const model,
668  DataCollectorAbstract* const data, const std::size_t id)
669  : Base(model, data) {
671  dynamic_cast<DataCollectorMultibodyInContact*>(shared);
672  if (d == NULL) {
673  throw_pretty(
674  "Invalid argument: the shared data should be derived from "
675  "DataCollectorMultibodyInContact");
676  }
677  typename ContactModelMultiple::ContactDataContainer::iterator it, end;
678  for (it = d->contacts->contacts.begin(),
679  end = d->contacts->contacts.end();
680  it != end; ++it) {
681  if (id == it->second->frame) { // TODO(cmastalli): use model->get_id()
682  // and avoid to pass id in constructor
683  contact = it->second.get();
684  break;
685  }
686  }
687  }
688 
690  using Base::r;
691  using Base::Ru;
692  using Base::Rx;
693  using Base::shared;
694  };
695 };
696 } // namespace crocoddyl
697 
698 /* --- Details -------------------------------------------------------------- */
699 /* --- Details -------------------------------------------------------------- */
700 /* --- Details -------------------------------------------------------------- */
701 #include <crocoddyl/multibody/actions/contact-invdyn.hxx>
702 
703 #endif // CROCODDYL_MULTIBODY_ACTIONS_CONTACT_INVDYN_HPP_
Abstract class for the actuation-mapping model.
Define a stack of contact models.
Abstract class for differential action model.
std::shared_ptr< StateAbstract > state_
Model of the state.
VectorXs g_ub_
Lower bound of the inequality constraints.
std::size_t nh_
Number of equality constraints.
VectorXs g_lb_
Lower bound of the inequality constraints.
std::size_t ng_
Number of inequality constraints.
ResidualModelActuation(std::shared_ptr< StateMultibody > state, const std::size_t nu, const std::size_t nc)
Initialize the actuation residual model.
virtual void calcDiff(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &)
Compute the derivatives of the actuation residual.
virtual void print(std::ostream &os) const
Print relevant information of the actuation residual model.
virtual void calc(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &)
Compute the actuation residual.
virtual void calc(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &)
virtual std::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the actuation residual data.
virtual void calcDiff(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &)
virtual void print(std::ostream &os) const
Print relevant information of the contact-acceleration residual model.
virtual void calc(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &)
void calcDiff(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &)
Compute the derivatives of the contact-acceleration residual.
ResidualModelContact(std::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const std::size_t nr, const std::size_t nc)
Initialize the contact-acceleration residual model.
virtual std::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the contact-acceleration residual data.
virtual void calcDiff(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &)
void calc(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &)
Compute the contact-acceleration residual.
Differential action model for contact inverse dynamics in multibody systems.
pinocchio::ModelTpl< Scalar > & get_pinocchio() const
Return the Pinocchio model.
DifferentialActionModelContactInvDynamicsTpl(std::shared_ptr< StateMultibody > state, std::shared_ptr< ActuationModelAbstract > actuation, std::shared_ptr< ContactModelMultiple > contacts, std::shared_ptr< CostModelSum > costs)
Initialize the contact inverse-dynamics action model.
virtual std::size_t get_ng() const
Return the number of inequality constraints.
const std::shared_ptr< ActuationModelAbstract > & get_actuation() const
Return the actuation model.
virtual std::shared_ptr< DifferentialActionDataAbstract > createData()
Create the contact inverse-dynamics data.
virtual std::size_t get_nh() const
Return the number of equality constraints.
virtual void print(std::ostream &os) const
Print relevant information of the contact inverse-dynamics model.
DifferentialActionModelContactInvDynamicsTpl(std::shared_ptr< StateMultibody > state, std::shared_ptr< ActuationModelAbstract > actuation, std::shared_ptr< ContactModelMultiple > contacts, std::shared_ptr< CostModelSum > costs, std::shared_ptr< ConstraintModelManager > constraints)
Initialize the contact inverse-dynamics action model.
const std::shared_ptr< ConstraintModelManager > & get_constraints() const
Return the constraint model manager.
virtual void calcDiff(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the derivatives of the dynamics, cost and constraint functions.
virtual const VectorXs & get_g_lb() const
Return the lower bound of the inequality constraints.
virtual void calc(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the system acceleration, cost value and constraint residuals.
virtual std::size_t get_nh_T() const
Return the number of equality terminal constraints.
virtual bool checkData(const std::shared_ptr< DifferentialActionDataAbstract > &data)
Checks that a specific data belongs to the contact inverse-dynamics model.
virtual void quasiStatic(const std::shared_ptr< DifferentialActionDataAbstract > &data, Eigen::Ref< VectorXs > u, const Eigen::Ref< const VectorXs > &x, const std::size_t maxiter=100, const Scalar tol=Scalar(1e-9))
Computes the quasic static commands.
virtual void calcDiff(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
const std::shared_ptr< CostModelSum > & get_costs() const
Return the cost model.
virtual std::size_t get_ng_T() const
Return the number of equality terminal constraints.
const std::shared_ptr< ContactModelMultiple > & get_contacts() const
Return the contact model.
virtual const VectorXs & get_g_ub() const
Return the upper bound of the inequality constraints.
virtual void calc(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
Abstract class for residual models.
std::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
std::size_t nr_
Residual vector dimension.
State multibody representation.
Definition: multibody.hpp:35
MatrixXs Jc
Contact Jacobian.
Definition: force-base.hpp:53
Define the multi-contact data.
MatrixXs Fx
Jacobian of the dynamics w.r.t. the state .
MatrixXs Fu
Jacobian of the dynamics w.r.t. the control .
MatrixXs Luu
Hessian of the cost w.r.t. the control .
VectorXs Lx
Jacobian of the cost w.r.t. the state .
MatrixXs Lxx
Hessian of the cost w.r.t. the state .
VectorXs Lu
Jacobian of the cost w.r.t. the control .
MatrixXs Ru
Jacobian of the residual vector with respect the control.
MatrixXs Rx
Jacobian of the residual vector with respect the state.
std::shared_ptr< ActuationDataAbstract > actuation
Actuation data.
DataCollectorAbstract * shared
Shared data allocated by the action model.
MatrixXs Ru
Jacobian of the residual vector with respect the control.
MatrixXs Rx
Jacobian of the residual vector with respect the state.
ContactDataAbstractTpl< Scalar > * contact
Contact force data.
DataCollectorAbstract * shared
Shared data allocated by the action model.
MatrixXs Fu
Jacobian of the dynamics w.r.t. the control .
DataCollectorJointActMultibodyInContact multibody
Multibody data.
std::shared_ptr< ConstraintDataManager > constraints
Constraints data.
VectorXs tmp_xstatic
State point used for computing the quasi-static input.
VectorXs tmp_rstatic
Factorization used for computing the quasi-static input.
pinocchio::DataTpl< Scalar > pinocchio
Pinocchio data.
std::shared_ptr< CostDataSum > costs
Costs data.
MatrixXs tmp_Jstatic
Jacobian used for computing the quasi-static input.
MatrixXs Ru
Jacobian of the residual vector with respect the control.
MatrixXs Rx
Jacobian of the residual vector with respect the state.
DataCollectorAbstract * shared
Shared data allocated by the action model.