Directory: | ./ |
---|---|
File: | include/crocoddyl/multibody/actions/impulse-fwddyn.hpp |
Date: | 2025-01-16 08:47:40 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 21 | 21 | 100.0% |
Branches: | 17 | 32 | 53.1% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | /////////////////////////////////////////////////////////////////////////////// | ||
2 | // BSD 3-Clause License | ||
3 | // | ||
4 | // Copyright (C) 2019-2024, LAAS-CNRS, University of Edinburgh, | ||
5 | // University of Oxford, Heriot-Watt University | ||
6 | // Copyright note valid unless otherwise stated in individual files. | ||
7 | // All rights reserved. | ||
8 | /////////////////////////////////////////////////////////////////////////////// | ||
9 | |||
10 | #ifndef CROCODDYL_MULTIBODY_ACTIONS_IMPULSE_FWDDYN_HPP_ | ||
11 | #define CROCODDYL_MULTIBODY_ACTIONS_IMPULSE_FWDDYN_HPP_ | ||
12 | |||
13 | #include <pinocchio/algorithm/centroidal.hpp> | ||
14 | #include <pinocchio/algorithm/compute-all-terms.hpp> | ||
15 | #include <pinocchio/algorithm/contact-dynamics.hpp> | ||
16 | #include <pinocchio/algorithm/frames.hpp> | ||
17 | #include <pinocchio/algorithm/kinematics-derivatives.hpp> | ||
18 | #include <pinocchio/algorithm/rnea-derivatives.hpp> | ||
19 | #include <stdexcept> | ||
20 | |||
21 | #include "crocoddyl/core/action-base.hpp" | ||
22 | #include "crocoddyl/core/constraints/constraint-manager.hpp" | ||
23 | #include "crocoddyl/core/costs/cost-sum.hpp" | ||
24 | #include "crocoddyl/core/utils/exception.hpp" | ||
25 | #include "crocoddyl/multibody/actions/impulse-fwddyn.hpp" | ||
26 | #include "crocoddyl/multibody/actuations/floating-base.hpp" | ||
27 | #include "crocoddyl/multibody/data/impulses.hpp" | ||
28 | #include "crocoddyl/multibody/fwd.hpp" | ||
29 | #include "crocoddyl/multibody/impulses/multiple-impulses.hpp" | ||
30 | #include "crocoddyl/multibody/states/multibody.hpp" | ||
31 | |||
32 | namespace crocoddyl { | ||
33 | |||
34 | /** | ||
35 | * @brief Action model for impulse forward dynamics in multibody systems. | ||
36 | * | ||
37 | * This class implements impulse forward dynamics given a stack of | ||
38 | * rigid-impulses described in `ImpulseModelMultipleTpl`, i.e., \f[ | ||
39 | * \left[\begin{matrix}\mathbf{v}^+ \\ -\boldsymbol{\Lambda}\end{matrix}\right] | ||
40 | * = \left[\begin{matrix}\mathbf{M} & \mathbf{J}^{\top}_c \\ {\mathbf{J}_{c}} & | ||
41 | * \mathbf{0} \end{matrix}\right]^{-1} | ||
42 | * \left[\begin{matrix}\mathbf{M}\mathbf{v}^- \\ -e\mathbf{J}_c\mathbf{v}^- | ||
43 | * \\\end{matrix}\right], \f] where \f$\mathbf{q}\in Q\f$, | ||
44 | * \f$\mathbf{v}\in\mathbb{R}^{nv}\f$ are the configuration point and | ||
45 | * generalized velocity (its tangent vector), respectively; \f$\mathbf{v}^+\f$, | ||
46 | * \f$\mathbf{v}^-\f$ are the discontinuous changes in the generalized velocity | ||
47 | * (i.e., velocity before and after impact, respectively); | ||
48 | * \f$\mathbf{J}_c\in\mathbb{R}^{nc\times nv}\f$ is the contact Jacobian | ||
49 | * expressed in the local frame; and | ||
50 | * \f$\boldsymbol{\Lambda}\in\mathbb{R}^{nc}\f$ is the impulse vector. | ||
51 | * | ||
52 | * The derivatives of the next state and contact impulses are computed | ||
53 | * efficiently based on the analytical derivatives of Recursive Newton Euler | ||
54 | * Algorithm (RNEA) as described in \cite mastalli-icra20. Note that the | ||
55 | * algorithm for computing the RNEA derivatives is described in \cite | ||
56 | * carpentier-rss18. | ||
57 | * | ||
58 | * The stack of cost and constraint functions are implemented in | ||
59 | * `CostModelSumTpl` and `ConstraintModelAbstractTpl`, respectively. The | ||
60 | * computation of the impulse dynamics and its derivatives are carrying out | ||
61 | * inside `calc()` and `calcDiff()` functions, respectively. It is also | ||
62 | * important to remark that `calcDiff()` computes the derivatives using the | ||
63 | * latest stored values by `calc()`. Thus, we need to run `calc()` first. | ||
64 | * | ||
65 | * \sa `ActionModelAbstractTpl`, `calc()`, `calcDiff()`, `createData()` | ||
66 | */ | ||
67 | template <typename _Scalar> | ||
68 | class ActionModelImpulseFwdDynamicsTpl | ||
69 | : public ActionModelAbstractTpl<_Scalar> { | ||
70 | public: | ||
71 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW | ||
72 | |||
73 | typedef _Scalar Scalar; | ||
74 | typedef ActionModelAbstractTpl<Scalar> Base; | ||
75 | typedef ActionDataImpulseFwdDynamicsTpl<Scalar> Data; | ||
76 | typedef MathBaseTpl<Scalar> MathBase; | ||
77 | typedef CostModelSumTpl<Scalar> CostModelSum; | ||
78 | typedef ConstraintModelManagerTpl<Scalar> ConstraintModelManager; | ||
79 | typedef StateMultibodyTpl<Scalar> StateMultibody; | ||
80 | typedef ActionDataAbstractTpl<Scalar> ActionDataAbstract; | ||
81 | typedef ImpulseModelMultipleTpl<Scalar> ImpulseModelMultiple; | ||
82 | typedef typename MathBase::VectorXs VectorXs; | ||
83 | typedef typename MathBase::MatrixXs MatrixXs; | ||
84 | |||
85 | /** | ||
86 | * @brief Initialize the impulse forward-dynamics action model | ||
87 | * | ||
88 | * It describes the impulse dynamics of a multibody system under rigid-contact | ||
89 | * constraints defined by `ImpulseModelMultipleTpl`. It computes the cost | ||
90 | * described in `CostModelSumTpl`. | ||
91 | * | ||
92 | * @param[in] state State of the multibody system | ||
93 | * @param[in] actuation Actuation model | ||
94 | * @param[in] impulses Stack of rigid impulses | ||
95 | * @param[in] costs Stack of cost functions | ||
96 | * @param[in] r_coeff Restitution coefficient (default 0.) | ||
97 | * @param[in] JMinvJt_damping Damping term used in operational space inertia | ||
98 | * matrix (default 0.) | ||
99 | * @param[in] enable_force Enable the computation of the contact force | ||
100 | * derivatives (default false) | ||
101 | */ | ||
102 | ActionModelImpulseFwdDynamicsTpl( | ||
103 | boost::shared_ptr<StateMultibody> state, | ||
104 | boost::shared_ptr<ImpulseModelMultiple> impulses, | ||
105 | boost::shared_ptr<CostModelSum> costs, const Scalar r_coeff = Scalar(0.), | ||
106 | const Scalar JMinvJt_damping = Scalar(0.), | ||
107 | const bool enable_force = false); | ||
108 | |||
109 | /** | ||
110 | * @brief Initialize the impulse forward-dynamics action model | ||
111 | * | ||
112 | * It describes the impulse dynamics of a multibody system under rigid-contact | ||
113 | * constraints defined by `ImpulseModelMultipleTpl`. It computes the cost | ||
114 | * described in `CostModelSumTpl`. | ||
115 | * | ||
116 | * @param[in] state State of the multibody system | ||
117 | * @param[in] actuation Actuation model | ||
118 | * @param[in] impulses Stack of rigid impulses | ||
119 | * @param[in] costs Stack of cost functions | ||
120 | * @param[in] constraints Stack of constraints | ||
121 | * @param[in] r_coeff Restitution coefficient (default 0.) | ||
122 | * @param[in] JMinvJt_damping Damping term used in operational space inertia | ||
123 | * matrix (default 0.) | ||
124 | * @param[in] enable_force Enable the computation of the contact force | ||
125 | * derivatives (default false) | ||
126 | */ | ||
127 | ActionModelImpulseFwdDynamicsTpl( | ||
128 | boost::shared_ptr<StateMultibody> state, | ||
129 | boost::shared_ptr<ImpulseModelMultiple> impulses, | ||
130 | boost::shared_ptr<CostModelSum> costs, | ||
131 | boost::shared_ptr<ConstraintModelManager> constraints, | ||
132 | const Scalar r_coeff = Scalar(0.), | ||
133 | const Scalar JMinvJt_damping = Scalar(0.), | ||
134 | const bool enable_force = false); | ||
135 | virtual ~ActionModelImpulseFwdDynamicsTpl(); | ||
136 | |||
137 | /** | ||
138 | * @brief Compute the system acceleration, and cost value | ||
139 | * | ||
140 | * It computes the system acceleration using the impulse dynamics. | ||
141 | * | ||
142 | * @param[in] data Impulse forward-dynamics data | ||
143 | * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$ | ||
144 | * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$ | ||
145 | */ | ||
146 | virtual void calc(const boost::shared_ptr<ActionDataAbstract>& data, | ||
147 | const Eigen::Ref<const VectorXs>& x, | ||
148 | const Eigen::Ref<const VectorXs>& u); | ||
149 | |||
150 | /** | ||
151 | * @brief Compute the total cost value for nodes that depends only on the | ||
152 | * state | ||
153 | * | ||
154 | * It updates the total cost and the system acceleration is not updated as it | ||
155 | * is expected to be zero. Additionally, it does not update the contact | ||
156 | * forces. This function is used in the terminal nodes of an optimal control | ||
157 | * problem. | ||
158 | * | ||
159 | * @param[in] data Impulse forward-dynamics data | ||
160 | * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$ | ||
161 | */ | ||
162 | virtual void calc(const boost::shared_ptr<ActionDataAbstract>& data, | ||
163 | const Eigen::Ref<const VectorXs>& x); | ||
164 | |||
165 | /** | ||
166 | * @brief Compute the derivatives of the impulse dynamics, and cost function | ||
167 | * | ||
168 | * @param[in] data Impulse forward-dynamics data | ||
169 | * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$ | ||
170 | * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$ | ||
171 | */ | ||
172 | virtual void calcDiff(const boost::shared_ptr<ActionDataAbstract>& data, | ||
173 | const Eigen::Ref<const VectorXs>& x, | ||
174 | const Eigen::Ref<const VectorXs>& u); | ||
175 | |||
176 | /** | ||
177 | * @brief Compute the derivatives of the cost functions with respect to the | ||
178 | * state only | ||
179 | * | ||
180 | * It updates the derivatives of the cost function with respect to the state | ||
181 | * only. Additionally, it does not update the contact forces derivatives. This | ||
182 | * function is used in the terminal nodes of an optimal control problem. | ||
183 | * | ||
184 | * @param[in] data Impulse forward-dynamics data | ||
185 | * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$ | ||
186 | */ | ||
187 | virtual void calcDiff(const boost::shared_ptr<ActionDataAbstract>& data, | ||
188 | const Eigen::Ref<const VectorXs>& x); | ||
189 | |||
190 | /** | ||
191 | * @brief Create the impulse forward-dynamics data | ||
192 | * | ||
193 | * @return impulse forward-dynamics data | ||
194 | */ | ||
195 | virtual boost::shared_ptr<ActionDataAbstract> createData(); | ||
196 | |||
197 | /** | ||
198 | * @brief Check that the given data belongs to the impulse forward-dynamics | ||
199 | * data | ||
200 | */ | ||
201 | virtual bool checkData(const boost::shared_ptr<ActionDataAbstract>& data); | ||
202 | |||
203 | /** | ||
204 | * @brief @copydoc Base::quasiStatic() | ||
205 | */ | ||
206 | virtual void quasiStatic(const boost::shared_ptr<ActionDataAbstract>& data, | ||
207 | Eigen::Ref<VectorXs> u, | ||
208 | const Eigen::Ref<const VectorXs>& x, | ||
209 | const std::size_t maxiter = 100, | ||
210 | const Scalar tol = Scalar(1e-9)); | ||
211 | |||
212 | /** | ||
213 | * @brief Return the number of inequality constraints | ||
214 | */ | ||
215 | virtual std::size_t get_ng() const; | ||
216 | |||
217 | /** | ||
218 | * @brief Return the number of equality constraints | ||
219 | */ | ||
220 | virtual std::size_t get_nh() const; | ||
221 | |||
222 | /** | ||
223 | * @brief Return the number of equality terminal constraints | ||
224 | */ | ||
225 | virtual std::size_t get_ng_T() const; | ||
226 | |||
227 | /** | ||
228 | * @brief Return the number of equality terminal constraints | ||
229 | */ | ||
230 | virtual std::size_t get_nh_T() const; | ||
231 | |||
232 | /** | ||
233 | * @brief Return the lower bound of the inequality constraints | ||
234 | */ | ||
235 | virtual const VectorXs& get_g_lb() const; | ||
236 | |||
237 | /** | ||
238 | * @brief Return the upper bound of the inequality constraints | ||
239 | */ | ||
240 | virtual const VectorXs& get_g_ub() const; | ||
241 | |||
242 | /** | ||
243 | * @brief Return the impulse model | ||
244 | */ | ||
245 | const boost::shared_ptr<ImpulseModelMultiple>& get_impulses() const; | ||
246 | |||
247 | /** | ||
248 | * @brief Return the cost model | ||
249 | */ | ||
250 | const boost::shared_ptr<CostModelSum>& get_costs() const; | ||
251 | |||
252 | /** | ||
253 | * @brief Return the constraint model manager | ||
254 | */ | ||
255 | const boost::shared_ptr<ConstraintModelManager>& get_constraints() const; | ||
256 | |||
257 | /** | ||
258 | * @brief Return the Pinocchio model | ||
259 | */ | ||
260 | pinocchio::ModelTpl<Scalar>& get_pinocchio() const; | ||
261 | |||
262 | /** | ||
263 | * @brief Return the armature vector | ||
264 | */ | ||
265 | const VectorXs& get_armature() const; | ||
266 | |||
267 | /** | ||
268 | * @brief Return the restituion coefficient | ||
269 | */ | ||
270 | const Scalar get_restitution_coefficient() const; | ||
271 | |||
272 | /** | ||
273 | * @brief Return the damping factor used in the operational space inertia | ||
274 | * matrix | ||
275 | */ | ||
276 | const Scalar get_damping_factor() const; | ||
277 | |||
278 | /** | ||
279 | * @brief Modify the armature vector | ||
280 | */ | ||
281 | void set_armature(const VectorXs& armature); | ||
282 | |||
283 | /** | ||
284 | * @brief Modify the restituion coefficient | ||
285 | */ | ||
286 | void set_restitution_coefficient(const Scalar r_coeff); | ||
287 | |||
288 | /** | ||
289 | * @brief Modify the damping factor used in the operational space inertia | ||
290 | * matrix | ||
291 | */ | ||
292 | void set_damping_factor(const Scalar damping); | ||
293 | |||
294 | /** | ||
295 | * @brief Print relevant information of the impulse forward-dynamics model | ||
296 | * | ||
297 | * @param[out] os Output stream object | ||
298 | */ | ||
299 | virtual void print(std::ostream& os) const; | ||
300 | |||
301 | protected: | ||
302 | using Base::g_lb_; //!< Lower bound of the inequality constraints | ||
303 | using Base::g_ub_; //!< Upper bound of the inequality constraints | ||
304 | using Base::state_; //!< Model of the state | ||
305 | |||
306 | private: | ||
307 | void init(); | ||
308 | void initCalc(Data* data, const Eigen::Ref<const VectorXs>& x); | ||
309 | void initCalcDiff(Data* data, const Eigen::Ref<const VectorXs>& x); | ||
310 | boost::shared_ptr<ImpulseModelMultiple> impulses_; //!< Impulse model | ||
311 | boost::shared_ptr<CostModelSum> costs_; //!< Cost model | ||
312 | boost::shared_ptr<ConstraintModelManager> constraints_; //!< Constraint model | ||
313 | pinocchio::ModelTpl<Scalar>& pinocchio_; //!< Pinocchio model | ||
314 | bool with_armature_; //!< Indicate if we have defined an armature | ||
315 | VectorXs armature_; //!< Armature vector | ||
316 | Scalar r_coeff_; //!< Restitution coefficient | ||
317 | Scalar JMinvJt_damping_; //!< Damping factor used in operational space | ||
318 | //!< inertia matrix | ||
319 | bool enable_force_; //!< Indicate if we have enabled the computation of the | ||
320 | //!< contact-forces derivatives | ||
321 | pinocchio::MotionTpl<Scalar> gravity_; //! Gravity acceleration | ||
322 | }; | ||
323 | |||
324 | template <typename _Scalar> | ||
325 | struct ActionDataImpulseFwdDynamicsTpl : public ActionDataAbstractTpl<_Scalar> { | ||
326 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW | ||
327 | typedef _Scalar Scalar; | ||
328 | typedef MathBaseTpl<Scalar> MathBase; | ||
329 | typedef ActionDataAbstractTpl<Scalar> Base; | ||
330 | typedef typename MathBase::VectorXs VectorXs; | ||
331 | typedef typename MathBase::MatrixXs MatrixXs; | ||
332 | |||
333 | template <template <typename Scalar> class Model> | ||
334 | 4256 | explicit ActionDataImpulseFwdDynamicsTpl(Model<Scalar>* const model) | |
335 | : Base(model), | ||
336 |
1/2✓ Branch 1 taken 4256 times.
✗ Branch 2 not taken.
|
4256 | pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())), |
337 |
2/4✓ Branch 3 taken 4256 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 4256 times.
✗ Branch 7 not taken.
|
4256 | multibody(&pinocchio, model->get_impulses()->createData(&pinocchio)), |
338 |
1/2✓ Branch 3 taken 4256 times.
✗ Branch 4 not taken.
|
4256 | costs(model->get_costs()->createData(&multibody)), |
339 |
1/2✓ Branch 4 taken 4256 times.
✗ Branch 5 not taken.
|
4256 | vnone(model->get_state()->get_nv()), |
340 |
1/2✓ Branch 3 taken 4256 times.
✗ Branch 4 not taken.
|
8512 | Kinv(model->get_state()->get_nv() + |
341 | 4256 | model->get_impulses()->get_nc_total(), | |
342 | 8512 | model->get_state()->get_nv() + | |
343 | 4256 | model->get_impulses()->get_nc_total()), | |
344 |
1/2✓ Branch 3 taken 4256 times.
✗ Branch 4 not taken.
|
4256 | df_dx(model->get_impulses()->get_nc_total(), |
345 | 4256 | model->get_state()->get_ndx()), | |
346 |
1/2✓ Branch 10 taken 4256 times.
✗ Branch 11 not taken.
|
12768 | dgrav_dq(model->get_state()->get_nv(), model->get_state()->get_nv()) { |
347 |
1/2✓ Branch 2 taken 4256 times.
✗ Branch 3 not taken.
|
4256 | costs->shareMemory(this); |
348 |
2/2✓ Branch 2 taken 796 times.
✓ Branch 3 taken 3460 times.
|
4256 | if (model->get_constraints() != nullptr) { |
349 |
1/2✓ Branch 3 taken 796 times.
✗ Branch 4 not taken.
|
796 | constraints = model->get_constraints()->createData(&multibody); |
350 |
1/2✓ Branch 2 taken 796 times.
✗ Branch 3 not taken.
|
796 | constraints->shareMemory(this); |
351 | } | ||
352 |
1/2✓ Branch 1 taken 4256 times.
✗ Branch 2 not taken.
|
4256 | vnone.setZero(); |
353 |
1/2✓ Branch 1 taken 4256 times.
✗ Branch 2 not taken.
|
4256 | Kinv.setZero(); |
354 |
1/2✓ Branch 1 taken 4256 times.
✗ Branch 2 not taken.
|
4256 | df_dx.setZero(); |
355 |
1/2✓ Branch 1 taken 4256 times.
✗ Branch 2 not taken.
|
4256 | dgrav_dq.setZero(); |
356 | 4256 | } | |
357 | |||
358 | pinocchio::DataTpl<Scalar> pinocchio; | ||
359 | DataCollectorMultibodyInImpulseTpl<Scalar> multibody; | ||
360 | boost::shared_ptr<CostDataSumTpl<Scalar> > costs; | ||
361 | boost::shared_ptr<ConstraintDataManagerTpl<Scalar> > constraints; | ||
362 | VectorXs vnone; | ||
363 | MatrixXs Kinv; | ||
364 | MatrixXs df_dx; | ||
365 | MatrixXs dgrav_dq; | ||
366 | }; | ||
367 | |||
368 | } // namespace crocoddyl | ||
369 | |||
370 | /* --- Details -------------------------------------------------------------- */ | ||
371 | /* --- Details -------------------------------------------------------------- */ | ||
372 | /* --- Details -------------------------------------------------------------- */ | ||
373 | #include <crocoddyl/multibody/actions/impulse-fwddyn.hxx> | ||
374 | |||
375 | #endif // CROCODDYL_MULTIBODY_ACTIONS_IMPULSE_FWDDYN_HPP_ | ||
376 |