10 #ifndef CROCODDYL_MULTIBODY_ACTIONS_CONTACT_FWDDYN_HPP_
11 #define CROCODDYL_MULTIBODY_ACTIONS_CONTACT_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/contacts/multiple-contacts.hpp"
18 #include "crocoddyl/multibody/data/contacts.hpp"
19 #include "crocoddyl/multibody/fwd.hpp"
20 #include "crocoddyl/multibody/states/multibody.hpp"
71 template <
typename _Scalar>
75 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
79 typedef _Scalar Scalar;
90 typedef typename MathBase::VectorXs VectorXs;
91 typedef typename MathBase::MatrixXs MatrixXs;
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);
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);
153 virtual void calc(
const std::shared_ptr<DifferentialActionDataAbstract>& data,
154 const Eigen::Ref<const VectorXs>& x,
155 const Eigen::Ref<const VectorXs>& u)
override;
169 virtual void calc(
const std::shared_ptr<DifferentialActionDataAbstract>& data,
170 const Eigen::Ref<const VectorXs>& x)
override;
180 const std::shared_ptr<DifferentialActionDataAbstract>& data,
181 const Eigen::Ref<const VectorXs>& x,
182 const Eigen::Ref<const VectorXs>& u)
override;
196 const std::shared_ptr<DifferentialActionDataAbstract>& data,
197 const Eigen::Ref<const VectorXs>& x)
override;
204 virtual std::shared_ptr<DifferentialActionDataAbstract>
createData()
override;
215 template <
typename NewScalar>
223 const std::shared_ptr<DifferentialActionDataAbstract>& data)
override;
229 const std::shared_ptr<DifferentialActionDataAbstract>& data,
230 Eigen::Ref<VectorXs> u,
const Eigen::Ref<const VectorXs>& x,
231 const std::size_t maxiter = 100,
232 const Scalar tol = Scalar(1e-9))
override;
237 virtual std::size_t
get_ng()
const override;
242 virtual std::size_t
get_nh()
const override;
314 virtual void print(std::ostream& os)
const override;
324 std::shared_ptr<ActuationModelAbstract> actuation_;
325 std::shared_ptr<ContactModelMultiple> contacts_;
326 std::shared_ptr<CostModelSum> costs_;
327 std::shared_ptr<ConstraintModelManager> constraints_;
328 pinocchio::ModelTpl<Scalar>* pinocchio_;
331 Scalar JMinvJt_damping_;
337 template <
typename _Scalar>
340 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
341 typedef _Scalar Scalar;
347 typedef typename MathBase::VectorXs VectorXs;
348 typedef typename MathBase::MatrixXs MatrixXs;
350 template <
template <
typename Scalar>
class Model>
352 Model<Scalar>*
const model)
354 pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
356 &pinocchio, model->get_actuation()->createData(),
357 std::make_shared<JointDataAbstract>(
358 model->get_state(), model->get_actuation(), model->get_nu()),
359 model->get_contacts()->createData(&pinocchio)),
360 costs(model->get_costs()->createData(&multibody)),
361 Kinv(model->get_state()->get_nv() +
362 model->get_contacts()->get_nc_total(),
363 model->get_state()->get_nv() +
364 model->get_contacts()->get_nc_total()),
365 df_dx(model->get_contacts()->get_nc_total(),
366 model->get_state()->get_ndx()),
367 df_du(model->get_contacts()->get_nc_total(), model->get_nu()),
368 tmp_xstatic(model->get_state()->get_nx()),
369 tmp_Jstatic(model->get_state()->get_nv(),
370 model->get_nu() + model->get_contacts()->get_nc_total()) {
371 multibody.joint->dtau_du.diagonal().setOnes();
372 costs->shareMemory(
this);
373 if (model->get_constraints() !=
nullptr) {
374 constraints = model->get_constraints()->createData(&multibody);
375 constraints->shareMemory(
this);
380 tmp_xstatic.setZero();
381 tmp_Jstatic.setZero();
382 pinocchio.lambda_c.resize(model->get_contacts()->get_nc_total());
383 pinocchio.lambda_c.setZero();
387 pinocchio::DataTpl<Scalar> pinocchio;
389 std::shared_ptr<CostDataSumTpl<Scalar> > costs;
390 std::shared_ptr<ConstraintDataManagerTpl<Scalar> > constraints;
394 VectorXs tmp_xstatic;
395 MatrixXs tmp_Jstatic;
414 #include <crocoddyl/multibody/actions/contact-fwddyn.hxx>
416 CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(
418 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.
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