10 #ifndef CROCODDYL_MULTIBODY_RESIDUALS_MOMENTUM_HPP_
11 #define CROCODDYL_MULTIBODY_RESIDUALS_MOMENTUM_HPP_
13 #include "crocoddyl/core/residual-base.hpp"
14 #include "crocoddyl/multibody/data/multibody.hpp"
15 #include "crocoddyl/multibody/fwd.hpp"
16 #include "crocoddyl/multibody/states/multibody.hpp"
35 template <
typename _Scalar>
39 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
41 typedef _Scalar Scalar;
49 typedef typename MathBase::Vector6s Vector6s;
50 typedef typename MathBase::VectorXs VectorXs;
51 typedef typename MathBase::Matrix6xs Matrix6xs;
62 const std::size_t nu);
73 const Vector6s& href);
83 virtual void calc(
const boost::shared_ptr<ResidualDataAbstract>& data,
84 const Eigen::Ref<const VectorXs>& x,
85 const Eigen::Ref<const VectorXs>& u);
94 virtual void calcDiff(
const boost::shared_ptr<ResidualDataAbstract>& data,
95 const Eigen::Ref<const VectorXs>& x,
96 const Eigen::Ref<const VectorXs>& u);
119 virtual void print(std::ostream& os)
const;
128 boost::shared_ptr<typename StateMultibody::PinocchioModel>
132 template <
typename _Scalar>
135 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
137 typedef _Scalar Scalar;
141 typedef typename MathBase::Matrix6xs Matrix6xs;
143 template <
template <
typename Scalar>
class Model>
147 dhd_dq(6, model->get_state()->get_nv()),
148 dhd_dv(6, model->get_state()->get_nv()) {
157 "Invalid argument: the shared data should be derived from "
158 "DataCollectorMultibody");
179 #include "crocoddyl/multibody/residuals/centroidal-momentum.hxx"
Abstract class for residual models.
boost::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
Centroidal momentum residual.
ResidualModelCentroidalMomentumTpl(boost::shared_ptr< StateMultibody > state, const Vector6s &href, const std::size_t nu)
Initialize the centroidal momentum residual model.
virtual void print(std::ostream &os) const
Print relevant information of the centroidal-momentum residual.
virtual void calc(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the centroidal momentum residual.
void set_reference(const Vector6s &href)
Modify the reference centroidal momentum.
ResidualModelCentroidalMomentumTpl(boost::shared_ptr< StateMultibody > state, const Vector6s &href)
Initialize the centroidal momentum residual model.
virtual void calcDiff(const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the derivatives of the centroidal momentum residual.
const Vector6s & get_reference() const
Return the reference centroidal momentum.
virtual boost::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the centroidal momentum residual data.
State multibody representation.
MatrixXs Ru
Jacobian of the residual vector with respect the control.
MatrixXs Rx
Jacobian of the residual vector with respect the state.
DataCollectorAbstract * shared
Shared data allocated by the action model.
VectorXs r
Residual vector.
Matrix6xs dhd_dq
Jacobian of the centroidal momentum.
DataCollectorAbstract * shared
Shared data allocated by the action model.
Matrix6xs dhd_dv
Jacobian of the centroidal momentum.
pinocchio::DataTpl< Scalar > * pinocchio
Pinocchio data.