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