GCC Code Coverage Report


Directory: ./
File: include/crocoddyl/multibody/actions/free-fwddyn.hpp
Date: 2025-01-16 08:47:40
Exec Total Coverage
Lines: 20 20 100.0%
Branches: 20 38 52.6%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2019-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_ACTIONS_FREE_FWDDYN_HPP_
11 #define CROCODDYL_MULTIBODY_ACTIONS_FREE_FWDDYN_HPP_
12
13 #include <stdexcept>
14
15 #ifdef PINOCCHIO_WITH_CPPAD_SUPPORT // TODO(cmastalli): Removed after merging
16 // Pinocchio v.2.4.8
17 #include <pinocchio/codegen/cppadcg.hpp>
18 #endif
19
20 #include "crocoddyl/core/actuation-base.hpp"
21 #include "crocoddyl/core/constraints/constraint-manager.hpp"
22 #include "crocoddyl/core/costs/cost-sum.hpp"
23 #include "crocoddyl/core/diff-action-base.hpp"
24 #include "crocoddyl/core/utils/exception.hpp"
25 #include "crocoddyl/multibody/data/multibody.hpp"
26 #include "crocoddyl/multibody/fwd.hpp"
27 #include "crocoddyl/multibody/states/multibody.hpp"
28
29 namespace crocoddyl {
30
31 /**
32 * @brief Differential action model for free forward dynamics in multibody
33 * systems.
34 *
35 * This class implements free forward dynamics, i.e.,
36 * \f[
37 * \mathbf{M}\dot{\mathbf{v}} + \mathbf{h}(\mathbf{q},\mathbf{v}) =
38 * \boldsymbol{\tau}, \f] where \f$\mathbf{q}\in Q\f$,
39 * \f$\mathbf{v}\in\mathbb{R}^{nv}\f$ are the configuration point and
40 * generalized velocity (its tangent vector), respectively;
41 * \f$\boldsymbol{\tau}\f$ is the torque inputs and
42 * \f$\mathbf{h}(\mathbf{q},\mathbf{v})\f$ are the Coriolis effect and gravity
43 * field.
44 *
45 * The derivatives of the system acceleration is computed efficiently based on
46 * the analytical derivatives of Articulate Body Algorithm (ABA) as described in
47 * \cite carpentier-rss18.
48 *
49 * The stack of cost functions is implemented in `CostModelSumTpl`. The
50 * computation of the free forward dynamics and its derivatives are carrying out
51 * inside `calc()` and `calcDiff()` functions, respectively. It is also
52 * important to remark that `calcDiff()` computes the derivatives using the
53 * latest stored values by `calc()`. Thus, we need to run `calc()` first.
54 *
55 * \sa `DifferentialActionModelAbstractTpl`, `calc()`, `calcDiff()`,
56 * `createData()`
57 */
58 template <typename _Scalar>
59 class DifferentialActionModelFreeFwdDynamicsTpl
60 : public DifferentialActionModelAbstractTpl<_Scalar> {
61 public:
62 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
63
64 typedef _Scalar Scalar;
65 typedef DifferentialActionModelAbstractTpl<Scalar> Base;
66 typedef DifferentialActionDataFreeFwdDynamicsTpl<Scalar> Data;
67 typedef DifferentialActionDataAbstractTpl<Scalar>
68 DifferentialActionDataAbstract;
69 typedef StateMultibodyTpl<Scalar> StateMultibody;
70 typedef CostModelSumTpl<Scalar> CostModelSum;
71 typedef ConstraintModelManagerTpl<Scalar> ConstraintModelManager;
72 typedef ActuationModelAbstractTpl<Scalar> ActuationModelAbstract;
73 typedef MathBaseTpl<Scalar> MathBase;
74 typedef typename MathBase::VectorXs VectorXs;
75 typedef typename MathBase::MatrixXs MatrixXs;
76
77 DifferentialActionModelFreeFwdDynamicsTpl(
78 boost::shared_ptr<StateMultibody> state,
79 boost::shared_ptr<ActuationModelAbstract> actuation,
80 boost::shared_ptr<CostModelSum> costs,
81 boost::shared_ptr<ConstraintModelManager> constraints = nullptr);
82 virtual ~DifferentialActionModelFreeFwdDynamicsTpl();
83
84 /**
85 * @brief Compute the system acceleration, and cost value
86 *
87 * It computes the system acceleration using the free forward-dynamics.
88 *
89 * @param[in] data Free forward-dynamics data
90 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
91 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
92 */
93 virtual void calc(
94 const boost::shared_ptr<DifferentialActionDataAbstract>& data,
95 const Eigen::Ref<const VectorXs>& x, const Eigen::Ref<const VectorXs>& u);
96
97 /**
98 * @brief @copydoc Base::calc(const
99 * boost::shared_ptr<DifferentialActionDataAbstract>& data, const
100 * Eigen::Ref<const VectorXs>& x)
101 */
102 virtual void calc(
103 const boost::shared_ptr<DifferentialActionDataAbstract>& data,
104 const Eigen::Ref<const VectorXs>& x);
105
106 /**
107 * @brief Compute the derivatives of the contact dynamics, and cost function
108 *
109 * @param[in] data Free forward-dynamics data
110 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
111 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
112 */
113 virtual void calcDiff(
114 const boost::shared_ptr<DifferentialActionDataAbstract>& data,
115 const Eigen::Ref<const VectorXs>& x, const Eigen::Ref<const VectorXs>& u);
116
117 /**
118 * @brief @copydoc Base::calcDiff(const
119 * boost::shared_ptr<DifferentialActionDataAbstract>& data, const
120 * Eigen::Ref<const VectorXs>& x)
121 */
122 virtual void calcDiff(
123 const boost::shared_ptr<DifferentialActionDataAbstract>& data,
124 const Eigen::Ref<const VectorXs>& x);
125
126 /**
127 * @brief Create the free forward-dynamics data
128 *
129 * @return free forward-dynamics data
130 */
131 virtual boost::shared_ptr<DifferentialActionDataAbstract> createData();
132
133 /**
134 * @brief Check that the given data belongs to the free forward-dynamics data
135 */
136 virtual bool checkData(
137 const boost::shared_ptr<DifferentialActionDataAbstract>& data);
138
139 /**
140 * @brief @copydoc Base::quasiStatic()
141 */
142 virtual void quasiStatic(
143 const boost::shared_ptr<DifferentialActionDataAbstract>& data,
144 Eigen::Ref<VectorXs> u, const Eigen::Ref<const VectorXs>& x,
145 const std::size_t maxiter = 100, const Scalar tol = Scalar(1e-9));
146
147 /**
148 * @brief Return the number of inequality constraints
149 */
150 virtual std::size_t get_ng() const;
151
152 /**
153 * @brief Return the number of equality constraints
154 */
155 virtual std::size_t get_nh() const;
156
157 /**
158 * @brief Return the number of equality terminal constraints
159 */
160 virtual std::size_t get_ng_T() const;
161
162 /**
163 * @brief Return the number of equality terminal constraints
164 */
165 virtual std::size_t get_nh_T() const;
166
167 /**
168 * @brief Return the lower bound of the inequality constraints
169 */
170 virtual const VectorXs& get_g_lb() const;
171
172 /**
173 * @brief Return the upper bound of the inequality constraints
174 */
175 virtual const VectorXs& get_g_ub() const;
176
177 /**
178 * @brief Return the actuation model
179 */
180 const boost::shared_ptr<ActuationModelAbstract>& get_actuation() const;
181
182 /**
183 * @brief Return the cost model
184 */
185 const boost::shared_ptr<CostModelSum>& get_costs() const;
186
187 /**
188 * @brief Return the constraint model manager
189 */
190 const boost::shared_ptr<ConstraintModelManager>& get_constraints() const;
191
192 /**
193 * @brief Return the Pinocchio model
194 */
195 pinocchio::ModelTpl<Scalar>& get_pinocchio() const;
196
197 /**
198 * @brief Return the armature vector
199 */
200 const VectorXs& get_armature() const;
201
202 /**
203 * @brief Modify the armature vector
204 */
205 void set_armature(const VectorXs& armature);
206
207 /**
208 * @brief Print relevant information of the free forward-dynamics model
209 *
210 * @param[out] os Output stream object
211 */
212 virtual void print(std::ostream& os) const;
213
214 protected:
215 using Base::g_lb_; //!< Lower bound of the inequality constraints
216 using Base::g_ub_; //!< Upper bound of the inequality constraints
217 using Base::nu_; //!< Control dimension
218 using Base::state_; //!< Model of the state
219
220 private:
221 boost::shared_ptr<ActuationModelAbstract> actuation_; //!< Actuation model
222 boost::shared_ptr<CostModelSum> costs_; //!< Cost model
223 boost::shared_ptr<ConstraintModelManager> constraints_; //!< Constraint model
224 pinocchio::ModelTpl<Scalar>& pinocchio_; //!< Pinocchio model
225 bool without_armature_; //!< Indicate if we have defined an armature
226 VectorXs armature_; //!< Armature vector
227 };
228
229 template <typename _Scalar>
230 struct DifferentialActionDataFreeFwdDynamicsTpl
231 : public DifferentialActionDataAbstractTpl<_Scalar> {
232 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
233 typedef _Scalar Scalar;
234 typedef MathBaseTpl<Scalar> MathBase;
235 typedef DifferentialActionDataAbstractTpl<Scalar> Base;
236 typedef JointDataAbstractTpl<Scalar> JointDataAbstract;
237 typedef DataCollectorJointActMultibodyTpl<Scalar>
238 DataCollectorJointActMultibody;
239 typedef typename MathBase::VectorXs VectorXs;
240 typedef typename MathBase::MatrixXs MatrixXs;
241
242 template <template <typename Scalar> class Model>
243 10438 explicit DifferentialActionDataFreeFwdDynamicsTpl(Model<Scalar>* const model)
244 : Base(model),
245
1/2
✓ Branch 1 taken 10438 times.
✗ Branch 2 not taken.
10438 pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
246
2/4
✓ Branch 2 taken 10438 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 10438 times.
✗ Branch 6 not taken.
20876 multibody(
247
1/2
✓ Branch 3 taken 10438 times.
✗ Branch 4 not taken.
10438 &pinocchio, model->get_actuation()->createData(),
248 boost::make_shared<JointDataAbstract>(
249 10438 model->get_state(), model->get_actuation(), model->get_nu())),
250
1/2
✓ Branch 3 taken 10438 times.
✗ Branch 4 not taken.
10438 costs(model->get_costs()->createData(&multibody)),
251
1/2
✓ Branch 7 taken 10438 times.
✗ Branch 8 not taken.
10438 Minv(model->get_state()->get_nv(), model->get_state()->get_nv()),
252
1/2
✓ Branch 4 taken 10438 times.
✗ Branch 5 not taken.
10438 u_drift(model->get_state()->get_nv()),
253
1/2
✓ Branch 7 taken 10438 times.
✗ Branch 8 not taken.
10438 dtau_dx(model->get_state()->get_nv(), model->get_state()->get_ndx()),
254
1/2
✓ Branch 7 taken 10438 times.
✗ Branch 8 not taken.
31314 tmp_xstatic(model->get_state()->get_nx()) {
255
2/4
✓ Branch 2 taken 10438 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 10438 times.
✗ Branch 6 not taken.
10438 multibody.joint->dtau_du.diagonal().setOnes();
256
1/2
✓ Branch 2 taken 10438 times.
✗ Branch 3 not taken.
10438 costs->shareMemory(this);
257
2/2
✓ Branch 2 taken 6663 times.
✓ Branch 3 taken 3775 times.
10438 if (model->get_constraints() != nullptr) {
258
1/2
✓ Branch 3 taken 6663 times.
✗ Branch 4 not taken.
6663 constraints = model->get_constraints()->createData(&multibody);
259
1/2
✓ Branch 2 taken 6663 times.
✗ Branch 3 not taken.
6663 constraints->shareMemory(this);
260 }
261
1/2
✓ Branch 1 taken 10438 times.
✗ Branch 2 not taken.
10438 Minv.setZero();
262
1/2
✓ Branch 1 taken 10438 times.
✗ Branch 2 not taken.
10438 u_drift.setZero();
263
1/2
✓ Branch 1 taken 10438 times.
✗ Branch 2 not taken.
10438 dtau_dx.setZero();
264
1/2
✓ Branch 1 taken 10438 times.
✗ Branch 2 not taken.
10438 tmp_xstatic.setZero();
265 10438 }
266
267 pinocchio::DataTpl<Scalar> pinocchio;
268 DataCollectorJointActMultibody multibody;
269 boost::shared_ptr<CostDataSumTpl<Scalar> > costs;
270 boost::shared_ptr<ConstraintDataManagerTpl<Scalar> > constraints;
271 MatrixXs Minv;
272 VectorXs u_drift;
273 MatrixXs dtau_dx;
274 VectorXs tmp_xstatic;
275
276 using Base::cost;
277 using Base::Fu;
278 using Base::Fx;
279 using Base::Lu;
280 using Base::Luu;
281 using Base::Lx;
282 using Base::Lxu;
283 using Base::Lxx;
284 using Base::r;
285 using Base::xout;
286 };
287
288 } // namespace crocoddyl
289
290 /* --- Details -------------------------------------------------------------- */
291 /* --- Details -------------------------------------------------------------- */
292 /* --- Details -------------------------------------------------------------- */
293 #include <crocoddyl/multibody/actions/free-fwddyn.hxx>
294
295 #endif // CROCODDYL_MULTIBODY_ACTIONS_FREE_FWDDYN_HPP_
296