Crocoddyl
 
Loading...
Searching...
No Matches
free-invdyn.hpp
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.
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
24namespace crocoddyl {
25
41template <typename _Scalar>
43 : public DifferentialActionModelAbstractTpl<_Scalar> {
44 public:
45 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
46
47 typedef _Scalar Scalar;
58 typedef typename MathBase::VectorXs VectorXs;
59
71 std::shared_ptr<StateMultibody> state,
72 std::shared_ptr<ActuationModelAbstract> actuation,
73 std::shared_ptr<CostModelSum> costs);
74
84 std::shared_ptr<StateMultibody> state,
85 std::shared_ptr<ActuationModelAbstract> actuation,
86 std::shared_ptr<CostModelSum> costs,
87 std::shared_ptr<ConstraintModelManager> constraints);
89
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
109 virtual void calc(const std::shared_ptr<DifferentialActionDataAbstract>& data,
110 const Eigen::Ref<const VectorXs>& x);
111
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
134 virtual void calcDiff(
135 const std::shared_ptr<DifferentialActionDataAbstract>& data,
136 const Eigen::Ref<const VectorXs>& x);
137
143 virtual std::shared_ptr<DifferentialActionDataAbstract> createData();
144
149 virtual bool checkData(
150 const std::shared_ptr<DifferentialActionDataAbstract>& data);
151
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
173 virtual std::size_t get_ng() const;
174
178 virtual std::size_t get_nh() const;
179
183 virtual std::size_t get_ng_T() const;
184
188 virtual std::size_t get_nh_T() const;
189
193 virtual const VectorXs& get_g_lb() const;
194
198 virtual const VectorXs& get_g_ub() const;
199
203 const std::shared_ptr<ActuationModelAbstract>& get_actuation() const;
204
208 const std::shared_ptr<CostModelSum>& get_costs() const;
209
213 const std::shared_ptr<ConstraintModelManager>& get_constraints() const;
214
218 pinocchio::ModelTpl<Scalar>& get_pinocchio() const;
219
225 virtual void print(std::ostream& os) const;
226
227 protected:
228 using Base::g_lb_;
229 using Base::g_ub_;
230 using Base::ng_;
231 using Base::nh_;
232 using Base::nu_;
233 using Base::state_;
234
235 private:
236 void init(const std::shared_ptr<StateMultibody>& state);
237 std::shared_ptr<ActuationModelAbstract> actuation_;
238 std::shared_ptr<CostModelSum> costs_;
239 std::shared_ptr<ConstraintModelManager> constraints_;
240 pinocchio::ModelTpl<Scalar>& pinocchio_;
241
242 public:
256 public:
257 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
258
259 typedef _Scalar Scalar;
266 typedef typename MathBase::VectorXs VectorXs;
267 typedef typename MathBase::MatrixXs MatrixXs;
268
275 ResidualModelActuation(std::shared_ptr<StateMultibody> state,
276 const std::size_t nu)
277 : Base(state, state->get_nv() - nu, state->get_nv(), true, true, true),
278 na_(nu) {}
279 virtual ~ResidualModelActuation() {}
280
288 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 static_cast<typename Data::ResidualDataActuation*>(data.get());
293 // Update the under-actuation set and residual
294 std::size_t nrow = 0;
295 for (std::size_t k = 0;
296 k < static_cast<std::size_t>(d->actuation->tau_set.size()); ++k) {
297 if (!d->actuation->tau_set[k]) {
298 data->r(nrow) = d->pinocchio->tau(k);
299 nrow += 1;
300 }
301 }
302 }
303
308 virtual void calc(const std::shared_ptr<ResidualDataAbstract>& data,
309 const Eigen::Ref<const VectorXs>&) {
310 data->r.setZero();
311 }
312
320 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 static_cast<typename Data::ResidualDataActuation*>(data.get());
325 std::size_t nrow = 0;
326 const std::size_t nv = state_->get_nv();
327 d->dtau_dx.leftCols(nv) = d->pinocchio->dtau_dq;
328 d->dtau_dx.rightCols(nv) = d->pinocchio->dtau_dv;
329 d->dtau_dx -= d->actuation->dtau_dx;
330 for (std::size_t k = 0;
331 k < static_cast<std::size_t>(d->actuation->tau_set.size()); ++k) {
332 if (!d->actuation->tau_set[k]) {
333 d->Rx.row(nrow) = d->dtau_dx.row(k);
334 d->Ru.row(nrow) = d->pinocchio->M.row(k);
335 nrow += 1;
336 }
337 }
338 }
339
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
356 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 this, data);
361 }
362
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_;
376 using Base::nu_;
377 using Base::state_;
378 };
379};
380
381template <typename _Scalar>
383 : public DifferentialActionDataAbstractTpl<_Scalar> {
384 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
385 typedef _Scalar Scalar;
393 typedef typename MathBase::VectorXs VectorXs;
394
395 template <template <typename Scalar> class Model>
396 explicit DifferentialActionDataFreeInvDynamicsTpl(Model<Scalar>* const model)
397 : Base(model),
398 pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
399 multibody(
400 &pinocchio, model->get_actuation()->createData(),
401 std::make_shared<JointDataAbstract>(
402 model->get_state(), model->get_actuation(), model->get_nu())),
403 costs(model->get_costs()->createData(&multibody)),
404 constraints(model->get_constraints()->createData(&multibody)),
405 tmp_xstatic(model->get_state()->get_nx()) {
406 const std::size_t nv = model->get_state()->get_nv();
407 Fu.leftCols(nv).diagonal().setOnes();
408 multibody.joint->da_du.leftCols(nv).diagonal().setOnes();
409 costs->shareMemory(this);
410 constraints->shareMemory(this);
411 tmp_xstatic.setZero();
412 }
413
414 pinocchio::DataTpl<Scalar> pinocchio;
416 std::shared_ptr<CostDataSum> costs;
417 std::shared_ptr<ConstraintDataManager> constraints;
418 VectorXs
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
432 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
433
434 typedef _Scalar Scalar;
440 typedef typename MathBase::MatrixXs MatrixXs;
441
442 template <template <typename Scalar> class Model>
443 ResidualDataActuation(Model<Scalar>* const model,
444 DataCollectorAbstract* const data)
445 : Base(model, data),
446 dtau_dx(model->get_state()->get_nv(), model->get_state()->get_ndx()) {
447 dtau_dx.setZero();
448 // Check that proper shared data has been passed
450 dynamic_cast<DataCollectorActMultibody*>(shared);
451 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 pinocchio = d->pinocchio;
459 actuation = d->actuation;
460 }
461
462 pinocchio::DataTpl<Scalar>* pinocchio;
463 std::shared_ptr<ActuationDataAbstract> actuation;
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_
Abstract class for the actuation-mapping model.
Manage the individual constraint models.
Residual-based constraint.
Definition residual.hpp:47
Summation of individual cost models.
Definition cost-sum.hpp:73
Abstract class for differential action model.
std::shared_ptr< StateAbstract > state_
Model of the state.
VectorXs g_ub_
Lower bound of the inequality constraints.
std::size_t nh_
Number of equality constraints.
VectorXs g_lb_
Lower bound of the inequality constraints.
std::size_t ng_
Number of inequality constraints.
ResidualModelActuation(std::shared_ptr< StateMultibody > state, const std::size_t nu)
Initialize the actuation residual model.
virtual void calcDiff(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &)
Compute the derivatives of the actuation residual.
virtual void print(std::ostream &os) const
Print relevant information of the actuation residual model.
virtual void calc(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &)
Compute the actuation residual.
virtual void calc(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &)
Compute the residual vector for nodes that depends only on the state.
virtual std::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the actuation residual data.
virtual void calcDiff(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &)
Differential action model for free inverse dynamics in multibody systems.
const std::shared_ptr< ConstraintModelManager > & get_constraints() const
Return the constraint model manager.
virtual std::size_t get_ng() const
Return the number of inequality constraints.
virtual const VectorXs & get_g_lb() const
Return the lower bound of the inequality constraints.
virtual std::size_t get_nh() const
Return the number of equality constraints.
virtual void print(std::ostream &os) const
Print relevant information of the free inverse-dynamics model.
virtual const VectorXs & get_g_ub() const
Return the upper bound of the inequality constraints.
virtual void calcDiff(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the derivatives of the dynamics, cost and constraint functions.
DifferentialActionModelFreeInvDynamicsTpl(std::shared_ptr< StateMultibody > state, std::shared_ptr< ActuationModelAbstract > actuation, std::shared_ptr< CostModelSum > costs)
Initialize the free inverse-dynamics action model.
const std::shared_ptr< CostModelSum > & get_costs() const
Return the cost model.
virtual std::shared_ptr< DifferentialActionDataAbstract > createData()
Create the free inverse-dynamics data.
virtual void calc(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the system acceleration, cost value and constraint residuals.
virtual std::size_t get_nh_T() const
Return the number of equality terminal constraints.
DifferentialActionModelFreeInvDynamicsTpl(std::shared_ptr< StateMultibody > state, std::shared_ptr< ActuationModelAbstract > actuation, std::shared_ptr< CostModelSum > costs, std::shared_ptr< ConstraintModelManager > constraints)
Initialize the free inverse-dynamics action model.
virtual bool checkData(const std::shared_ptr< DifferentialActionDataAbstract > &data)
Checks that a specific data belongs to the free inverse-dynamics model.
const std::shared_ptr< ActuationModelAbstract > & get_actuation() const
Return the actuation model.
virtual void quasiStatic(const std::shared_ptr< DifferentialActionDataAbstract > &data, Eigen::Ref< VectorXs > u, const Eigen::Ref< const VectorXs > &x, const std::size_t maxiter=100, const Scalar tol=Scalar(1e-9))
Computes the quasic static commands.
virtual void calcDiff(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
virtual std::size_t get_ng_T() const
Return the number of equality terminal constraints.
virtual void calc(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
pinocchio::ModelTpl< Scalar > & get_pinocchio() const
Return the Pinocchio model.
Abstract class for residual models.
std::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
State multibody representation.
Definition multibody.hpp:35
MatrixXs Fx
Jacobian of the dynamics w.r.t. the state .
MatrixXs Fu
Jacobian of the dynamics w.r.t. the control .
MatrixXs Luu
Hessian of the cost w.r.t. the control .
VectorXs Lx
Jacobian of the cost w.r.t. the state .
MatrixXs Lxx
Hessian of the cost w.r.t. the state .
VectorXs Lu
Jacobian of the cost w.r.t. the control .
MatrixXs Ru
Jacobian of the residual vector with respect the control.
MatrixXs Rx
Jacobian of the residual vector with respect the state.
std::shared_ptr< ActuationDataAbstract > actuation
Actuation data.
DataCollectorAbstract * shared
Shared data allocated by the action model.
MatrixXs Fu
Jacobian of the dynamics w.r.t. the control .
std::shared_ptr< ConstraintDataManager > constraints
Constraints data.
VectorXs tmp_xstatic
State point used for computing the quasi-static input.
DataCollectorJointActMultibody multibody
Multibody data.
pinocchio::DataTpl< Scalar > pinocchio
Pinocchio data.
std::shared_ptr< CostDataSum > costs
Costs data.
MatrixXs Ru
Jacobian of the residual vector with respect the control.
MatrixXs Rx
Jacobian of the residual vector with respect the state.
DataCollectorAbstract * shared
Shared data allocated by the action model.