9 #ifndef CROCODDYL_MULTIBODY_COSTS_MOMENTUM_HPP_ 10 #define CROCODDYL_MULTIBODY_COSTS_MOMENTUM_HPP_ 12 #include "crocoddyl/multibody/fwd.hpp" 13 #include "crocoddyl/multibody/cost-base.hpp" 14 #include "crocoddyl/multibody/data/multibody.hpp" 15 #include "crocoddyl/core/utils/exception.hpp" 19 template <
typename _Scalar>
22 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
24 typedef _Scalar Scalar;
33 typedef typename MathBase::Vector6s Vector6s;
34 typedef typename MathBase::VectorXs VectorXs;
35 typedef typename MathBase::MatrixXs MatrixXs;
36 typedef typename MathBase::Matrix6xs Matrix6xs;
39 boost::shared_ptr<ActivationModelAbstract> activation,
const Vector6s& mref,
40 const std::size_t& nu);
42 boost::shared_ptr<ActivationModelAbstract> activation,
const Vector6s& mref);
47 virtual void calc(
const boost::shared_ptr<CostDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x,
48 const Eigen::Ref<const VectorXs>& u);
49 virtual void calcDiff(
const boost::shared_ptr<CostDataAbstract>& data,
const Eigen::Ref<const VectorXs>& x,
50 const Eigen::Ref<const VectorXs>& u);
51 virtual boost::shared_ptr<CostDataAbstract> createData(DataCollectorAbstract*
const data);
53 virtual void set_referenceImpl(
const std::type_info& ti,
const void* pv);
54 virtual void get_referenceImpl(
const std::type_info& ti,
void* pv);
56 const Vector6s& get_href()
const;
57 void set_href(
const Vector6s& mref_in);
60 using Base::activation_;
69 template <
typename _Scalar>
71 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
73 typedef _Scalar Scalar;
77 typedef typename MathBase::VectorXs VectorXs;
78 typedef typename MathBase::MatrixXs MatrixXs;
79 typedef typename MathBase::Matrix6xs Matrix6xs;
80 typedef typename MathBase::Matrix6s Matrix6s;
81 typedef typename MathBase::Vector6s Vector6s;
83 template <
template <
typename Scalar>
class Model>
85 : Base(model, data), dhd_dq(6, model->get_state()->get_nv()), dhd_dv(6, model->get_state()->get_nv()) {
92 throw_pretty(
"Invalid argument: the shared data should be derived from DataCollectorMultibody");
96 pinocchio = d->pinocchio;
99 pinocchio::DataTpl<Scalar>* pinocchio;
103 using Base::activation;
121 #include "crocoddyl/multibody/costs/centroidal-momentum.hxx" 123 #endif // CROCODDYL_MULTIBODY_COSTS_MOMENTUM_HPP_