GCC Code Coverage Report


Directory: ./
File: include/crocoddyl/multibody/actions/free-invdyn.hpp
Date: 2025-03-26 19:23:43
Exec Total Coverage
Lines: 55 73 75.3%
Branches: 51 108 47.2%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2021-2025, Heriot-Watt University, University of Edinburgh
5 // Copyright note valid unless otherwise stated in individual files.
6 // All rights reserved.
7 ///////////////////////////////////////////////////////////////////////////////
8
9 #ifndef CROCODDYL_MULTIBODY_ACTIONS_FREE_INVDYN_HPP_
10 #define CROCODDYL_MULTIBODY_ACTIONS_FREE_INVDYN_HPP_
11
12 #include <stdexcept>
13
14 #include "crocoddyl/core/actuation-base.hpp"
15 #include "crocoddyl/core/constraints/constraint-manager.hpp"
16 #include "crocoddyl/core/costs/cost-sum.hpp"
17 #include "crocoddyl/core/diff-action-base.hpp"
18 #include "crocoddyl/core/residual-base.hpp"
19 #include "crocoddyl/multibody/data/multibody.hpp"
20 #include "crocoddyl/multibody/fwd.hpp"
21 #include "crocoddyl/multibody/states/multibody.hpp"
22
23 namespace crocoddyl {
24
25 /**
26 * @brief Differential action model for free inverse dynamics in multibody
27 * systems.
28 *
29 * This class implements forward kinematic with an inverse-dynamics computed
30 * using the Recursive Newton Euler Algorithm (RNEA). The stack of cost and
31 * constraint functions are implemented in `CostModelSumTpl` and
32 * `ConstraintModelManagerTpl`, respectively. The accelerations are the decision
33 * variables defined as the control inputs, and the under-actuation constraint
34 * is under the name `tau`, thus the user is not allowed to use it.
35 *
36 *
37 * \sa `DifferentialActionModelAbstractTpl`, `calc()`, `calcDiff()`,
38 * `createData()`
39 */
40 template <typename _Scalar>
41 class DifferentialActionModelFreeInvDynamicsTpl
42 : public DifferentialActionModelAbstractTpl<_Scalar> {
43 public:
44 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
45 CROCODDYL_DERIVED_CAST(DifferentialActionModelBase,
46 DifferentialActionModelFreeInvDynamicsTpl)
47
48 typedef _Scalar Scalar;
49 typedef MathBaseTpl<Scalar> MathBase;
50 typedef DifferentialActionModelAbstractTpl<Scalar> Base;
51 typedef DifferentialActionDataFreeInvDynamicsTpl<Scalar> Data;
52 typedef DifferentialActionDataAbstractTpl<Scalar>
53 DifferentialActionDataAbstract;
54 typedef CostModelSumTpl<Scalar> CostModelSum;
55 typedef ConstraintModelManagerTpl<Scalar> ConstraintModelManager;
56 typedef StateMultibodyTpl<Scalar> StateMultibody;
57 typedef ActuationModelAbstractTpl<Scalar> ActuationModelAbstract;
58 typedef ConstraintModelResidualTpl<Scalar> ConstraintModelResidual;
59 typedef typename MathBase::VectorXs VectorXs;
60
61 /**
62 * @brief Initialize the free inverse-dynamics action model
63 *
64 * It describes the kinematic evolution of the multibody system and computes
65 * the needed torques using inverse dynamics.
66 *
67 * @param[in] state State of the multibody system
68 * @param[in] actuation Actuation model
69 * @param[in] costs Cost model
70 */
71 DifferentialActionModelFreeInvDynamicsTpl(
72 std::shared_ptr<StateMultibody> state,
73 std::shared_ptr<ActuationModelAbstract> actuation,
74 std::shared_ptr<CostModelSum> costs);
75
76 /**
77 * @brief Initialize the free inverse-dynamics action model
78 *
79 * @param[in] state State of the multibody system
80 * @param[in] actuation Actuation model
81 * @param[in] costs Cost model
82 * @param[in] constraints Constraints model
83 */
84 DifferentialActionModelFreeInvDynamicsTpl(
85 std::shared_ptr<StateMultibody> state,
86 std::shared_ptr<ActuationModelAbstract> actuation,
87 std::shared_ptr<CostModelSum> costs,
88 std::shared_ptr<ConstraintModelManager> constraints);
89 306 virtual ~DifferentialActionModelFreeInvDynamicsTpl() = default;
90
91 /**
92 * @brief Compute the system acceleration, cost value and constraint residuals
93 *
94 * It extracts the acceleration value from control vector and also computes
95 * the cost and constraints.
96 *
97 * @param[in] data Free inverse-dynamics data
98 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
99 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
100 */
101 virtual void calc(const std::shared_ptr<DifferentialActionDataAbstract>& data,
102 const Eigen::Ref<const VectorXs>& x,
103 const Eigen::Ref<const VectorXs>& u) override;
104
105 /**
106 * @brief @copydoc Base::calc(const
107 * std::shared_ptr<DifferentialActionDataAbstract>& data, const
108 * Eigen::Ref<const VectorXs>& x)
109 */
110 virtual void calc(const std::shared_ptr<DifferentialActionDataAbstract>& data,
111 const Eigen::Ref<const VectorXs>& x) override;
112
113 /**
114 * @brief Compute the derivatives of the dynamics, cost and constraint
115 * functions
116 *
117 * It computes the partial derivatives of the dynamical system and the cost
118 * and contraint functions. It assumes that `calc()` has been run first. This
119 * function builds a quadratic approximation of the time-continuous action
120 * model (i.e., dynamical system, cost and constraint functions).
121 *
122 * @param[in] data Free inverse-dynamics data
123 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
124 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
125 */
126 virtual void calcDiff(
127 const std::shared_ptr<DifferentialActionDataAbstract>& data,
128 const Eigen::Ref<const VectorXs>& x,
129 const Eigen::Ref<const VectorXs>& u) override;
130
131 /**
132 * @brief @copydoc Base::calcDiff(const
133 * std::shared_ptr<DifferentialActionDataAbstract>& data, const
134 * Eigen::Ref<const VectorXs>& x)
135 */
136 virtual void calcDiff(
137 const std::shared_ptr<DifferentialActionDataAbstract>& data,
138 const Eigen::Ref<const VectorXs>& x) override;
139
140 /**
141 * @brief Create the free inverse-dynamics data
142 *
143 * @return free inverse-dynamics data
144 */
145 virtual std::shared_ptr<DifferentialActionDataAbstract> createData() override;
146
147 /**
148 * @brief Cast the free-invdyn model to a different scalar type.
149 *
150 * It is useful for operations requiring different precision or scalar types.
151 *
152 * @tparam NewScalar The new scalar type to cast to.
153 * @return DifferentialActionModelFreeInvDynamicsTpl<NewScalar> A
154 * differential-action model with the new scalar type.
155 */
156 template <typename NewScalar>
157 DifferentialActionModelFreeInvDynamicsTpl<NewScalar> cast() const;
158
159 /**
160 * @brief Checks that a specific data belongs to the free inverse-dynamics
161 * model
162 */
163 virtual bool checkData(
164 const std::shared_ptr<DifferentialActionDataAbstract>& data) override;
165
166 /**
167 * @brief Computes the quasic static commands
168 *
169 * The quasic static commands are the ones produced for a reference posture as
170 * an equilibrium point with zero acceleration, i.e., for
171 * \f$\mathbf{f^q_x}\delta\mathbf{q}+\mathbf{f_u}\delta\mathbf{u}=\mathbf{0}\f$
172 *
173 * @param[in] data Free inverse-dynamics data
174 * @param[out] u Quasic-static commands
175 * @param[in] x State point (velocity has to be zero)
176 * @param[in] maxiter Maximum allowed number of iterations (default 100)
177 * @param[in] tol Tolerance (default 1e-9)
178 */
179 virtual void quasiStatic(
180 const std::shared_ptr<DifferentialActionDataAbstract>& data,
181 Eigen::Ref<VectorXs> u, const Eigen::Ref<const VectorXs>& x,
182 const std::size_t maxiter = 100,
183 const Scalar tol = Scalar(1e-9)) override;
184
185 /**
186 * @brief Return the number of inequality constraints
187 */
188 virtual std::size_t get_ng() const override;
189
190 /**
191 * @brief Return the number of equality constraints
192 */
193 virtual std::size_t get_nh() const override;
194
195 /**
196 * @brief Return the number of equality terminal constraints
197 */
198 virtual std::size_t get_ng_T() const override;
199
200 /**
201 * @brief Return the number of equality terminal constraints
202 */
203 virtual std::size_t get_nh_T() const override;
204
205 /**
206 * @brief Return the lower bound of the inequality constraints
207 */
208 virtual const VectorXs& get_g_lb() const override;
209
210 /**
211 * @brief Return the upper bound of the inequality constraints
212 */
213 virtual const VectorXs& get_g_ub() const override;
214
215 /**
216 * @brief Return the actuation model
217 */
218 const std::shared_ptr<ActuationModelAbstract>& get_actuation() const;
219
220 /**
221 * @brief Return the cost model
222 */
223 const std::shared_ptr<CostModelSum>& get_costs() const;
224
225 /**
226 * @brief Return the constraint model manager
227 */
228 const std::shared_ptr<ConstraintModelManager>& get_constraints() const;
229
230 /**
231 * @brief Return the Pinocchio model
232 */
233 pinocchio::ModelTpl<Scalar>& get_pinocchio() const;
234
235 /**
236 * @brief Print relevant information of the free inverse-dynamics model
237 *
238 * @param[out] os Output stream object
239 */
240 virtual void print(std::ostream& os) const override;
241
242 protected:
243 using Base::g_lb_; //!< Lower bound of the inequality constraints
244 using Base::g_ub_; //!< Upper bound of the inequality constraints
245 using Base::ng_; //!< Number of inequality constraints
246 using Base::nh_; //!< Number of equality constraints
247 using Base::nu_; //!< Control dimension
248 using Base::state_; //!< Model of the state
249
250 private:
251 void init(const std::shared_ptr<StateMultibody>& state);
252 std::shared_ptr<ActuationModelAbstract> actuation_; //!< Actuation model
253 std::shared_ptr<CostModelSum> costs_; //!< Cost model
254 std::shared_ptr<ConstraintModelManager> constraints_; //!< Constraint model
255 pinocchio::ModelTpl<Scalar>* pinocchio_; //!< Pinocchio model
256
257 public:
258 /**
259 * @brief Actuation residual
260 *
261 * This residual function enforces the torques of under-actuated joints (e.g.,
262 * floating-base joints) to be zero. We compute these torques and their
263 * derivatives using RNEA inside `DifferentialActionModelFreeInvDynamicsTpl`.
264 *
265 * As described in `ResidualModelAbstractTpl`, the residual value and its
266 * Jacobians are calculated by `calc` and `calcDiff`, respectively.
267 *
268 * \sa `ResidualModelAbstractTpl`, `calc()`, `calcDiff()`, `createData()`
269 */
270 class ResidualModelActuation : public ResidualModelAbstractTpl<_Scalar> {
271 public:
272 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
273 CROCODDYL_INNER_DERIVED_CAST(ResidualModelBase,
274 DifferentialActionModelFreeInvDynamicsTpl,
275 ResidualModelActuation)
276
277 typedef _Scalar Scalar;
278 typedef MathBaseTpl<Scalar> MathBase;
279 typedef ResidualModelAbstractTpl<Scalar> Base;
280 typedef StateMultibodyTpl<Scalar> StateMultibody;
281 typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
282 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
283 typedef ActuationModelAbstractTpl<Scalar> ActuationModelAbstract;
284 typedef typename MathBase::VectorXs VectorXs;
285 typedef typename MathBase::MatrixXs MatrixXs;
286
287 /**
288 * @brief Initialize the actuation residual model
289 *
290 * @param[in] state State of the multibody system
291 * @param[in] nu Dimension of the joint torques
292 */
293 51 ResidualModelActuation(std::shared_ptr<StateMultibody> state,
294 const std::size_t nu)
295 51 : Base(state, state->get_nv() - nu, state->get_nv(), true, true, true),
296
1/2
✓ Branch 5 taken 51 times.
✗ Branch 6 not taken.
102 na_(nu) {}
297 102 virtual ~ResidualModelActuation() = default;
298
299 /**
300 * @brief Compute the actuation residual
301 *
302 * @param[in] data Actuation residual data
303 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
304 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nv+nu}\f$
305 */
306 2311 virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
307 const Eigen::Ref<const VectorXs>&,
308 const Eigen::Ref<const VectorXs>&) override {
309 typename Data::ResidualDataActuation* d =
310 2311 static_cast<typename Data::ResidualDataActuation*>(data.get());
311 // Update the under-actuation set and residual
312 2311 std::size_t nrow = 0;
313 16177 for (std::size_t k = 0;
314
2/2
✓ Branch 2 taken 13866 times.
✓ Branch 3 taken 2311 times.
16177 k < static_cast<std::size_t>(d->actuation->tau_set.size()); ++k) {
315
2/2
✓ Branch 3 taken 4622 times.
✓ Branch 4 taken 9244 times.
13866 if (!d->actuation->tau_set[k]) {
316 4622 data->r(nrow) = d->pinocchio->tau(k);
317 4622 nrow += 1;
318 }
319 }
320 2311 }
321
322 /**
323 * @brief @copydoc Base::calc(const std::shared_ptr<ResidualDataAbstract>&
324 * data, const Eigen::Ref<const VectorXs>& x)
325 */
326 virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
327 const Eigen::Ref<const VectorXs>&) override {
328 data->r.setZero();
329 }
330
331 /**
332 * @brief Compute the derivatives of the actuation residual
333 *
334 * @param[in] data Actuation residual data
335 * @param[in] x State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
336 * @param[in] u Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
337 */
338 627 virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
339 const Eigen::Ref<const VectorXs>&,
340 const Eigen::Ref<const VectorXs>&) override {
341 typename Data::ResidualDataActuation* d =
342 627 static_cast<typename Data::ResidualDataActuation*>(data.get());
343 627 std::size_t nrow = 0;
344 627 const std::size_t nv = state_->get_nv();
345
1/2
✓ Branch 2 taken 627 times.
✗ Branch 3 not taken.
627 d->dtau_dx.leftCols(nv) = d->pinocchio->dtau_dq;
346
1/2
✓ Branch 2 taken 627 times.
✗ Branch 3 not taken.
627 d->dtau_dx.rightCols(nv) = d->pinocchio->dtau_dv;
347 627 d->dtau_dx -= d->actuation->dtau_dx;
348 4389 for (std::size_t k = 0;
349
2/2
✓ Branch 2 taken 3762 times.
✓ Branch 3 taken 627 times.
4389 k < static_cast<std::size_t>(d->actuation->tau_set.size()); ++k) {
350
2/2
✓ Branch 3 taken 1254 times.
✓ Branch 4 taken 2508 times.
3762 if (!d->actuation->tau_set[k]) {
351
2/4
✓ Branch 2 taken 1254 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1254 times.
✗ Branch 6 not taken.
1254 d->Rx.row(nrow) = d->dtau_dx.row(k);
352
2/4
✓ Branch 2 taken 1254 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1254 times.
✗ Branch 6 not taken.
1254 d->Ru.row(nrow) = d->pinocchio->M.row(k);
353 1254 nrow += 1;
354 }
355 }
356 627 }
357
358 /**
359 * @brief @copydoc Base::calcDiff(const
360 * std::shared_ptr<ResidualDataAbstract>& data, const Eigen::Ref<const
361 * VectorXs>& x)
362 */
363 virtual void calcDiff(const std::shared_ptr<ResidualDataAbstract>& data,
364 const Eigen::Ref<const VectorXs>&) override {
365 data->Rx.setZero();
366 data->Ru.setZero();
367 }
368
369 /**
370 * @brief Create the actuation residual data
371 *
372 * @return Actuation residual data
373 */
374 3230 virtual std::shared_ptr<ResidualDataAbstract> createData(
375 DataCollectorAbstract* const data) override {
376 return std::allocate_shared<typename Data::ResidualDataActuation>(
377 Eigen::aligned_allocator<typename Data::ResidualDataActuation>(),
378
1/2
✓ Branch 2 taken 3230 times.
✗ Branch 3 not taken.
3230 this, data);
379 }
380
381 /**
382 * @brief Cast the actuation-residual model to a different scalar type.
383 *
384 * It is useful for operations requiring different precision or scalar
385 * types.
386 *
387 * @tparam NewScalar The new scalar type to cast to.
388 * @return typename
389 * DifferentialActionModelFreeInvDynamicsTpl<NewScalar>::ResidualModelActuation
390 * A residual model with the new scalar type.
391 */
392 template <typename NewScalar>
393 typename DifferentialActionModelFreeInvDynamicsTpl<
394 NewScalar>::ResidualModelActuation
395 cast() const {
396 typedef typename DifferentialActionModelFreeInvDynamicsTpl<
397 NewScalar>::ResidualModelActuation ReturnType;
398 typedef StateMultibodyTpl<NewScalar> StateType;
399 ReturnType ret(std::static_pointer_cast<StateType>(
400 state_->template cast<NewScalar>()),
401 na_);
402 return ret;
403 }
404
405 /**
406 * @brief Print relevant information of the actuation residual model
407 *
408 * @param[out] os Output stream object
409 */
410 virtual void print(std::ostream& os) const override {
411 os << "ResidualModelActuation {nx=" << state_->get_nx()
412 << ", ndx=" << state_->get_ndx() << ", nu=" << nu_ << ", na=" << na_
413 << "}";
414 }
415
416 protected:
417 std::size_t na_; //!< Dimension of the joint torques
418 using Base::nu_;
419 using Base::state_;
420 };
421 };
422
423 template <typename _Scalar>
424 struct DifferentialActionDataFreeInvDynamicsTpl
425 : public DifferentialActionDataAbstractTpl<_Scalar> {
426 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
427 typedef _Scalar Scalar;
428 typedef MathBaseTpl<Scalar> MathBase;
429 typedef DifferentialActionDataAbstractTpl<Scalar> Base;
430 typedef JointDataAbstractTpl<Scalar> JointDataAbstract;
431 typedef DataCollectorJointActMultibodyTpl<Scalar>
432 DataCollectorJointActMultibody;
433 typedef CostDataSumTpl<Scalar> CostDataSum;
434 typedef ConstraintDataManagerTpl<Scalar> ConstraintDataManager;
435 typedef typename MathBase::VectorXs VectorXs;
436
437 template <template <typename Scalar> class Model>
438 9896 explicit DifferentialActionDataFreeInvDynamicsTpl(Model<Scalar>* const model)
439 : Base(model),
440
1/2
✓ Branch 1 taken 9894 times.
✗ Branch 2 not taken.
9896 pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
441
3/6
✓ Branch 1 taken 9894 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 9894 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 9894 times.
✗ Branch 8 not taken.
19792 multibody(
442
2/4
✓ Branch 1 taken 9894 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 9894 times.
✗ Branch 6 not taken.
9896 &pinocchio, model->get_actuation()->createData(),
443 std::make_shared<JointDataAbstract>(
444
2/4
✓ Branch 1 taken 9894 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 9894 times.
✗ Branch 5 not taken.
9896 model->get_state(), model->get_actuation(), model->get_nu())),
445
2/4
✓ Branch 1 taken 9894 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 9894 times.
✗ Branch 6 not taken.
9896 costs(model->get_costs()->createData(&multibody)),
446
2/4
✓ Branch 1 taken 9894 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 9894 times.
✗ Branch 6 not taken.
9896 constraints(model->get_constraints()->createData(&multibody)),
447
4/8
✓ Branch 2 taken 9894 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 9894 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 9894 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 9894 times.
✗ Branch 13 not taken.
19792 tmp_xstatic(model->get_state()->get_nx()) {
448
2/4
✓ Branch 1 taken 9894 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 9894 times.
✗ Branch 6 not taken.
9896 const std::size_t nv = model->get_state()->get_nv();
449
3/6
✓ Branch 1 taken 9894 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 9894 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 9894 times.
✗ Branch 8 not taken.
9896 Fu.leftCols(nv).diagonal().setOnes();
450
3/6
✓ Branch 2 taken 9894 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 9894 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 9894 times.
✗ Branch 9 not taken.
9896 multibody.joint->da_du.leftCols(nv).diagonal().setOnes();
451
1/2
✓ Branch 2 taken 9894 times.
✗ Branch 3 not taken.
9896 costs->shareMemory(this);
452
1/2
✓ Branch 2 taken 9894 times.
✗ Branch 3 not taken.
9896 constraints->shareMemory(this);
453
1/2
✓ Branch 1 taken 9894 times.
✗ Branch 2 not taken.
9896 tmp_xstatic.setZero();
454 9896 }
455 19788 virtual ~DifferentialActionDataFreeInvDynamicsTpl() = default;
456
457 pinocchio::DataTpl<Scalar> pinocchio; //!< Pinocchio data
458 DataCollectorJointActMultibody multibody; //!< Multibody data
459 std::shared_ptr<CostDataSum> costs; //!< Costs data
460 std::shared_ptr<ConstraintDataManager> constraints; //!< Constraints data
461 VectorXs
462 tmp_xstatic; //!< State point used for computing the quasi-static input
463 using Base::cost;
464 using Base::Fu;
465 using Base::Fx;
466 using Base::Lu;
467 using Base::Luu;
468 using Base::Lx;
469 using Base::Lxu;
470 using Base::Lxx;
471 using Base::r;
472 using Base::xout;
473
474 struct ResidualDataActuation : public ResidualDataAbstractTpl<_Scalar> {
475 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
476
477 typedef _Scalar Scalar;
478 typedef MathBaseTpl<Scalar> MathBase;
479 typedef ResidualDataAbstractTpl<Scalar> Base;
480 typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
481 typedef DataCollectorActMultibodyTpl<Scalar> DataCollectorActMultibody;
482 typedef ActuationDataAbstractTpl<Scalar> ActuationDataAbstract;
483 typedef typename MathBase::MatrixXs MatrixXs;
484
485 template <template <typename Scalar> class Model>
486 3232 ResidualDataActuation(Model<Scalar>* const model,
487 DataCollectorAbstract* const data)
488 : Base(model, data),
489
5/10
✓ Branch 3 taken 3230 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 3230 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 3230 times.
✗ Branch 11 not taken.
✓ Branch 14 taken 3230 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 3230 times.
✗ Branch 18 not taken.
3232 dtau_dx(model->get_state()->get_nv(), model->get_state()->get_ndx()) {
490
1/2
✓ Branch 1 taken 3230 times.
✗ Branch 2 not taken.
3232 dtau_dx.setZero();
491 // Check that proper shared data has been passed
492 3232 DataCollectorActMultibody* d =
493
1/2
✓ Branch 0 taken 3230 times.
✗ Branch 1 not taken.
3232 dynamic_cast<DataCollectorActMultibody*>(shared);
494
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 3230 times.
3232 if (d == NULL) {
495 throw_pretty(
496 "Invalid argument: the shared data should be derived from "
497 "DataCollectorActMultibody");
498 }
499
500 // Avoids data casting at runtime
501 3232 pinocchio = d->pinocchio;
502 3232 actuation = d->actuation;
503 3232 }
504
505 pinocchio::DataTpl<Scalar>* pinocchio; //!< Pinocchio data
506 std::shared_ptr<ActuationDataAbstract> actuation; //!< Actuation data
507 MatrixXs dtau_dx;
508 using Base::r;
509 using Base::Ru;
510 using Base::Rx;
511 using Base::shared;
512 };
513 };
514
515 } // namespace crocoddyl
516
517 /* --- Details -------------------------------------------------------------- */
518 /* --- Details -------------------------------------------------------------- */
519 /* --- Details -------------------------------------------------------------- */
520 #include <crocoddyl/multibody/actions/free-invdyn.hxx>
521
522 CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(
523 crocoddyl::DifferentialActionModelFreeInvDynamicsTpl)
524 CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT(
525 crocoddyl::DifferentialActionDataFreeInvDynamicsTpl)
526
527 #endif // CROCODDYL_MULTIBODY_ACTIONS_FREE_INVDYN_HPP_
528