Crocoddyl
impulse-fwddyn.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2019-2023, LAAS-CNRS, University of Edinburgh,
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_IMPULSE_FWDDYN_HPP_
11 #define CROCODDYL_MULTIBODY_ACTIONS_IMPULSE_FWDDYN_HPP_
12 
13 #include <pinocchio/algorithm/centroidal.hpp>
14 #include <pinocchio/algorithm/compute-all-terms.hpp>
15 #include <pinocchio/algorithm/contact-dynamics.hpp>
16 #include <pinocchio/algorithm/frames.hpp>
17 #include <pinocchio/algorithm/kinematics-derivatives.hpp>
18 #include <pinocchio/algorithm/rnea-derivatives.hpp>
19 #include <stdexcept>
20 
21 #include "crocoddyl/core/action-base.hpp"
22 #include "crocoddyl/core/constraints/constraint-manager.hpp"
23 #include "crocoddyl/core/costs/cost-sum.hpp"
24 #include "crocoddyl/core/utils/exception.hpp"
25 #include "crocoddyl/multibody/actions/impulse-fwddyn.hpp"
26 #include "crocoddyl/multibody/actuations/floating-base.hpp"
27 #include "crocoddyl/multibody/data/impulses.hpp"
28 #include "crocoddyl/multibody/fwd.hpp"
29 #include "crocoddyl/multibody/impulses/multiple-impulses.hpp"
30 #include "crocoddyl/multibody/states/multibody.hpp"
31 
32 namespace crocoddyl {
33 
67 template <typename _Scalar>
69  : public ActionModelAbstractTpl<_Scalar> {
70  public:
71  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
72 
73  typedef _Scalar Scalar;
82  typedef typename MathBase::VectorXs VectorXs;
83  typedef typename MathBase::MatrixXs MatrixXs;
84 
103  boost::shared_ptr<StateMultibody> state,
104  boost::shared_ptr<ImpulseModelMultiple> impulses,
105  boost::shared_ptr<CostModelSum> costs, const Scalar r_coeff = Scalar(0.),
106  const Scalar JMinvJt_damping = Scalar(0.),
107  const bool enable_force = false);
108 
128  boost::shared_ptr<StateMultibody> state,
129  boost::shared_ptr<ImpulseModelMultiple> impulses,
130  boost::shared_ptr<CostModelSum> costs,
131  boost::shared_ptr<ConstraintModelManager> constraints,
132  const Scalar r_coeff = Scalar(0.),
133  const Scalar JMinvJt_damping = Scalar(0.),
134  const bool enable_force = false);
136 
146  virtual void calc(const boost::shared_ptr<ActionDataAbstract>& data,
147  const Eigen::Ref<const VectorXs>& x,
148  const Eigen::Ref<const VectorXs>& u);
149 
162  virtual void calc(const boost::shared_ptr<ActionDataAbstract>& data,
163  const Eigen::Ref<const VectorXs>& x);
164 
172  virtual void calcDiff(const boost::shared_ptr<ActionDataAbstract>& data,
173  const Eigen::Ref<const VectorXs>& x,
174  const Eigen::Ref<const VectorXs>& u);
175 
187  virtual void calcDiff(const boost::shared_ptr<ActionDataAbstract>& data,
188  const Eigen::Ref<const VectorXs>& x);
189 
195  virtual boost::shared_ptr<ActionDataAbstract> createData();
196 
201  virtual bool checkData(const boost::shared_ptr<ActionDataAbstract>& data);
202 
206  virtual void quasiStatic(const boost::shared_ptr<ActionDataAbstract>& data,
207  Eigen::Ref<VectorXs> u,
208  const Eigen::Ref<const VectorXs>& x,
209  const std::size_t maxiter = 100,
210  const Scalar tol = Scalar(1e-9));
211 
215  virtual std::size_t get_ng() const;
216 
220  virtual std::size_t get_nh() const;
221 
225  virtual const VectorXs& get_g_lb() const;
226 
230  virtual const VectorXs& get_g_ub() const;
231 
235  const boost::shared_ptr<ImpulseModelMultiple>& get_impulses() const;
236 
240  const boost::shared_ptr<CostModelSum>& get_costs() const;
241 
245  const boost::shared_ptr<ConstraintModelManager>& get_constraints() const;
246 
250  pinocchio::ModelTpl<Scalar>& get_pinocchio() const;
251 
255  const VectorXs& get_armature() const;
256 
260  const Scalar get_restitution_coefficient() const;
261 
266  const Scalar get_damping_factor() const;
267 
271  void set_armature(const VectorXs& armature);
272 
276  void set_restitution_coefficient(const Scalar r_coeff);
277 
282  void set_damping_factor(const Scalar damping);
283 
289  virtual void print(std::ostream& os) const;
290 
291  protected:
292  using Base::g_lb_;
293  using Base::g_ub_;
294  using Base::state_;
295 
296  private:
297  void init();
298  void initCalc(Data* data, const Eigen::Ref<const VectorXs>& x);
299  void initCalcDiff(Data* data, const Eigen::Ref<const VectorXs>& x);
300  boost::shared_ptr<ImpulseModelMultiple> impulses_;
301  boost::shared_ptr<CostModelSum> costs_;
302  boost::shared_ptr<ConstraintModelManager> constraints_;
303  pinocchio::ModelTpl<Scalar>& pinocchio_;
304  bool with_armature_;
305  VectorXs armature_;
306  Scalar r_coeff_;
307  Scalar JMinvJt_damping_;
309  bool enable_force_;
311  pinocchio::MotionTpl<Scalar> gravity_;
312 };
313 
314 template <typename _Scalar>
316  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
317  typedef _Scalar Scalar;
320  typedef typename MathBase::VectorXs VectorXs;
321  typedef typename MathBase::MatrixXs MatrixXs;
322 
323  template <template <typename Scalar> class Model>
324  explicit ActionDataImpulseFwdDynamicsTpl(Model<Scalar>* const model)
325  : Base(model),
326  pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
327  multibody(&pinocchio, model->get_impulses()->createData(&pinocchio)),
328  costs(model->get_costs()->createData(&multibody)),
329  vnone(model->get_state()->get_nv()),
330  Kinv(model->get_state()->get_nv() +
331  model->get_impulses()->get_nc_total(),
332  model->get_state()->get_nv() +
333  model->get_impulses()->get_nc_total()),
334  df_dx(model->get_impulses()->get_nc_total(),
335  model->get_state()->get_ndx()),
336  dgrav_dq(model->get_state()->get_nv(), model->get_state()->get_nv()) {
337  costs->shareMemory(this);
338  if (model->get_constraints() != nullptr) {
339  constraints = model->get_constraints()->createData(&multibody);
340  constraints->shareMemory(this);
341  }
342  vnone.setZero();
343  Kinv.setZero();
344  df_dx.setZero();
345  dgrav_dq.setZero();
346  }
347 
348  pinocchio::DataTpl<Scalar> pinocchio;
350  boost::shared_ptr<CostDataSumTpl<Scalar> > costs;
351  boost::shared_ptr<ConstraintDataManagerTpl<Scalar> > constraints;
352  VectorXs vnone;
353  MatrixXs Kinv;
354  MatrixXs df_dx;
355  MatrixXs dgrav_dq;
356 };
357 
358 } // namespace crocoddyl
359 
360 /* --- Details -------------------------------------------------------------- */
361 /* --- Details -------------------------------------------------------------- */
362 /* --- Details -------------------------------------------------------------- */
363 #include <crocoddyl/multibody/actions/impulse-fwddyn.hxx>
364 
365 #endif // CROCODDYL_MULTIBODY_ACTIONS_IMPULSE_FWDDYN_HPP_
Abstract class for action model.
Definition: action-base.hpp:95
VectorXs g_ub_
Lower bound of the inequality constraints.
boost::shared_ptr< StateAbstract > state_
Model of the state.
VectorXs g_lb_
Lower bound of the inequality constraints.
Action model for impulse 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.
void set_restitution_coefficient(const Scalar r_coeff)
Modify the restituion coefficient.
const VectorXs & get_armature() const
Return the armature vector.
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 impulse forward-dynamics model.
ActionModelImpulseFwdDynamicsTpl(boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ImpulseModelMultiple > impulses, boost::shared_ptr< CostModelSum > costs, boost::shared_ptr< ConstraintModelManager > constraints, const Scalar r_coeff=Scalar(0.), const Scalar JMinvJt_damping=Scalar(0.), const bool enable_force=false)
Initialize the impulse forward-dynamics action 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.
void set_damping_factor(const Scalar damping)
Modify the damping factor used in the operational space inertia matrix.
virtual void calc(const boost::shared_ptr< ActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the system acceleration, and cost value.
const Scalar get_restitution_coefficient() const
Return the restituion coefficient.
virtual void calcDiff(const boost::shared_ptr< ActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the derivatives of the impulse dynamics, and cost function.
void set_armature(const VectorXs &armature)
Modify the armature vector.
virtual bool checkData(const boost::shared_ptr< ActionDataAbstract > &data)
Check that the given data belongs to the impulse forward-dynamics data.
const Scalar get_damping_factor() const
Return the damping factor used in the operational space inertia matrix.
const boost::shared_ptr< ConstraintModelManager > & get_constraints() const
Return the constraint model manager.
const boost::shared_ptr< ImpulseModelMultiple > & get_impulses() const
Return the impulse model.
virtual void calc(const boost::shared_ptr< ActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
Compute the total cost value for nodes that depends only on the state.
virtual const VectorXs & get_g_ub() const
Return the upper bound of the inequality constraints.
virtual void calcDiff(const boost::shared_ptr< ActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
Compute the derivatives of the cost functions with respect to the state only.
virtual boost::shared_ptr< ActionDataAbstract > createData()
Create the impulse forward-dynamics data.
ActionModelImpulseFwdDynamicsTpl(boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ImpulseModelMultiple > impulses, boost::shared_ptr< CostModelSum > costs, const Scalar r_coeff=Scalar(0.), const Scalar JMinvJt_damping=Scalar(0.), const bool enable_force=false)
Initialize the impulse forward-dynamics action model.
virtual void quasiStatic(const boost::shared_ptr< ActionDataAbstract > &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.
Define a stack of impulse models.
State multibody representation.
Definition: multibody.hpp:35