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  boost::shared_ptr<StateMultibody> state,
78  boost::shared_ptr<ActuationModelAbstract> actuation,
79  boost::shared_ptr<ContactModelMultiple> contacts,
80  boost::shared_ptr<CostModelSum> costs);
81 
92  boost::shared_ptr<StateMultibody> state,
93  boost::shared_ptr<ActuationModelAbstract> actuation,
94  boost::shared_ptr<ContactModelMultiple> contacts,
95  boost::shared_ptr<CostModelSum> costs,
96  boost::shared_ptr<ConstraintModelManager> constraints);
98 
109  virtual void calc(
110  const boost::shared_ptr<DifferentialActionDataAbstract>& data,
111  const Eigen::Ref<const VectorXs>& x, const Eigen::Ref<const VectorXs>& u);
112 
118  virtual void calc(
119  const boost::shared_ptr<DifferentialActionDataAbstract>& data,
120  const Eigen::Ref<const VectorXs>& x);
121 
135  virtual void calcDiff(
136  const boost::shared_ptr<DifferentialActionDataAbstract>& data,
137  const Eigen::Ref<const VectorXs>& x, const Eigen::Ref<const VectorXs>& u);
138 
144  virtual void calcDiff(
145  const boost::shared_ptr<DifferentialActionDataAbstract>& data,
146  const Eigen::Ref<const VectorXs>& x);
147 
153  virtual boost::shared_ptr<DifferentialActionDataAbstract> createData();
154 
159  virtual bool checkData(
160  const boost::shared_ptr<DifferentialActionDataAbstract>& data);
161 
175  virtual void quasiStatic(
176  const boost::shared_ptr<DifferentialActionDataAbstract>& data,
177  Eigen::Ref<VectorXs> u, const Eigen::Ref<const VectorXs>& x,
178  const std::size_t maxiter = 100, const Scalar tol = Scalar(1e-9));
179 
183  virtual std::size_t get_ng() const;
184 
188  virtual std::size_t get_nh() const;
189 
193  virtual std::size_t get_ng_T() const;
194 
198  virtual std::size_t get_nh_T() const;
199 
203  virtual const VectorXs& get_g_lb() const;
204 
208  virtual const VectorXs& get_g_ub() const;
209 
213  const boost::shared_ptr<ActuationModelAbstract>& get_actuation() const;
214 
218  const boost::shared_ptr<ContactModelMultiple>& get_contacts() const;
219 
223  const boost::shared_ptr<CostModelSum>& get_costs() const;
224 
228  const boost::shared_ptr<ConstraintModelManager>& get_constraints() const;
229 
233  pinocchio::ModelTpl<Scalar>& get_pinocchio() const;
234 
239  virtual void print(std::ostream& os) const;
240 
241  protected:
242  using Base::g_lb_;
243  using Base::g_ub_;
244  using Base::ng_;
245  using Base::nh_;
246  using Base::nu_;
247  using Base::state_;
248 
249  private:
250  void init(const boost::shared_ptr<StateMultibody>& state);
251  boost::shared_ptr<ActuationModelAbstract> actuation_;
252  boost::shared_ptr<ContactModelMultiple> contacts_;
253  boost::shared_ptr<CostModelSum> costs_;
254  boost::shared_ptr<ConstraintModelManager> constraints_;
255  pinocchio::ModelTpl<Scalar>& pinocchio_;
256 
257  public:
272  public:
273  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
274 
275  typedef _Scalar Scalar;
281  typedef typename MathBase::VectorXs VectorXs;
282 
290  ResidualModelActuation(boost::shared_ptr<StateMultibody> state,
291  const std::size_t nu, const std::size_t nc)
292  : Base(state, state->get_nv() - nu, state->get_nv() + nc, true, true,
293  true),
294  na_(nu),
295  nc_(nc) {}
296  virtual ~ResidualModelActuation() {}
297 
305  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
306  const Eigen::Ref<const VectorXs>&,
307  const Eigen::Ref<const VectorXs>&) {
308  typename Data::ResidualDataActuation* d =
309  static_cast<typename Data::ResidualDataActuation*>(data.get());
310  // Update the under-actuation set and residual
311  std::size_t nrow = 0;
312  for (std::size_t k = 0;
313  k < static_cast<std::size_t>(d->actuation->tau_set.size()); ++k) {
314  if (!d->actuation->tau_set[k]) {
315  data->r(nrow) = d->pinocchio->tau(k);
316  nrow += 1;
317  }
318  }
319  }
320 
325  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
326  const Eigen::Ref<const VectorXs>&) {
327  data->r.setZero();
328  }
329 
337  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
338  const Eigen::Ref<const VectorXs>&,
339  const Eigen::Ref<const VectorXs>&) {
340  typename Data::ResidualDataActuation* d =
341  static_cast<typename Data::ResidualDataActuation*>(data.get());
342  std::size_t nrow = 0;
343  const std::size_t nv = state_->get_nv();
344  d->dtau_dx.leftCols(nv) = d->pinocchio->dtau_dq;
345  d->dtau_dx.rightCols(nv) = d->pinocchio->dtau_dv;
346  d->dtau_dx -= d->actuation->dtau_dx;
347  d->dtau_du.leftCols(nv) = d->pinocchio->M;
348  d->dtau_du.rightCols(nc_) = -d->contact->Jc.transpose();
349  for (std::size_t k = 0;
350  k < static_cast<std::size_t>(d->actuation->tau_set.size()); ++k) {
351  if (!d->actuation->tau_set[k]) {
352  d->Rx.row(nrow) = d->dtau_dx.row(k);
353  d->Ru.row(nrow) = d->dtau_du.row(k);
354  nrow += 1;
355  }
356  }
357  }
358 
364  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
365  const Eigen::Ref<const VectorXs>&) {
366  data->Rx.setZero();
367  data->Ru.setZero();
368  }
369 
375  virtual boost::shared_ptr<ResidualDataAbstract> createData(
376  DataCollectorAbstract* const data) {
377  return boost::allocate_shared<typename Data::ResidualDataActuation>(
378  Eigen::aligned_allocator<typename Data::ResidualDataActuation>(),
379  this, data);
380  }
381 
387  virtual void print(std::ostream& os) const {
388  os << "ResidualModelActuation {nx=" << state_->get_nx()
389  << ", ndx=" << state_->get_ndx() << ", nu=" << nu_ << ", na=" << na_
390  << "}";
391  }
392 
393  protected:
394  using Base::nu_;
395  using Base::state_;
396 
397  private:
398  std::size_t na_;
399  std::size_t nc_;
400  };
401 
402  public:
419  public:
420  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
421 
422  typedef _Scalar Scalar;
428  typedef typename MathBase::VectorXs VectorXs;
429  typedef typename MathBase::MatrixXs MatrixXs;
430 
439  ResidualModelContact(boost::shared_ptr<StateMultibody> state,
440  const pinocchio::FrameIndex id, const std::size_t nr,
441  const std::size_t nc)
442  : Base(state, nr, state->get_nv() + nc, true, true, true),
443  id_(id),
444  frame_name_(state->get_pinocchio()->frames[id].name) {}
445  virtual ~ResidualModelContact() {}
446 
454  void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
455  const Eigen::Ref<const VectorXs>&,
456  const Eigen::Ref<const VectorXs>&) {
457  typename Data::ResidualDataContact* d =
458  static_cast<typename Data::ResidualDataContact*>(data.get());
459  d->r = d->contact->a0;
460  }
461 
466  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
467  const Eigen::Ref<const VectorXs>&) {
468  data->r.setZero();
469  }
470 
478  void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
479  const Eigen::Ref<const VectorXs>&,
480  const Eigen::Ref<const VectorXs>&) {
481  typename Data::ResidualDataContact* d =
482  static_cast<typename Data::ResidualDataContact*>(data.get());
483  d->Rx = d->contact->da0_dx;
484  d->Ru.leftCols(state_->get_nv()) = d->contact->Jc;
485  }
486 
492  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
493  const Eigen::Ref<const VectorXs>&) {
494  data->Rx.setZero();
495  data->Ru.setZero();
496  }
497 
503  virtual boost::shared_ptr<ResidualDataAbstract> createData(
504  DataCollectorAbstract* const data) {
505  return boost::allocate_shared<typename Data::ResidualDataContact>(
506  Eigen::aligned_allocator<typename Data::ResidualDataContact>(), this,
507  data, id_);
508  }
509 
516  virtual void print(std::ostream& os) const {
517  os << "ResidualModelContact {frame=" << frame_name_ << ", nr=" << nr_
518  << "}";
519  }
520 
521  protected:
522  using Base::nr_;
523  using Base::nu_;
524  using Base::state_;
525 
526  private:
527  pinocchio::FrameIndex id_;
528  std::string frame_name_;
529  };
530 };
531 template <typename _Scalar>
533  : public DifferentialActionDataAbstractTpl<_Scalar> {
534  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
535  typedef _Scalar Scalar;
544  typedef typename MathBase::VectorXs VectorXs;
545  typedef typename MathBase::MatrixXs MatrixXs;
546 
547  template <template <typename Scalar> class Model>
549  Model<Scalar>* const model)
550  : Base(model),
551  pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
552  multibody(
553  &pinocchio, model->get_actuation()->createData(),
554  boost::make_shared<JointDataAbstract>(
555  model->get_state(), model->get_actuation(), model->get_nu()),
556  model->get_contacts()->createData(&pinocchio)),
557  tmp_xstatic(model->get_state()->get_nx()),
558  tmp_rstatic(model->get_actuation()->get_nu() +
559  model->get_contacts()->get_nc()),
560  tmp_Jstatic(model->get_state()->get_nv(),
561  model->get_actuation()->get_nu() +
562  model->get_contacts()->get_nc()) {
563  // Set constant values for Fu, df_dx, and df_du
564  const std::size_t nv = model->get_state()->get_nv();
565  const std::size_t nc = model->get_contacts()->get_nc_total();
566  Fu.leftCols(nv).diagonal().setOnes();
567  multibody.joint->da_du.leftCols(nv).diagonal().setOnes();
568  MatrixXs df_dx = MatrixXs::Zero(nc, model->get_state()->get_ndx());
569  MatrixXs df_du = MatrixXs::Zero(nc, model->get_nu());
570  std::size_t fid = 0;
571  for (typename ContactModelMultiple::ContactModelContainer::const_iterator
572  it = model->get_contacts()->get_contacts().begin();
573  it != model->get_contacts()->get_contacts().end(); ++it) {
574  const std::size_t nc = it->second->contact->get_nc();
575  df_du.block(fid, nv + fid, nc, nc).diagonal().setOnes();
576  fid += nc;
577  }
578  model->get_contacts()->updateForceDiff(multibody.contacts, df_dx, df_du);
579  costs = model->get_costs()->createData(&multibody);
580  constraints = model->get_constraints()->createData(&multibody);
581  costs->shareMemory(this);
582  constraints->shareMemory(this);
583 
584  tmp_xstatic.setZero();
585  tmp_rstatic.setZero();
586  tmp_Jstatic.setZero();
587  }
588 
589  pinocchio::DataTpl<Scalar> pinocchio;
591  boost::shared_ptr<CostDataSum> costs;
592  boost::shared_ptr<ConstraintDataManager> constraints;
593  VectorXs
595  VectorXs
597  MatrixXs tmp_Jstatic;
598 
599  using Base::cost;
600  using Base::Fu;
601  using Base::Fx;
602  using Base::Lu;
603  using Base::Luu;
604  using Base::Lx;
605  using Base::Lxu;
606  using Base::Lxx;
607  using Base::r;
608  using Base::xout;
609 
611  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
612 
613  typedef _Scalar Scalar;
621  typedef typename MathBase::MatrixXs MatrixXs;
622 
623  template <template <typename Scalar> class Model>
624  ResidualDataActuation(Model<Scalar>* const model,
625  DataCollectorAbstract* const data)
626  : Base(model, data),
627  dtau_dx(model->get_state()->get_nv(), model->get_state()->get_ndx()),
628  dtau_du(model->get_state()->get_nv(), model->get_nu()) {
629  // Check that proper shared data has been passed
632  if (d == NULL) {
633  throw_pretty(
634  "Invalid argument: the shared data should be derived from "
635  "DataCollectorActMultibodyInContact");
636  }
637  // Avoids data casting at runtime
638  pinocchio = d->pinocchio;
639  actuation = d->actuation;
640  contact = d->contacts;
641  dtau_dx.setZero();
642  dtau_du.setZero();
643  }
644 
645  pinocchio::DataTpl<Scalar>* pinocchio;
646  boost::shared_ptr<ActuationDataAbstract> actuation;
647  boost::shared_ptr<ContactDataMultiple> contact;
648  MatrixXs dtau_dx;
649  MatrixXs dtau_du;
650  using Base::r;
651  using Base::Ru;
652  using Base::Rx;
653  using Base::shared;
654  };
655 
656  struct ResidualDataContact : public ResidualDataAbstractTpl<_Scalar> {
657  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
658 
659  typedef _Scalar Scalar;
666 
667  template <template <typename Scalar> class Model>
668  ResidualDataContact(Model<Scalar>* const model,
669  DataCollectorAbstract* const data, const std::size_t id)
670  : Base(model, data) {
672  dynamic_cast<DataCollectorMultibodyInContact*>(shared);
673  if (d == NULL) {
674  throw_pretty(
675  "Invalid argument: the shared data should be derived from "
676  "DataCollectorMultibodyInContact");
677  }
678  typename ContactModelMultiple::ContactDataContainer::iterator it, end;
679  for (it = d->contacts->contacts.begin(),
680  end = d->contacts->contacts.end();
681  it != end; ++it) {
682  if (id == it->second->frame) { // TODO(cmastalli): use model->get_id()
683  // and avoid to pass id in constructor
684  contact = it->second.get();
685  break;
686  }
687  }
688  }
689 
691  using Base::r;
692  using Base::Ru;
693  using Base::Rx;
694  using Base::shared;
695  };
696 };
697 } // namespace crocoddyl
698 
699 /* --- Details -------------------------------------------------------------- */
700 /* --- Details -------------------------------------------------------------- */
701 /* --- Details -------------------------------------------------------------- */
702 #include <crocoddyl/multibody/actions/contact-invdyn.hxx>
703 
704 #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.
VectorXs g_ub_
Lower bound of the inequality constraints.
boost::shared_ptr< StateAbstract > state_
Model of the state.
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.
virtual void print(std::ostream &os) const
Print relevant information of the actuation residual model.
virtual void calcDiff(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &)
Compute the derivatives of the actuation residual.
virtual boost::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the actuation residual data.
virtual void calc(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &)
virtual void calc(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &)
Compute the actuation residual.
ResidualModelActuation(boost::shared_ptr< StateMultibody > state, const std::size_t nu, const std::size_t nc)
Initialize the actuation residual model.
virtual void calcDiff(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &)
ResidualModelContact(boost::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 void print(std::ostream &os) const
Print relevant information of the contact-acceleration residual model.
void calcDiff(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &)
Compute the derivatives of the contact-acceleration residual.
boost::shared_ptr< StateAbstract > state_
State description.
virtual boost::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the contact-acceleration residual data.
virtual void calc(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &)
void calc(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &)
Compute the contact-acceleration residual.
virtual void calcDiff(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &)
Differential action model for contact inverse dynamics in multibody systems.
pinocchio::ModelTpl< Scalar > & get_pinocchio() const
Return the Pinocchio model.
DifferentialActionModelContactInvDynamicsTpl(boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActuationModelAbstract > actuation, boost::shared_ptr< ContactModelMultiple > contacts, boost::shared_ptr< CostModelSum > costs)
Initialize the contact inverse-dynamics action model.
const boost::shared_ptr< ContactModelMultiple > & get_contacts() const
Return the contact model.
virtual void calc(const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
virtual std::size_t get_ng() const
Return the number of inequality constraints.
virtual void calcDiff(const boost::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 std::size_t get_nh() const
Return the number of equality constraints.
virtual boost::shared_ptr< DifferentialActionDataAbstract > createData()
Create the contact inverse-dynamics data.
virtual void print(std::ostream &os) const
Print relevant information of the contact inverse-dynamics model.
virtual const VectorXs & get_g_lb() const
Return the lower bound of the inequality constraints.
const boost::shared_ptr< CostModelSum > & get_costs() const
Return the cost model.
DifferentialActionModelContactInvDynamicsTpl(boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActuationModelAbstract > actuation, boost::shared_ptr< ContactModelMultiple > contacts, boost::shared_ptr< CostModelSum > costs, boost::shared_ptr< ConstraintModelManager > constraints)
Initialize the contact inverse-dynamics action model.
virtual std::size_t get_nh_T() const
Return the number of equality terminal constraints.
virtual void calc(const boost::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.
const boost::shared_ptr< ConstraintModelManager > & get_constraints() const
Return the constraint model manager.
virtual void quasiStatic(const boost::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.
const boost::shared_ptr< ActuationModelAbstract > & get_actuation() const
Return the actuation model.
virtual std::size_t get_ng_T() const
Return the number of equality terminal constraints.
virtual bool checkData(const boost::shared_ptr< DifferentialActionDataAbstract > &data)
Checks that a specific data belongs to the contact inverse-dynamics model.
virtual const VectorXs & get_g_ub() const
Return the upper bound of the inequality constraints.
virtual void calcDiff(const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
Abstract class for residual models.
boost::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.
boost::shared_ptr< ActuationDataAbstract > actuation
Actuation data.
boost::shared_ptr< ContactDataMultiple > contact
Contact 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.
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.
MatrixXs tmp_Jstatic
Jacobian used for computing the quasi-static input.
boost::shared_ptr< CostDataSum > costs
Costs data.
boost::shared_ptr< ConstraintDataManager > constraints
Constraints data.
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.