Crocoddyl
centroidal-momentum.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2021-2024, LAAS-CNRS, University of Edinburgh,
5 // Heriot-Watt University
6 // Copyright note valid unless otherwise stated in individual files.
7 // All rights reserved.
9 
10 #ifndef CROCODDYL_MULTIBODY_RESIDUALS_MOMENTUM_HPP_
11 #define CROCODDYL_MULTIBODY_RESIDUALS_MOMENTUM_HPP_
12 
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"
17 
18 namespace crocoddyl {
19 
35 template <typename _Scalar>
37  : public ResidualModelAbstractTpl<_Scalar> {
38  public:
39  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
40 
41  typedef _Scalar Scalar;
49  typedef typename MathBase::Vector6s Vector6s;
50  typedef typename MathBase::VectorXs VectorXs;
51  typedef typename MathBase::Matrix6xs Matrix6xs;
52 
60  ResidualModelCentroidalMomentumTpl(boost::shared_ptr<StateMultibody> state,
61  const Vector6s& href,
62  const std::size_t nu);
63 
72  ResidualModelCentroidalMomentumTpl(boost::shared_ptr<StateMultibody> state,
73  const Vector6s& href);
75 
83  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
84  const Eigen::Ref<const VectorXs>& x,
85  const Eigen::Ref<const VectorXs>& u);
86 
94  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
95  const Eigen::Ref<const VectorXs>& x,
96  const Eigen::Ref<const VectorXs>& u);
97 
101  virtual boost::shared_ptr<ResidualDataAbstract> createData(
102  DataCollectorAbstract* const data);
103 
107  const Vector6s& get_reference() const;
108 
112  void set_reference(const Vector6s& href);
113 
119  virtual void print(std::ostream& os) const;
120 
121  protected:
122  using Base::nu_;
123  using Base::state_;
124  using Base::u_dependent_;
125 
126  private:
127  Vector6s href_;
128  boost::shared_ptr<typename StateMultibody::PinocchioModel>
129  pin_model_;
130 };
131 
132 template <typename _Scalar>
134  : public ResidualDataAbstractTpl<_Scalar> {
135  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
136 
137  typedef _Scalar Scalar;
141  typedef typename MathBase::Matrix6xs Matrix6xs;
142 
143  template <template <typename Scalar> class Model>
144  ResidualDataCentroidalMomentumTpl(Model<Scalar>* const model,
145  DataCollectorAbstract* const data)
146  : Base(model, data),
147  dhd_dq(6, model->get_state()->get_nv()),
148  dhd_dv(6, model->get_state()->get_nv()) {
149  dhd_dq.setZero();
150  dhd_dv.setZero();
151 
152  // Check that proper shared data has been passed
155  if (d == NULL) {
156  throw_pretty(
157  "Invalid argument: the shared data should be derived from "
158  "DataCollectorMultibody");
159  }
160 
161  // Avoids data casting at runtime
162  pinocchio = d->pinocchio;
163  }
164 
165  pinocchio::DataTpl<Scalar>* pinocchio;
166  Matrix6xs dhd_dq;
167  Matrix6xs dhd_dv;
168  using Base::r;
169  using Base::Ru;
170  using Base::Rx;
171  using Base::shared;
172 };
173 
174 } // namespace crocoddyl
175 
176 /* --- Details -------------------------------------------------------------- */
177 /* --- Details -------------------------------------------------------------- */
178 /* --- Details -------------------------------------------------------------- */
179 #include "crocoddyl/multibody/residuals/centroidal-momentum.hxx"
180 
181 #endif // CROCODDYL_MULTIBODY_RESIDUALS_MOMENTUM_HPP_
Abstract class for residual models.
boost::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
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.
Definition: multibody.hpp:35
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.
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.