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 const VectorXs& get_g_lb() const;
194 
198  virtual const VectorXs& get_g_ub() const;
199 
203  const boost::shared_ptr<ActuationModelAbstract>& get_actuation() const;
204 
208  const boost::shared_ptr<ContactModelMultiple>& get_contacts() const;
209 
213  const boost::shared_ptr<CostModelSum>& get_costs() const;
214 
218  const boost::shared_ptr<ConstraintModelManager>& get_constraints() const;
219 
223  pinocchio::ModelTpl<Scalar>& get_pinocchio() const;
224 
229  virtual void print(std::ostream& os) const;
230 
231  protected:
232  using Base::g_lb_;
233  using Base::g_ub_;
234  using Base::ng_;
235  using Base::nh_;
236  using Base::nu_;
237  using Base::state_;
238 
239  private:
240  void init(const boost::shared_ptr<StateMultibody>& state);
241  boost::shared_ptr<ActuationModelAbstract> actuation_;
242  boost::shared_ptr<ContactModelMultiple> contacts_;
243  boost::shared_ptr<CostModelSum> costs_;
244  boost::shared_ptr<ConstraintModelManager> constraints_;
245  pinocchio::ModelTpl<Scalar>& pinocchio_;
246 
247  public:
262  public:
263  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
264 
265  typedef _Scalar Scalar;
271  typedef typename MathBase::VectorXs VectorXs;
272 
280  ResidualModelActuation(boost::shared_ptr<StateMultibody> state,
281  const std::size_t nu, const std::size_t nc)
282  : Base(state, state->get_nv() - nu, state->get_nv() + nc, true, true,
283  true),
284  na_(nu),
285  nc_(nc) {}
286  virtual ~ResidualModelActuation() {}
287 
295  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
296  const Eigen::Ref<const VectorXs>&,
297  const Eigen::Ref<const VectorXs>&) {
298  typename Data::ResidualDataActuation* d =
299  static_cast<typename Data::ResidualDataActuation*>(data.get());
300  // Update the under-actuation set and residual
301  std::size_t nrow = 0;
302  for (std::size_t k = 0;
303  k < static_cast<std::size_t>(d->actuation->tau_set.size()); ++k) {
304  if (!d->actuation->tau_set[k]) {
305  data->r(nrow) = d->pinocchio->tau(k);
306  nrow += 1;
307  }
308  }
309  }
310 
315  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
316  const Eigen::Ref<const VectorXs>&) {
317  data->r.setZero();
318  }
319 
327  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
328  const Eigen::Ref<const VectorXs>&,
329  const Eigen::Ref<const VectorXs>&) {
330  typename Data::ResidualDataActuation* d =
331  static_cast<typename Data::ResidualDataActuation*>(data.get());
332  std::size_t nrow = 0;
333  const std::size_t nv = state_->get_nv();
334  d->dtau_dx.leftCols(nv) = d->pinocchio->dtau_dq;
335  d->dtau_dx.rightCols(nv) = d->pinocchio->dtau_dv;
336  d->dtau_dx -= d->actuation->dtau_dx;
337  d->dtau_du.leftCols(nv) = d->pinocchio->M;
338  d->dtau_du.rightCols(nc_) = -d->contact->Jc.transpose();
339  for (std::size_t k = 0;
340  k < static_cast<std::size_t>(d->actuation->tau_set.size()); ++k) {
341  if (!d->actuation->tau_set[k]) {
342  d->Rx.row(nrow) = d->dtau_dx.row(k);
343  d->Ru.row(nrow) = d->dtau_du.row(k);
344  nrow += 1;
345  }
346  }
347  }
348 
354  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
355  const Eigen::Ref<const VectorXs>&) {
356  data->Rx.setZero();
357  data->Ru.setZero();
358  }
359 
365  virtual boost::shared_ptr<ResidualDataAbstract> createData(
366  DataCollectorAbstract* const data) {
367  return boost::allocate_shared<typename Data::ResidualDataActuation>(
368  Eigen::aligned_allocator<typename Data::ResidualDataActuation>(),
369  this, data);
370  }
371 
377  virtual void print(std::ostream& os) const {
378  os << "ResidualModelActuation {nx=" << state_->get_nx()
379  << ", ndx=" << state_->get_ndx() << ", nu=" << nu_ << ", na=" << na_
380  << "}";
381  }
382 
383  protected:
384  using Base::nu_;
385  using Base::state_;
386 
387  private:
388  std::size_t na_;
389  std::size_t nc_;
390  };
391 
392  public:
409  public:
410  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
411 
412  typedef _Scalar Scalar;
418  typedef typename MathBase::VectorXs VectorXs;
419  typedef typename MathBase::MatrixXs MatrixXs;
420 
429  ResidualModelContact(boost::shared_ptr<StateMultibody> state,
430  const pinocchio::FrameIndex id, const std::size_t nr,
431  const std::size_t nc)
432  : Base(state, nr, state->get_nv() + nc, true, true, true),
433  id_(id),
434  frame_name_(state->get_pinocchio()->frames[id].name) {}
435  virtual ~ResidualModelContact() {}
436 
444  void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
445  const Eigen::Ref<const VectorXs>&,
446  const Eigen::Ref<const VectorXs>&) {
447  typename Data::ResidualDataContact* d =
448  static_cast<typename Data::ResidualDataContact*>(data.get());
449  d->r = d->contact->a0;
450  }
451 
456  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
457  const Eigen::Ref<const VectorXs>&) {
458  data->r.setZero();
459  }
460 
468  void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
469  const Eigen::Ref<const VectorXs>&,
470  const Eigen::Ref<const VectorXs>&) {
471  typename Data::ResidualDataContact* d =
472  static_cast<typename Data::ResidualDataContact*>(data.get());
473  d->Rx = d->contact->da0_dx;
474  d->Ru.leftCols(state_->get_nv()) = d->contact->Jc;
475  }
476 
482  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
483  const Eigen::Ref<const VectorXs>&) {
484  data->Rx.setZero();
485  data->Ru.setZero();
486  }
487 
493  virtual boost::shared_ptr<ResidualDataAbstract> createData(
494  DataCollectorAbstract* const data) {
495  return boost::allocate_shared<typename Data::ResidualDataContact>(
496  Eigen::aligned_allocator<typename Data::ResidualDataContact>(), this,
497  data, id_);
498  }
499 
506  virtual void print(std::ostream& os) const {
507  os << "ResidualModelContact {frame=" << frame_name_ << ", nr=" << nr_
508  << "}";
509  }
510 
511  protected:
512  using Base::nr_;
513  using Base::nu_;
514  using Base::state_;
515 
516  private:
517  pinocchio::FrameIndex id_;
518  std::string frame_name_;
519  };
520 };
521 template <typename _Scalar>
523  : public DifferentialActionDataAbstractTpl<_Scalar> {
524  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
525  typedef _Scalar Scalar;
534  typedef typename MathBase::VectorXs VectorXs;
535  typedef typename MathBase::MatrixXs MatrixXs;
536 
537  template <template <typename Scalar> class Model>
539  Model<Scalar>* const model)
540  : Base(model),
541  pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
542  multibody(
543  &pinocchio, model->get_actuation()->createData(),
544  boost::make_shared<JointDataAbstract>(
545  model->get_state(), model->get_actuation(), model->get_nu()),
546  model->get_contacts()->createData(&pinocchio)),
547  tmp_xstatic(model->get_state()->get_nx()),
548  tmp_rstatic(model->get_actuation()->get_nu() +
549  model->get_contacts()->get_nc()),
550  tmp_Jstatic(model->get_state()->get_nv(),
551  model->get_actuation()->get_nu() +
552  model->get_contacts()->get_nc()) {
553  // Set constant values for Fu, df_dx, and df_du
554  const std::size_t nv = model->get_state()->get_nv();
555  const std::size_t nc = model->get_contacts()->get_nc_total();
556  Fu.leftCols(nv).diagonal().setOnes();
557  multibody.joint->da_du.leftCols(nv).diagonal().setOnes();
558  MatrixXs df_dx = MatrixXs::Zero(nc, model->get_state()->get_ndx());
559  MatrixXs df_du = MatrixXs::Zero(nc, model->get_nu());
560  std::size_t fid = 0;
561  for (typename ContactModelMultiple::ContactModelContainer::const_iterator
562  it = model->get_contacts()->get_contacts().begin();
563  it != model->get_contacts()->get_contacts().end(); ++it) {
564  const std::size_t nc = it->second->contact->get_nc();
565  df_du.block(fid, nv + fid, nc, nc).diagonal().setOnes();
566  fid += nc;
567  }
568  model->get_contacts()->updateForceDiff(multibody.contacts, df_dx, df_du);
569  costs = model->get_costs()->createData(&multibody);
570  constraints = model->get_constraints()->createData(&multibody);
571  costs->shareMemory(this);
572  constraints->shareMemory(this);
573 
574  tmp_xstatic.setZero();
575  tmp_rstatic.setZero();
576  tmp_Jstatic.setZero();
577  }
578 
579  pinocchio::DataTpl<Scalar> pinocchio;
581  boost::shared_ptr<CostDataSum> costs;
582  boost::shared_ptr<ConstraintDataManager> constraints;
583  VectorXs
585  VectorXs
587  MatrixXs tmp_Jstatic;
588 
589  using Base::cost;
590  using Base::Fu;
591  using Base::Fx;
592  using Base::Lu;
593  using Base::Luu;
594  using Base::Lx;
595  using Base::Lxu;
596  using Base::Lxx;
597  using Base::r;
598  using Base::xout;
599 
601  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
602 
603  typedef _Scalar Scalar;
611  typedef typename MathBase::MatrixXs MatrixXs;
612 
613  template <template <typename Scalar> class Model>
614  ResidualDataActuation(Model<Scalar>* const model,
615  DataCollectorAbstract* const data)
616  : Base(model, data),
617  dtau_dx(model->get_state()->get_nv(), model->get_state()->get_ndx()),
618  dtau_du(model->get_state()->get_nv(), model->get_nu()) {
619  // Check that proper shared data has been passed
622  if (d == NULL) {
623  throw_pretty(
624  "Invalid argument: the shared data should be derived from "
625  "DataCollectorActMultibodyInContact");
626  }
627  // Avoids data casting at runtime
628  pinocchio = d->pinocchio;
629  actuation = d->actuation;
630  contact = d->contacts;
631  dtau_dx.setZero();
632  dtau_du.setZero();
633  }
634 
635  pinocchio::DataTpl<Scalar>* pinocchio;
636  boost::shared_ptr<ActuationDataAbstract> actuation;
637  boost::shared_ptr<ContactDataMultiple> contact;
638  MatrixXs dtau_dx;
639  MatrixXs dtau_du;
640  using Base::r;
641  using Base::Ru;
642  using Base::Rx;
643  using Base::shared;
644  };
645 
646  struct ResidualDataContact : public ResidualDataAbstractTpl<_Scalar> {
647  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
648 
649  typedef _Scalar Scalar;
656 
657  template <template <typename Scalar> class Model>
658  ResidualDataContact(Model<Scalar>* const model,
659  DataCollectorAbstract* const data, const std::size_t id)
660  : Base(model, data) {
662  dynamic_cast<DataCollectorMultibodyInContact*>(shared);
663  if (d == NULL) {
664  throw_pretty(
665  "Invalid argument: the shared data should be derived from "
666  "DataCollectorMultibodyInContact");
667  }
668  typename ContactModelMultiple::ContactDataContainer::iterator it, end;
669  for (it = d->contacts->contacts.begin(),
670  end = d->contacts->contacts.end();
671  it != end; ++it) {
672  if (id == it->second->frame) { // TODO(cmastalli): use model->get_id()
673  // and avoid to pass id in constructor
674  contact = it->second.get();
675  break;
676  }
677  }
678  }
679 
681  using Base::r;
682  using Base::Ru;
683  using Base::Rx;
684  using Base::shared;
685  };
686 };
687 } // namespace crocoddyl
688 
689 /* --- Details -------------------------------------------------------------- */
690 /* --- Details -------------------------------------------------------------- */
691 /* --- Details -------------------------------------------------------------- */
692 #include <crocoddyl/multibody/actions/contact-invdyn.hxx>
693 
694 #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 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 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.