10 #ifndef CROCODDYL_MULTIBODY_ACTIONS_FREE_FWDDYN_HPP_
11 #define CROCODDYL_MULTIBODY_ACTIONS_FREE_FWDDYN_HPP_
13 #include "crocoddyl/core/actuation-base.hpp"
14 #include "crocoddyl/core/constraints/constraint-manager.hpp"
15 #include "crocoddyl/core/costs/cost-sum.hpp"
16 #include "crocoddyl/core/diff-action-base.hpp"
17 #include "crocoddyl/multibody/data/multibody.hpp"
18 #include "crocoddyl/multibody/fwd.hpp"
19 #include "crocoddyl/multibody/states/multibody.hpp"
50 template <
typename _Scalar>
54 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
58 typedef _Scalar Scalar;
68 typedef typename MathBase::VectorXs VectorXs;
69 typedef typename MathBase::MatrixXs MatrixXs;
72 std::shared_ptr<StateMultibody> state,
73 std::shared_ptr<ActuationModelAbstract> actuation,
74 std::shared_ptr<CostModelSum> costs,
75 std::shared_ptr<ConstraintModelManager> constraints =
nullptr);
87 virtual void calc(
const std::shared_ptr<DifferentialActionDataAbstract>& data,
88 const Eigen::Ref<const VectorXs>& x,
89 const Eigen::Ref<const VectorXs>& u)
override;
96 virtual void calc(
const std::shared_ptr<DifferentialActionDataAbstract>& data,
97 const Eigen::Ref<const VectorXs>& x)
override;
107 const std::shared_ptr<DifferentialActionDataAbstract>& data,
108 const Eigen::Ref<const VectorXs>& x,
109 const Eigen::Ref<const VectorXs>& u)
override;
117 const std::shared_ptr<DifferentialActionDataAbstract>& data,
118 const Eigen::Ref<const VectorXs>& x)
override;
125 virtual std::shared_ptr<DifferentialActionDataAbstract>
createData()
override;
136 template <
typename NewScalar>
143 const std::shared_ptr<DifferentialActionDataAbstract>& data)
override;
149 const std::shared_ptr<DifferentialActionDataAbstract>& data,
150 Eigen::Ref<VectorXs> u,
const Eigen::Ref<const VectorXs>& x,
151 const std::size_t maxiter = 100,
152 const Scalar tol = Scalar(1e-9))
override;
157 virtual std::size_t
get_ng()
const override;
162 virtual std::size_t
get_nh()
const override;
219 virtual void print(std::ostream& os)
const override;
228 std::shared_ptr<ActuationModelAbstract> actuation_;
229 std::shared_ptr<CostModelSum> costs_;
230 std::shared_ptr<ConstraintModelManager> constraints_;
231 pinocchio::ModelTpl<Scalar>* pinocchio_;
232 bool without_armature_;
236 template <
typename _Scalar>
239 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
240 typedef _Scalar Scalar;
246 typedef typename MathBase::VectorXs VectorXs;
247 typedef typename MathBase::MatrixXs MatrixXs;
249 template <
template <
typename Scalar>
class Model>
252 pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
254 &pinocchio, model->get_actuation()->createData(),
255 std::make_shared<JointDataAbstract>(
256 model->get_state(), model->get_actuation(), model->get_nu())),
257 costs(model->get_costs()->createData(&multibody)),
258 Minv(model->get_state()->get_nv(), model->get_state()->get_nv()),
259 u_drift(model->get_state()->get_nv()),
260 dtau_dx(model->get_state()->get_nv(), model->get_state()->get_ndx()),
261 tmp_xstatic(model->get_state()->get_nx()) {
262 multibody.joint->dtau_du.diagonal().setOnes();
263 costs->shareMemory(
this);
264 if (model->get_constraints() !=
nullptr) {
265 constraints = model->get_constraints()->createData(&multibody);
266 constraints->shareMemory(
this);
271 tmp_xstatic.setZero();
275 pinocchio::DataTpl<Scalar> pinocchio;
277 std::shared_ptr<CostDataSumTpl<Scalar> > costs;
278 std::shared_ptr<ConstraintDataManagerTpl<Scalar> > constraints;
282 VectorXs tmp_xstatic;
301 #include <crocoddyl/multibody/actions/free-fwddyn.hxx>
303 CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(
305 CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT(
Abstract class for the actuation-mapping model.
Abstract class for differential action model.
std::shared_ptr< StateAbstract > state_
Model of the state.
VectorXs g_ub_
Lower bound of the inequality constraints.
std::size_t nu_
Control dimension.
VectorXs g_lb_
Lower bound of the inequality constraints.
Differential action model for free forward dynamics in multibody systems.
virtual bool checkData(const std::shared_ptr< DifferentialActionDataAbstract > &data) override
Check that the given data belongs to the free forward-dynamics data.
pinocchio::ModelTpl< Scalar > & get_pinocchio() const
Return the Pinocchio model.
virtual void calcDiff(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x) override
virtual void calc(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) override
Compute the system acceleration, and cost value.
const std::shared_ptr< ActuationModelAbstract > & get_actuation() const
Return the actuation model.
const VectorXs & get_armature() const
Return the armature vector.
DifferentialActionModelFreeFwdDynamicsTpl< NewScalar > cast() const
Cast the free-fwddyn model to a different scalar type.
virtual std::shared_ptr< DifferentialActionDataAbstract > createData() override
Create the free forward-dynamics data.
virtual std::size_t get_ng() const override
Return the number of inequality constraints.
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.
virtual std::size_t get_ng_T() const override
Return the number of equality terminal constraints.
virtual void calc(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x) override
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)) override
Computes the quasic static commands.
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 free forward-dynamics model.
virtual void calcDiff(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) override
Compute the derivatives of the contact dynamics, and cost function.
virtual const VectorXs & get_g_lb() const override
Return the lower bound of the inequality constraints.
State multibody representation.
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 .
VectorXs xout
evolution state