Crocoddyl
 
Loading...
Searching...
No Matches
impulse-fwddyn.hpp
1
2// BSD 3-Clause License
3//
4// Copyright (C) 2019-2024, 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
32namespace crocoddyl {
33
67template <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 std::shared_ptr<StateMultibody> state,
104 std::shared_ptr<ImpulseModelMultiple> impulses,
105 std::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 std::shared_ptr<StateMultibody> state,
129 std::shared_ptr<ImpulseModelMultiple> impulses,
130 std::shared_ptr<CostModelSum> costs,
131 std::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 std::shared_ptr<ActionDataAbstract>& data,
147 const Eigen::Ref<const VectorXs>& x,
148 const Eigen::Ref<const VectorXs>& u);
149
162 virtual void calc(const std::shared_ptr<ActionDataAbstract>& data,
163 const Eigen::Ref<const VectorXs>& x);
164
172 virtual void calcDiff(const std::shared_ptr<ActionDataAbstract>& data,
173 const Eigen::Ref<const VectorXs>& x,
174 const Eigen::Ref<const VectorXs>& u);
175
187 virtual void calcDiff(const std::shared_ptr<ActionDataAbstract>& data,
188 const Eigen::Ref<const VectorXs>& x);
189
195 virtual std::shared_ptr<ActionDataAbstract> createData();
196
201 virtual bool checkData(const std::shared_ptr<ActionDataAbstract>& data);
202
206 virtual void quasiStatic(const std::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 std::size_t get_ng_T() const;
226
230 virtual std::size_t get_nh_T() const;
231
235 virtual const VectorXs& get_g_lb() const;
236
240 virtual const VectorXs& get_g_ub() const;
241
245 const std::shared_ptr<ImpulseModelMultiple>& get_impulses() const;
246
250 const std::shared_ptr<CostModelSum>& get_costs() const;
251
255 const std::shared_ptr<ConstraintModelManager>& get_constraints() const;
256
260 pinocchio::ModelTpl<Scalar>& get_pinocchio() const;
261
265 const VectorXs& get_armature() const;
266
270 const Scalar get_restitution_coefficient() const;
271
276 const Scalar get_damping_factor() const;
277
281 void set_armature(const VectorXs& armature);
282
286 void set_restitution_coefficient(const Scalar r_coeff);
287
292 void set_damping_factor(const Scalar damping);
293
299 virtual void print(std::ostream& os) const;
300
301 protected:
302 using Base::g_lb_;
303 using Base::g_ub_;
304 using Base::state_;
305
306 private:
307 void init();
308 void initCalc(Data* data, const Eigen::Ref<const VectorXs>& x);
309 void initCalcDiff(Data* data, const Eigen::Ref<const VectorXs>& x);
310 std::shared_ptr<ImpulseModelMultiple> impulses_;
311 std::shared_ptr<CostModelSum> costs_;
312 std::shared_ptr<ConstraintModelManager> constraints_;
313 pinocchio::ModelTpl<Scalar>& pinocchio_;
314 bool with_armature_;
315 VectorXs armature_;
316 Scalar r_coeff_;
317 Scalar JMinvJt_damping_;
319 bool enable_force_;
321 pinocchio::MotionTpl<Scalar> gravity_;
322};
323
324template <typename _Scalar>
326 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
327 typedef _Scalar Scalar;
330 typedef typename MathBase::VectorXs VectorXs;
331 typedef typename MathBase::MatrixXs MatrixXs;
332
333 template <template <typename Scalar> class Model>
334 explicit ActionDataImpulseFwdDynamicsTpl(Model<Scalar>* const model)
335 : Base(model),
336 pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
337 multibody(&pinocchio, model->get_impulses()->createData(&pinocchio)),
338 costs(model->get_costs()->createData(&multibody)),
339 vnone(model->get_state()->get_nv()),
340 Kinv(model->get_state()->get_nv() +
341 model->get_impulses()->get_nc_total(),
342 model->get_state()->get_nv() +
343 model->get_impulses()->get_nc_total()),
344 df_dx(model->get_impulses()->get_nc_total(),
345 model->get_state()->get_ndx()),
346 dgrav_dq(model->get_state()->get_nv(), model->get_state()->get_nv()) {
347 costs->shareMemory(this);
348 if (model->get_constraints() != nullptr) {
349 constraints = model->get_constraints()->createData(&multibody);
350 constraints->shareMemory(this);
351 }
352 vnone.setZero();
353 Kinv.setZero();
354 df_dx.setZero();
355 dgrav_dq.setZero();
356 }
357
358 pinocchio::DataTpl<Scalar> pinocchio;
360 std::shared_ptr<CostDataSumTpl<Scalar> > costs;
361 std::shared_ptr<ConstraintDataManagerTpl<Scalar> > constraints;
362 VectorXs vnone;
363 MatrixXs Kinv;
364 MatrixXs df_dx;
365 MatrixXs dgrav_dq;
366};
367
368} // namespace crocoddyl
369
370/* --- Details -------------------------------------------------------------- */
371/* --- Details -------------------------------------------------------------- */
372/* --- Details -------------------------------------------------------------- */
373#include <crocoddyl/multibody/actions/impulse-fwddyn.hxx>
374
375#endif // CROCODDYL_MULTIBODY_ACTIONS_IMPULSE_FWDDYN_HPP_
Abstract class for 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.
Action model for impulse forward dynamics in multibody systems.
const std::shared_ptr< ImpulseModelMultiple > & get_impulses() const
Return the impulse model.
const std::shared_ptr< ConstraintModelManager > & get_constraints() const
Return the constraint model manager.
virtual std::size_t get_ng() const
Return the number of inequality constraints.
virtual void calc(const std::shared_ptr< ActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the system acceleration, and cost value.
void set_restitution_coefficient(const Scalar r_coeff)
Modify the restituion coefficient.
virtual const VectorXs & get_g_lb() const
Return the lower bound of the inequality constraints.
ActionModelImpulseFwdDynamicsTpl(std::shared_ptr< StateMultibody > state, std::shared_ptr< ImpulseModelMultiple > impulses, std::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 calcDiff(const std::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.
virtual std::size_t get_nh() const
Return the number of equality constraints.
virtual void calcDiff(const std::shared_ptr< ActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
Compute the derivatives of the cost functions with respect to the state only.
virtual void print(std::ostream &os) const
Print relevant information of the impulse forward-dynamics model.
virtual const VectorXs & get_g_ub() const
Return the upper bound of the inequality constraints.
const VectorXs & get_armature() const
Return the armature vector.
void set_damping_factor(const Scalar damping)
Modify the damping factor used in the operational space inertia matrix.
const std::shared_ptr< CostModelSum > & get_costs() const
Return the cost model.
virtual std::shared_ptr< ActionDataAbstract > createData()
Create the impulse forward-dynamics data.
virtual std::size_t get_nh_T() const
Return the number of equality terminal constraints.
const Scalar get_restitution_coefficient() const
Return the restituion coefficient.
void set_armature(const VectorXs &armature)
Modify the armature vector.
const Scalar get_damping_factor() const
Return the damping factor used in the operational space inertia matrix.
virtual void quasiStatic(const std::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.
ActionModelImpulseFwdDynamicsTpl(std::shared_ptr< StateMultibody > state, std::shared_ptr< ImpulseModelMultiple > impulses, std::shared_ptr< CostModelSum > costs, std::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 std::size_t get_ng_T() const
Return the number of equality terminal constraints.
virtual void calc(const std::shared_ptr< ActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
Compute the total cost value for nodes that depends only on the state.
pinocchio::ModelTpl< Scalar > & get_pinocchio() const
Return the Pinocchio model.
virtual bool checkData(const std::shared_ptr< ActionDataAbstract > &data)
Check that the given data belongs to the impulse forward-dynamics data.
Manage the individual constraint models.
Summation of individual cost models.
Definition cost-sum.hpp:73
Define a stack of impulse models.
State multibody representation.
Definition multibody.hpp:35