10 #ifndef CROCODDYL_MULTIBODY_ACTIONS_IMPULSE_FWDDYN_HPP_
11 #define CROCODDYL_MULTIBODY_ACTIONS_IMPULSE_FWDDYN_HPP_
13 #include "crocoddyl/core/action-base.hpp"
14 #include "crocoddyl/core/constraints/constraint-manager.hpp"
15 #include "crocoddyl/core/costs/cost-sum.hpp"
16 #include "crocoddyl/multibody/actions/impulse-fwddyn.hpp"
17 #include "crocoddyl/multibody/actuations/floating-base.hpp"
18 #include "crocoddyl/multibody/data/impulses.hpp"
19 #include "crocoddyl/multibody/fwd.hpp"
20 #include "crocoddyl/multibody/impulses/multiple-impulses.hpp"
21 #include "crocoddyl/multibody/states/multibody.hpp"
58 template <
typename _Scalar>
62 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
65 typedef _Scalar Scalar;
74 typedef typename MathBase::VectorXs VectorXs;
75 typedef typename MathBase::MatrixXs MatrixXs;
95 std::shared_ptr<StateMultibody> state,
96 std::shared_ptr<ImpulseModelMultiple> impulses,
97 std::shared_ptr<CostModelSum> costs,
const Scalar r_coeff = Scalar(0.),
98 const Scalar JMinvJt_damping = Scalar(0.),
99 const bool enable_force =
false);
120 std::shared_ptr<StateMultibody> state,
121 std::shared_ptr<ImpulseModelMultiple> impulses,
122 std::shared_ptr<CostModelSum> costs,
123 std::shared_ptr<ConstraintModelManager> constraints,
124 const Scalar r_coeff = Scalar(0.),
125 const Scalar JMinvJt_damping = Scalar(0.),
126 const bool enable_force =
false);
138 virtual void calc(
const std::shared_ptr<ActionDataAbstract>& data,
139 const Eigen::Ref<const VectorXs>& x,
140 const Eigen::Ref<const VectorXs>& u)
override;
154 virtual void calc(
const std::shared_ptr<ActionDataAbstract>& data,
155 const Eigen::Ref<const VectorXs>& x)
override;
164 virtual void calcDiff(
const std::shared_ptr<ActionDataAbstract>& data,
165 const Eigen::Ref<const VectorXs>& x,
166 const Eigen::Ref<const VectorXs>& u)
override;
179 virtual void calcDiff(
const std::shared_ptr<ActionDataAbstract>& data,
180 const Eigen::Ref<const VectorXs>& x)
override;
187 virtual std::shared_ptr<ActionDataAbstract>
createData()
override;
198 template <
typename NewScalar>
206 const std::shared_ptr<ActionDataAbstract>& data)
override;
211 virtual void quasiStatic(
const std::shared_ptr<ActionDataAbstract>& data,
212 Eigen::Ref<VectorXs> u,
213 const Eigen::Ref<const VectorXs>& x,
214 const std::size_t maxiter = 100,
215 const Scalar tol = Scalar(1e-9))
override;
220 virtual std::size_t
get_ng()
const override;
225 virtual std::size_t
get_nh()
const override;
304 virtual void print(std::ostream& os)
const override;
313 void initCalc(
Data* data,
const Eigen::Ref<const VectorXs>& x);
314 void initCalcDiff(
Data* data,
const Eigen::Ref<const VectorXs>& x);
315 std::shared_ptr<ImpulseModelMultiple> impulses_;
316 std::shared_ptr<CostModelSum> costs_;
317 std::shared_ptr<ConstraintModelManager> constraints_;
318 pinocchio::ModelTpl<Scalar>* pinocchio_;
322 Scalar JMinvJt_damping_;
326 pinocchio::MotionTpl<Scalar> gravity_;
329 template <
typename _Scalar>
331 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
332 typedef _Scalar Scalar;
335 typedef typename MathBase::VectorXs VectorXs;
336 typedef typename MathBase::MatrixXs MatrixXs;
338 template <
template <
typename Scalar>
class Model>
341 pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
342 multibody(&pinocchio, model->get_impulses()->createData(&pinocchio)),
343 costs(model->get_costs()->createData(&multibody)),
344 vnone(model->get_state()->get_nv()),
345 Kinv(model->get_state()->get_nv() +
346 model->get_impulses()->get_nc_total(),
347 model->get_state()->get_nv() +
348 model->get_impulses()->get_nc_total()),
349 df_dx(model->get_impulses()->get_nc_total(),
350 model->get_state()->get_ndx()),
351 dgrav_dq(model->get_state()->get_nv(), model->get_state()->get_nv()) {
352 costs->shareMemory(
this);
353 if (model->get_constraints() !=
nullptr) {
354 constraints = model->get_constraints()->createData(&multibody);
355 constraints->shareMemory(
this);
364 pinocchio::DataTpl<Scalar> pinocchio;
366 std::shared_ptr<CostDataSumTpl<Scalar> > costs;
367 std::shared_ptr<ConstraintDataManagerTpl<Scalar> > constraints;
379 #include <crocoddyl/multibody/actions/impulse-fwddyn.hxx>
381 CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(
383 CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT(
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.
pinocchio::ModelTpl< Scalar > & get_pinocchio() const
Return the Pinocchio model.
virtual void calc(const std::shared_ptr< ActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) override
Compute the system acceleration, and cost value.
virtual std::shared_ptr< ActionDataAbstract > createData() override
Create the impulse forward-dynamics data.
const std::shared_ptr< ImpulseModelMultiple > & get_impulses() const
Return the impulse model.
virtual void calcDiff(const std::shared_ptr< ActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x) override
Compute the derivatives of the cost functions with respect to the state only.
void set_restitution_coefficient(const Scalar r_coeff)
Modify the restituion coefficient.
virtual bool checkData(const std::shared_ptr< ActionDataAbstract > &data) override
Check that the given data belongs to the impulse forward-dynamics data.
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.
const VectorXs & get_armature() const
Return the armature vector.
virtual std::size_t get_ng() const override
Return the number of inequality constraints.
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)) override
Computes the quasic static commands.
virtual const VectorXs & get_g_ub() const override
Return the upper bound of the inequality constraints.
const std::shared_ptr< ConstraintModelManager > & get_constraints() const
Return the constraint model manager.
virtual std::size_t get_nh_T() const override
Return the number of equality terminal constraints.
virtual std::size_t get_nh() const override
Return the number of equality constraints.
void set_damping_factor(const Scalar damping)
Modify the damping factor used in the operational space inertia matrix.
virtual void calc(const std::shared_ptr< ActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x) override
Compute the total cost value for nodes that depends only on the state.
const Scalar get_restitution_coefficient() const
Return the restituion coefficient.
virtual std::size_t get_ng_T() const override
Return the number of equality terminal constraints.
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 calcDiff(const std::shared_ptr< ActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) override
Compute the derivatives of the impulse dynamics, and cost function.
ActionModelImpulseFwdDynamicsTpl< NewScalar > cast() const
Cast the impulse-fwddyn model to a different scalar type.
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.
const std::shared_ptr< CostModelSum > & get_costs() const
Return the cost model.
virtual void print(std::ostream &os) const override
Print relevant information of the impulse forward-dynamics model.
virtual const VectorXs & get_g_lb() const override
Return the lower bound of the inequality constraints.
Define a stack of impulse models.
State multibody representation.