Crocoddyl
free-invdyn.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2021-2022, 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_FREE_INVDYN_HPP_
10 #define CROCODDYL_MULTIBODY_ACTIONS_FREE_INVDYN_HPP_
11 
12 #include <stdexcept>
13 
14 #include "crocoddyl/core/actuation-base.hpp"
15 #include "crocoddyl/core/constraints/constraint-manager.hpp"
16 #include "crocoddyl/core/costs/cost-sum.hpp"
17 #include "crocoddyl/core/diff-action-base.hpp"
18 #include "crocoddyl/core/residual-base.hpp"
19 #include "crocoddyl/core/utils/exception.hpp"
20 #include "crocoddyl/multibody/data/multibody.hpp"
21 #include "crocoddyl/multibody/fwd.hpp"
22 #include "crocoddyl/multibody/states/multibody.hpp"
23 
24 namespace crocoddyl {
25 
41 template <typename _Scalar>
43  : public DifferentialActionModelAbstractTpl<_Scalar> {
44  public:
45  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
46 
47  typedef _Scalar Scalar;
58  typedef typename MathBase::VectorXs VectorXs;
59 
71  boost::shared_ptr<StateMultibody> state,
72  boost::shared_ptr<ActuationModelAbstract> actuation,
73  boost::shared_ptr<CostModelSum> costs);
74 
84  boost::shared_ptr<StateMultibody> state,
85  boost::shared_ptr<ActuationModelAbstract> actuation,
86  boost::shared_ptr<CostModelSum> costs,
87  boost::shared_ptr<ConstraintModelManager> constraints);
89 
100  virtual void calc(
101  const boost::shared_ptr<DifferentialActionDataAbstract>& data,
102  const Eigen::Ref<const VectorXs>& x, const Eigen::Ref<const VectorXs>& u);
103 
109  virtual void calc(
110  const boost::shared_ptr<DifferentialActionDataAbstract>& data,
111  const Eigen::Ref<const VectorXs>& x);
112 
126  virtual void calcDiff(
127  const boost::shared_ptr<DifferentialActionDataAbstract>& data,
128  const Eigen::Ref<const VectorXs>& x, const Eigen::Ref<const VectorXs>& u);
129 
135  virtual void calcDiff(
136  const boost::shared_ptr<DifferentialActionDataAbstract>& data,
137  const Eigen::Ref<const VectorXs>& x);
138 
144  virtual boost::shared_ptr<DifferentialActionDataAbstract> createData();
145 
150  virtual bool checkData(
151  const boost::shared_ptr<DifferentialActionDataAbstract>& data);
152 
166  virtual void quasiStatic(
167  const boost::shared_ptr<DifferentialActionDataAbstract>& data,
168  Eigen::Ref<VectorXs> u, const Eigen::Ref<const VectorXs>& x,
169  const std::size_t maxiter = 100, const Scalar tol = Scalar(1e-9));
170 
174  virtual std::size_t get_ng() const;
175 
179  virtual std::size_t get_nh() const;
180 
184  virtual const VectorXs& get_g_lb() const;
185 
189  virtual const VectorXs& get_g_ub() const;
190 
194  const boost::shared_ptr<ActuationModelAbstract>& get_actuation() const;
195 
199  const boost::shared_ptr<CostModelSum>& get_costs() const;
200 
204  const boost::shared_ptr<ConstraintModelManager>& get_constraints() const;
205 
209  pinocchio::ModelTpl<Scalar>& get_pinocchio() const;
210 
216  virtual void print(std::ostream& os) const;
217 
218  protected:
219  using Base::g_lb_;
220  using Base::g_ub_;
221  using Base::ng_;
222  using Base::nh_;
223  using Base::nu_;
224  using Base::state_;
225 
226  private:
227  void init(const boost::shared_ptr<StateMultibody>& state);
228  boost::shared_ptr<ActuationModelAbstract> actuation_;
229  boost::shared_ptr<CostModelSum> costs_;
230  boost::shared_ptr<ConstraintModelManager> constraints_;
231  pinocchio::ModelTpl<Scalar>& pinocchio_;
232 
233  public:
247  public:
248  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
249 
250  typedef _Scalar Scalar;
257  typedef typename MathBase::VectorXs VectorXs;
258  typedef typename MathBase::MatrixXs MatrixXs;
259 
266  ResidualModelActuation(boost::shared_ptr<StateMultibody> state,
267  const std::size_t nu)
268  : Base(state, state->get_nv() - nu, state->get_nv(), true, true, true),
269  na_(nu) {}
270  virtual ~ResidualModelActuation() {}
271 
279  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
280  const Eigen::Ref<const VectorXs>&,
281  const Eigen::Ref<const VectorXs>&) {
282  typename Data::ResidualDataActuation* d =
283  static_cast<typename Data::ResidualDataActuation*>(data.get());
284  // Update the under-actuation set and residual
285  std::size_t nrow = 0;
286  for (std::size_t k = 0;
287  k < static_cast<std::size_t>(d->actuation->tau_set.size()); ++k) {
288  if (!d->actuation->tau_set[k]) {
289  data->r(nrow) = d->pinocchio->tau(k);
290  nrow += 1;
291  }
292  }
293  }
294 
299  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
300  const Eigen::Ref<const VectorXs>&) {
301  data->r.setZero();
302  }
303 
311  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
312  const Eigen::Ref<const VectorXs>&,
313  const Eigen::Ref<const VectorXs>&) {
314  typename Data::ResidualDataActuation* d =
315  static_cast<typename Data::ResidualDataActuation*>(data.get());
316  std::size_t nrow = 0;
317  const std::size_t nv = state_->get_nv();
318  d->dtau_dx.leftCols(nv) = d->pinocchio->dtau_dq;
319  d->dtau_dx.rightCols(nv) = d->pinocchio->dtau_dv;
320  d->dtau_dx -= d->actuation->dtau_dx;
321  for (std::size_t k = 0;
322  k < static_cast<std::size_t>(d->actuation->tau_set.size()); ++k) {
323  if (!d->actuation->tau_set[k]) {
324  d->Rx.row(nrow) = d->dtau_dx.row(k);
325  d->Ru.row(nrow) = d->pinocchio->M.row(k);
326  nrow += 1;
327  }
328  }
329  }
330 
336  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
337  const Eigen::Ref<const VectorXs>&) {
338  data->Rx.setZero();
339  data->Ru.setZero();
340  }
341 
347  virtual boost::shared_ptr<ResidualDataAbstract> createData(
348  DataCollectorAbstract* const data) {
349  return boost::allocate_shared<typename Data::ResidualDataActuation>(
350  Eigen::aligned_allocator<typename Data::ResidualDataActuation>(),
351  this, data);
352  }
353 
359  virtual void print(std::ostream& os) const {
360  os << "ResidualModelActuation {nx=" << state_->get_nx()
361  << ", ndx=" << state_->get_ndx() << ", nu=" << nu_ << ", na=" << na_
362  << "}";
363  }
364 
365  protected:
366  std::size_t na_;
367  using Base::nu_;
368  using Base::state_;
369  };
370 };
371 
372 template <typename _Scalar>
374  : public DifferentialActionDataAbstractTpl<_Scalar> {
375  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
376  typedef _Scalar Scalar;
384  typedef typename MathBase::VectorXs VectorXs;
385 
386  template <template <typename Scalar> class Model>
387  explicit DifferentialActionDataFreeInvDynamicsTpl(Model<Scalar>* const model)
388  : Base(model),
389  pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
390  multibody(
391  &pinocchio, model->get_actuation()->createData(),
392  boost::make_shared<JointDataAbstract>(
393  model->get_state(), model->get_actuation(), model->get_nu())),
394  costs(model->get_costs()->createData(&multibody)),
395  constraints(model->get_constraints()->createData(&multibody)),
396  tmp_xstatic(model->get_state()->get_nx()) {
397  const std::size_t nv = model->get_state()->get_nv();
398  Fu.leftCols(nv).diagonal().setOnes();
399  multibody.joint->da_du.leftCols(nv).diagonal().setOnes();
400  costs->shareMemory(this);
401  constraints->shareMemory(this);
402  tmp_xstatic.setZero();
403  }
404 
405  pinocchio::DataTpl<Scalar> pinocchio;
407  boost::shared_ptr<CostDataSum> costs;
408  boost::shared_ptr<ConstraintDataManager> constraints;
409  VectorXs
411  using Base::cost;
412  using Base::Fu;
413  using Base::Fx;
414  using Base::Lu;
415  using Base::Luu;
416  using Base::Lx;
417  using Base::Lxu;
418  using Base::Lxx;
419  using Base::r;
420  using Base::xout;
421 
423  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
424 
425  typedef _Scalar Scalar;
431  typedef typename MathBase::MatrixXs MatrixXs;
432 
433  template <template <typename Scalar> class Model>
434  ResidualDataActuation(Model<Scalar>* const model,
435  DataCollectorAbstract* const data)
436  : Base(model, data),
437  dtau_dx(model->get_state()->get_nv(), model->get_state()->get_ndx()) {
438  dtau_dx.setZero();
439  // Check that proper shared data has been passed
441  dynamic_cast<DataCollectorActMultibody*>(shared);
442  if (d == NULL) {
443  throw_pretty(
444  "Invalid argument: the shared data should be derived from "
445  "DataCollectorActMultibody");
446  }
447 
448  // Avoids data casting at runtime
449  pinocchio = d->pinocchio;
450  actuation = d->actuation;
451  }
452 
453  pinocchio::DataTpl<Scalar>* pinocchio;
454  boost::shared_ptr<ActuationDataAbstract> actuation;
455  MatrixXs dtau_dx;
456  using Base::r;
457  using Base::Ru;
458  using Base::Rx;
459  using Base::shared;
460  };
461 };
462 
463 } // namespace crocoddyl
464 
465 /* --- Details -------------------------------------------------------------- */
466 /* --- Details -------------------------------------------------------------- */
467 /* --- Details -------------------------------------------------------------- */
468 #include <crocoddyl/multibody/actions/free-invdyn.hxx>
469 
470 #endif // CROCODDYL_MULTIBODY_ACTIONS_FREE_INVDYN_HPP_
Abstract class for the actuation-mapping model.
Residual-based constraint.
Definition: residual.hpp:47
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.
ResidualModelActuation(boost::shared_ptr< StateMultibody > state, const std::size_t nu)
Initialize the actuation residual model.
boost::shared_ptr< StateAbstract > state_
State description.
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.
virtual void calcDiff(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &)
Differential action model for free inverse dynamics in multibody systems.
Definition: free-invdyn.hpp:43
DifferentialActionModelFreeInvDynamicsTpl(boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActuationModelAbstract > actuation, boost::shared_ptr< CostModelSum > costs, boost::shared_ptr< ConstraintModelManager > constraints)
Initialize the free inverse-dynamics action model.
pinocchio::ModelTpl< Scalar > & get_pinocchio() const
Return the Pinocchio 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 free inverse-dynamics data.
virtual void print(std::ostream &os) const
Print relevant information of the free 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.
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.
DifferentialActionModelFreeInvDynamicsTpl(boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActuationModelAbstract > actuation, boost::shared_ptr< CostModelSum > costs)
Initialize the free inverse-dynamics action model.
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 free 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.
State multibody representation.
Definition: multibody.hpp:35
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.
DataCollectorAbstract * shared
Shared data allocated by the action model.
MatrixXs Fu
Jacobian of the dynamics w.r.t. the control .
VectorXs tmp_xstatic
State point used for computing the quasi-static input.
DataCollectorJointActMultibody multibody
Multibody data.
pinocchio::DataTpl< Scalar > pinocchio
Pinocchio data.
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.