Crocoddyl
contact-fwddyn.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2019-2024, LAAS-CNRS, University of Edinburgh, CTU, INRIA,
5 // University of Oxford, Heriot-Watt University
6 // Copyright note valid unless otherwise stated in individual files.
7 // All rights reserved.
9 
10 #ifndef CROCODDYL_MULTIBODY_ACTIONS_CONTACT_FWDDYN_HPP_
11 #define CROCODDYL_MULTIBODY_ACTIONS_CONTACT_FWDDYN_HPP_
12 
13 #include <stdexcept>
14 
15 #include "crocoddyl/core/actuation-base.hpp"
16 #include "crocoddyl/core/constraints/constraint-manager.hpp"
17 #include "crocoddyl/core/costs/cost-sum.hpp"
18 #include "crocoddyl/core/diff-action-base.hpp"
19 #include "crocoddyl/multibody/contacts/multiple-contacts.hpp"
20 #include "crocoddyl/multibody/data/contacts.hpp"
21 #include "crocoddyl/multibody/fwd.hpp"
22 #include "crocoddyl/multibody/states/multibody.hpp"
23 
24 namespace crocoddyl {
25 
73 template <typename _Scalar>
75  : public DifferentialActionModelAbstractTpl<_Scalar> {
76  public:
77  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
78 
79  typedef _Scalar Scalar;
90  typedef typename MathBase::VectorXs VectorXs;
91  typedef typename MathBase::MatrixXs MatrixXs;
92 
110  std::shared_ptr<StateMultibody> state,
111  std::shared_ptr<ActuationModelAbstract> actuation,
112  std::shared_ptr<ContactModelMultiple> contacts,
113  std::shared_ptr<CostModelSum> costs,
114  const Scalar JMinvJt_damping = Scalar(0.),
115  const bool enable_force = false);
116 
135  std::shared_ptr<StateMultibody> state,
136  std::shared_ptr<ActuationModelAbstract> actuation,
137  std::shared_ptr<ContactModelMultiple> contacts,
138  std::shared_ptr<CostModelSum> costs,
139  std::shared_ptr<ConstraintModelManager> constraints,
140  const Scalar JMinvJt_damping = Scalar(0.),
141  const bool enable_force = false);
143 
153  virtual void calc(const std::shared_ptr<DifferentialActionDataAbstract>& data,
154  const Eigen::Ref<const VectorXs>& x,
155  const Eigen::Ref<const VectorXs>& u);
156 
169  virtual void calc(const std::shared_ptr<DifferentialActionDataAbstract>& data,
170  const Eigen::Ref<const VectorXs>& x);
171 
179  virtual void calcDiff(
180  const std::shared_ptr<DifferentialActionDataAbstract>& data,
181  const Eigen::Ref<const VectorXs>& x, const Eigen::Ref<const VectorXs>& u);
182 
194  virtual void calcDiff(
195  const std::shared_ptr<DifferentialActionDataAbstract>& data,
196  const Eigen::Ref<const VectorXs>& x);
197 
203  virtual std::shared_ptr<DifferentialActionDataAbstract> createData();
204 
209  virtual bool checkData(
210  const std::shared_ptr<DifferentialActionDataAbstract>& data);
211 
215  virtual void quasiStatic(
216  const std::shared_ptr<DifferentialActionDataAbstract>& data,
217  Eigen::Ref<VectorXs> u, const Eigen::Ref<const VectorXs>& x,
218  const std::size_t maxiter = 100, const Scalar tol = Scalar(1e-9));
219 
223  virtual std::size_t get_ng() const;
224 
228  virtual std::size_t get_nh() const;
229 
233  virtual std::size_t get_ng_T() const;
234 
238  virtual std::size_t get_nh_T() const;
239 
243  virtual const VectorXs& get_g_lb() const;
244 
248  virtual const VectorXs& get_g_ub() const;
249 
253  const std::shared_ptr<ActuationModelAbstract>& get_actuation() const;
254 
258  const std::shared_ptr<ContactModelMultiple>& get_contacts() const;
259 
263  const std::shared_ptr<CostModelSum>& get_costs() const;
264 
268  const std::shared_ptr<ConstraintModelManager>& get_constraints() const;
269 
273  pinocchio::ModelTpl<Scalar>& get_pinocchio() const;
274 
278  const VectorXs& get_armature() const;
279 
283  const Scalar get_damping_factor() const;
284 
288  void set_armature(const VectorXs& armature);
289 
293  void set_damping_factor(const Scalar damping);
294 
300  virtual void print(std::ostream& os) const;
301 
302  protected:
303  using Base::g_lb_;
304  using Base::g_ub_;
305  using Base::nu_;
306  using Base::state_;
307 
308  private:
309  void init();
310  std::shared_ptr<ActuationModelAbstract> actuation_;
311  std::shared_ptr<ContactModelMultiple> contacts_;
312  std::shared_ptr<CostModelSum> costs_;
313  std::shared_ptr<ConstraintModelManager> constraints_;
314  pinocchio::ModelTpl<Scalar>& pinocchio_;
315  bool with_armature_;
316  VectorXs armature_;
317  Scalar JMinvJt_damping_;
319  bool enable_force_;
321 };
322 
323 template <typename _Scalar>
325  : public DifferentialActionDataAbstractTpl<_Scalar> {
326  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
327  typedef _Scalar Scalar;
333  typedef typename MathBase::VectorXs VectorXs;
334  typedef typename MathBase::MatrixXs MatrixXs;
335 
336  template <template <typename Scalar> class Model>
338  Model<Scalar>* const model)
339  : Base(model),
340  pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
341  multibody(
342  &pinocchio, model->get_actuation()->createData(),
343  std::make_shared<JointDataAbstract>(
344  model->get_state(), model->get_actuation(), model->get_nu()),
345  model->get_contacts()->createData(&pinocchio)),
346  costs(model->get_costs()->createData(&multibody)),
347  Kinv(model->get_state()->get_nv() +
348  model->get_contacts()->get_nc_total(),
349  model->get_state()->get_nv() +
350  model->get_contacts()->get_nc_total()),
351  df_dx(model->get_contacts()->get_nc_total(),
352  model->get_state()->get_ndx()),
353  df_du(model->get_contacts()->get_nc_total(), model->get_nu()),
354  tmp_xstatic(model->get_state()->get_nx()),
355  tmp_Jstatic(model->get_state()->get_nv(),
356  model->get_nu() + model->get_contacts()->get_nc_total()) {
357  multibody.joint->dtau_du.diagonal().setOnes();
358  costs->shareMemory(this);
359  if (model->get_constraints() != nullptr) {
360  constraints = model->get_constraints()->createData(&multibody);
361  constraints->shareMemory(this);
362  }
363  Kinv.setZero();
364  df_dx.setZero();
365  df_du.setZero();
366  tmp_xstatic.setZero();
367  tmp_Jstatic.setZero();
368  pinocchio.lambda_c.resize(model->get_contacts()->get_nc_total());
369  pinocchio.lambda_c.setZero();
370  }
371 
372  pinocchio::DataTpl<Scalar> pinocchio;
374  std::shared_ptr<CostDataSumTpl<Scalar> > costs;
375  std::shared_ptr<ConstraintDataManagerTpl<Scalar> > constraints;
376  MatrixXs Kinv;
377  MatrixXs df_dx;
378  MatrixXs df_du;
379  VectorXs tmp_xstatic;
380  MatrixXs tmp_Jstatic;
381 
382  using Base::cost;
383  using Base::Fu;
384  using Base::Fx;
385  using Base::Lu;
386  using Base::Luu;
387  using Base::Lx;
388  using Base::Lxu;
389  using Base::Lxx;
390  using Base::r;
391  using Base::xout;
392 };
393 
394 } // namespace crocoddyl
395 
396 /* --- Details -------------------------------------------------------------- */
397 /* --- Details -------------------------------------------------------------- */
398 /* --- Details -------------------------------------------------------------- */
399 #include <crocoddyl/multibody/actions/contact-fwddyn.hxx>
400 
401 #endif // CROCODDYL_MULTIBODY_ACTIONS_CONTACT_FWDDYN_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.
VectorXs g_lb_
Lower bound of the inequality constraints.
Differential action model for contact forward dynamics in multibody systems.
pinocchio::ModelTpl< Scalar > & get_pinocchio() const
Return the Pinocchio model.
virtual std::size_t get_ng() const
Return the number of inequality constraints.
DifferentialActionModelContactFwdDynamicsTpl(std::shared_ptr< StateMultibody > state, std::shared_ptr< ActuationModelAbstract > actuation, std::shared_ptr< ContactModelMultiple > contacts, std::shared_ptr< CostModelSum > costs, const Scalar JMinvJt_damping=Scalar(0.), const bool enable_force=false)
Initialize the contact forward-dynamics action model.
const std::shared_ptr< ActuationModelAbstract > & get_actuation() const
Return the actuation model.
const VectorXs & get_armature() const
Return the armature vector.
virtual std::shared_ptr< DifferentialActionDataAbstract > createData()
Create the contact forward-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 forward-dynamics 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 contact dynamics, and cost function.
virtual const VectorXs & get_g_lb() const
Return the lower bound of the inequality constraints.
void set_damping_factor(const Scalar damping)
Modify the damping factor used in operational space inertia matrix.
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, and cost value.
virtual std::size_t get_nh_T() const
Return the number of equality terminal constraints.
virtual bool checkData(const std::shared_ptr< DifferentialActionDataAbstract > &data)
Check that the given data belongs to the contact forward-dynamics data.
void set_armature(const VectorXs &armature)
Modify the armature vector.
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.
const Scalar get_damping_factor() const
Return the damping factor used in operational space inertia matrix.
virtual void calcDiff(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
Compute the derivatives of the cost functions with respect to the state only.
const std::shared_ptr< CostModelSum > & get_costs() const
Return the cost model.
DifferentialActionModelContactFwdDynamicsTpl(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, const Scalar JMinvJt_damping=Scalar(0.), const bool enable_force=false)
Initialize the contact forward-dynamics action 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)
Compute the total cost value for nodes that depends only on the state.
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 .