Crocoddyl
centroidal-momentum.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2021-2025, 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
41 
42  typedef _Scalar Scalar;
50  typedef typename MathBase::Vector6s Vector6s;
51  typedef typename MathBase::VectorXs VectorXs;
52  typedef typename MathBase::Matrix6xs Matrix6xs;
53 
61  ResidualModelCentroidalMomentumTpl(std::shared_ptr<StateMultibody> state,
62  const Vector6s& href,
63  const std::size_t nu);
64 
73  ResidualModelCentroidalMomentumTpl(std::shared_ptr<StateMultibody> state,
74  const Vector6s& href);
75  virtual ~ResidualModelCentroidalMomentumTpl() = default;
76 
84  virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
85  const Eigen::Ref<const VectorXs>& x,
86  const Eigen::Ref<const VectorXs>& u) override;
87 
95  virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
96  const Eigen::Ref<const VectorXs>& x,
97  const Eigen::Ref<const VectorXs>& u) override;
98 
102  virtual std::shared_ptr<ResidualDataAbstract> createData(
103  DataCollectorAbstract* const data) override;
104 
115  template <typename NewScalar>
117 
121  const Vector6s& get_reference() const;
122 
126  void set_reference(const Vector6s& href);
127 
133  virtual void print(std::ostream& os) const override;
134 
135  protected:
136  using Base::nu_;
137  using Base::state_;
138  using Base::u_dependent_;
139 
140  private:
141  Vector6s href_;
142  std::shared_ptr<typename StateMultibody::PinocchioModel>
143  pin_model_;
144 };
145 
146 template <typename _Scalar>
148  : public ResidualDataAbstractTpl<_Scalar> {
149  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
150 
151  typedef _Scalar Scalar;
155  typedef typename MathBase::Matrix6xs Matrix6xs;
156 
157  template <template <typename Scalar> class Model>
158  ResidualDataCentroidalMomentumTpl(Model<Scalar>* const model,
159  DataCollectorAbstract* const data)
160  : Base(model, data),
161  dhd_dq(6, model->get_state()->get_nv()),
162  dhd_dv(6, model->get_state()->get_nv()) {
163  dhd_dq.setZero();
164  dhd_dv.setZero();
165 
166  // Check that proper shared data has been passed
169  if (d == NULL) {
170  throw_pretty(
171  "Invalid argument: the shared data should be derived from "
172  "DataCollectorMultibody");
173  }
174 
175  // Avoids data casting at runtime
176  pinocchio = d->pinocchio;
177  }
178  virtual ~ResidualDataCentroidalMomentumTpl() = default;
179 
180  pinocchio::DataTpl<Scalar>* pinocchio;
181  Matrix6xs dhd_dq;
182  Matrix6xs dhd_dv;
183  using Base::r;
184  using Base::Ru;
185  using Base::Rx;
186  using Base::shared;
187 };
188 
189 } // namespace crocoddyl
190 
191 /* --- Details -------------------------------------------------------------- */
192 /* --- Details -------------------------------------------------------------- */
193 /* --- Details -------------------------------------------------------------- */
194 #include "crocoddyl/multibody/residuals/centroidal-momentum.hxx"
195 
196 CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(
198 CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT(
200 
201 #endif // CROCODDYL_MULTIBODY_RESIDUALS_MOMENTUM_HPP_
Abstract class for residual models.
std::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
ResidualModelCentroidalMomentumTpl< NewScalar > cast() const
Cast the centroidal-momentum residual model to a different scalar type.
ResidualModelCentroidalMomentumTpl(std::shared_ptr< StateMultibody > state, const Vector6s &href, const std::size_t nu)
Initialize the centroidal momentum residual model.
virtual void calcDiff(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) override
Compute the derivatives of the centroidal momentum residual.
void set_reference(const Vector6s &href)
Modify the reference centroidal momentum.
ResidualModelCentroidalMomentumTpl(std::shared_ptr< StateMultibody > state, const Vector6s &href)
Initialize the centroidal momentum residual model.
const Vector6s & get_reference() const
Return the reference centroidal momentum.
virtual void calc(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) override
Compute the centroidal momentum residual.
virtual void print(std::ostream &os) const override
Print relevant information of the centroidal-momentum residual.
virtual std::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data) override
Create the centroidal momentum residual data.
State multibody representation.
Definition: multibody.hpp:34
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.