GCC Code Coverage Report


Directory: ./
File: include/crocoddyl/multibody/residuals/centroidal-momentum.hpp
Date: 2025-01-16 08:47:40
Exec Total Coverage
Lines: 10 11 90.9%
Branches: 6 20 30.0%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // 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.
8 ///////////////////////////////////////////////////////////////////////////////
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
20 /**
21 * @brief Centroidal momentum residual
22 *
23 * This residual function defines the centroidal momentum tracking as
24 * \f$\mathbf{r}=\mathbf{h}-\mathbf{h}^*\f$, where
25 * \f$\mathbf{h},\mathbf{h}^*\in~\mathcal{X}\f$ are the current and reference
26 * centroidal momenta, respectively. Note that the dimension of the residual
27 * vector is 6. Furthermore, the Jacobians of the residual function are computed
28 * analytically.
29 *
30 * As described in `ResidualModelAbstractTpl()`, the residual value and its
31 * Jacobians are calculated by `calc` and `calcDiff`, respectively.
32 *
33 * \sa `ResidualModelAbstractTpl`, `calc()`, `calcDiff()`, `createData()`
34 */
35 template <typename _Scalar>
36 class ResidualModelCentroidalMomentumTpl
37 : public ResidualModelAbstractTpl<_Scalar> {
38 public:
39 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
40
41 typedef _Scalar Scalar;
42 typedef MathBaseTpl<Scalar> MathBase;
43 typedef ResidualModelAbstractTpl<Scalar> Base;
44 typedef ResidualDataCentroidalMomentumTpl<Scalar> Data;
45 typedef StateMultibodyTpl<Scalar> StateMultibody;
46 typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
47 typedef ActivationModelAbstractTpl<Scalar> ActivationModelAbstract;
48 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
49 typedef typename MathBase::Vector6s Vector6s;
50 typedef typename MathBase::VectorXs VectorXs;
51 typedef typename MathBase::Matrix6xs Matrix6xs;
52
53 /**
54 * @brief Initialize the centroidal momentum residual model
55 *
56 * @param[in] state State of the multibody system
57 * @param[in] href Reference centroidal momentum
58 * @param[in] nu Dimension of the control vector
59 */
60 ResidualModelCentroidalMomentumTpl(boost::shared_ptr<StateMultibody> state,
61 const Vector6s& href,
62 const std::size_t nu);
63
64 /**
65 * @brief Initialize the centroidal momentum residual model
66 *
67 * The default `nu` is obtained from `StateAbstractTpl::get_nv()`.
68 *
69 * @param[in] state State of the multibody system
70 * @param[in] href Reference centroidal momentum
71 */
72 ResidualModelCentroidalMomentumTpl(boost::shared_ptr<StateMultibody> state,
73 const Vector6s& href);
74 virtual ~ResidualModelCentroidalMomentumTpl();
75
76 /**
77 * @brief Compute the centroidal momentum residual
78 *
79 * @param[in] data Centroidal momentum residual data
80 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
81 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
82 */
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
87 /**
88 * @brief Compute the derivatives of the centroidal momentum residual
89 *
90 * @param[in] data Centroidal momentum residual data
91 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
92 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
93 */
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
98 /**
99 * @brief Create the centroidal momentum residual data
100 */
101 virtual boost::shared_ptr<ResidualDataAbstract> createData(
102 DataCollectorAbstract* const data);
103
104 /**
105 * @brief Return the reference centroidal momentum
106 */
107 const Vector6s& get_reference() const;
108
109 /**
110 * @brief Modify the reference centroidal momentum
111 */
112 void set_reference(const Vector6s& href);
113
114 /**
115 * @brief Print relevant information of the centroidal-momentum residual
116 *
117 * @param[out] os Output stream object
118 */
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_; //!< Reference centroidal momentum
128 boost::shared_ptr<typename StateMultibody::PinocchioModel>
129 pin_model_; //!< Pinocchio model
130 };
131
132 template <typename _Scalar>
133 struct ResidualDataCentroidalMomentumTpl
134 : public ResidualDataAbstractTpl<_Scalar> {
135 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
136
137 typedef _Scalar Scalar;
138 typedef MathBaseTpl<Scalar> MathBase;
139 typedef ResidualDataAbstractTpl<Scalar> Base;
140 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
141 typedef typename MathBase::Matrix6xs Matrix6xs;
142
143 template <template <typename Scalar> class Model>
144 2404 ResidualDataCentroidalMomentumTpl(Model<Scalar>* const model,
145 DataCollectorAbstract* const data)
146 : Base(model, data),
147
1/2
✓ Branch 3 taken 2404 times.
✗ Branch 4 not taken.
2404 dhd_dq(6, model->get_state()->get_nv()),
148
1/2
✓ Branch 6 taken 2404 times.
✗ Branch 7 not taken.
4808 dhd_dv(6, model->get_state()->get_nv()) {
149
1/2
✓ Branch 1 taken 2404 times.
✗ Branch 2 not taken.
2404 dhd_dq.setZero();
150
1/2
✓ Branch 1 taken 2404 times.
✗ Branch 2 not taken.
2404 dhd_dv.setZero();
151
152 // Check that proper shared data has been passed
153 2404 DataCollectorMultibodyTpl<Scalar>* d =
154
1/2
✓ Branch 0 taken 2404 times.
✗ Branch 1 not taken.
2404 dynamic_cast<DataCollectorMultibodyTpl<Scalar>*>(shared);
155
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 2404 times.
2404 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 2404 pinocchio = d->pinocchio;
163 2404 }
164
165 pinocchio::DataTpl<Scalar>* pinocchio; //!< Pinocchio data
166 Matrix6xs dhd_dq; //!< Jacobian of the centroidal momentum
167 Matrix6xs dhd_dv; //!< Jacobian of the centroidal momentum
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_
182