aligator  0.10.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
kinodynamics-fwd.hpp
Go to the documentation of this file.
1
2#pragma once
3
5
6#ifdef PROXSUITE_NLP_WITH_PINOCCHIO
7
8#include <Eigen/LU>
9#include <proxsuite-nlp/modelling/spaces/multibody.hpp>
10#include <pinocchio/multibody/model.hpp>
11
12namespace aligator {
13namespace dynamics {
14template <typename Scalar> struct KinodynamicsFwdDataTpl;
15
30template <typename _Scalar>
31struct KinodynamicsFwdDynamicsTpl : ODEAbstractTpl<_Scalar> {
32 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
33 using Scalar = _Scalar;
35 using Base = ODEAbstractTpl<Scalar>;
36 using BaseData = ContinuousDynamicsDataTpl<Scalar>;
37 using ContDataAbstract = ContinuousDynamicsDataTpl<Scalar>;
38 using Data = KinodynamicsFwdDataTpl<Scalar>;
39 using Manifold = proxsuite::nlp::MultibodyPhaseSpace<Scalar>;
40 using Model = pinocchio::ModelTpl<Scalar>;
41 using Matrix3s = Eigen::Matrix<Scalar, 3, 3>;
42
43 using Base::nu_;
44
45 Manifold space_;
46 Model pin_model_;
47 double mass_;
48 Vector3s gravity_;
49 int force_size_;
50
51 std::vector<bool> contact_states_;
52 std::vector<pinocchio::FrameIndex> contact_ids_;
53
54 const Manifold &space() const { return space_; }
55
56 KinodynamicsFwdDynamicsTpl(
57 const Manifold &state, const Model &model, const Vector3s &gravity,
58 const std::vector<bool> &contact_states,
59 const std::vector<pinocchio::FrameIndex> &contact_ids,
60 const int force_size);
61
62 void forward(const ConstVectorRef &x, const ConstVectorRef &u,
63 BaseData &data) const;
64 void dForward(const ConstVectorRef &x, const ConstVectorRef &u,
65 BaseData &data) const;
66
67 shared_ptr<ContDataAbstract> createData() const;
68};
69
70template <typename Scalar>
71struct KinodynamicsFwdDataTpl : ContinuousDynamicsDataTpl<Scalar> {
72 using Base = ContinuousDynamicsDataTpl<Scalar>;
73 using PinData = pinocchio::DataTpl<Scalar>;
74 using VectorXs = typename math_types<Scalar>::VectorXs;
75 using Matrix6Xs = typename math_types<Scalar>::Matrix6Xs;
76 using Matrix3Xs = typename math_types<Scalar>::Matrix3Xs;
77 using Matrix3s = Eigen::Matrix<Scalar, 3, 3>;
78 using Matrix6s = Eigen::Matrix<Scalar, 6, 6>;
79 using Vector6s = Eigen::Matrix<Scalar, 6, 1>;
80
81 PinData pin_data_;
82 Matrix6Xs dh_dq_;
83 Matrix6Xs dhdot_dq_;
84 Matrix6Xs dhdot_dv_;
85 Matrix6Xs dhdot_da_;
86 Matrix6Xs temp1_;
87 Matrix3Xs temp2_;
88 Matrix6Xs fJf_;
89 VectorXs v0_;
90 VectorXs a0_;
91
92 Vector6s cforces_;
93 Matrix3s Jtemp_;
94 Matrix6s Agu_inv_;
95 Eigen::PartialPivLU<Eigen::Matrix<Scalar, 6, 6>> PivLU_;
96
97 KinodynamicsFwdDataTpl(const KinodynamicsFwdDynamicsTpl<Scalar> *model);
98};
99
100} // namespace dynamics
101} // namespace aligator
102
103#include "aligator/modelling/dynamics/kinodynamics-fwd.hxx"
104#endif
#define ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
Definition math.hpp:8
pinocchio::DataTpl< Scalar, Options > PinData
Definition context.hpp:10
typename math_types< Scalar >::Vector3s Vector3s
Main package namespace.
Defines a class representing ODEs.