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