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