aligator  0.9.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#include <Eigen/LU>
7#include <proxsuite-nlp/modelling/spaces/multibody.hpp>
8#include <pinocchio/multibody/model.hpp>
9
10namespace aligator {
11namespace dynamics {
12template <typename Scalar> struct KinodynamicsFwdDataTpl;
13
28template <typename _Scalar>
30 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
31 using Scalar = _Scalar;
37 using Manifold = proxsuite::nlp::MultibodyPhaseSpace<Scalar>;
38 using Model = pinocchio::ModelTpl<Scalar>;
39 using Matrix3s = Eigen::Matrix<Scalar, 3, 3>;
40
41 using Base::nu_;
42
45 double mass_;
46 Vector3s gravity_;
48
49 std::vector<bool> contact_states_;
50 std::vector<pinocchio::FrameIndex> contact_ids_;
51
52 const Manifold &space() const { return space_; }
53
55 const Manifold &state, const Model &model, const Vector3s &gravity,
56 const std::vector<bool> &contact_states,
57 const std::vector<pinocchio::FrameIndex> &contact_ids,
58 const int force_size);
59
60 void forward(const ConstVectorRef &x, const ConstVectorRef &u,
61 BaseData &data) const;
62 void dForward(const ConstVectorRef &x, const ConstVectorRef &u,
63 BaseData &data) const;
64
65 shared_ptr<ContDataAbstract> createData() const;
66};
67
68template <typename Scalar>
71 using PinData = pinocchio::DataTpl<Scalar>;
72 using VectorXs = typename math_types<Scalar>::VectorXs;
73 using Matrix6Xs = typename math_types<Scalar>::Matrix6Xs;
74 using Matrix3Xs = typename math_types<Scalar>::Matrix3Xs;
75 using Matrix3s = Eigen::Matrix<Scalar, 3, 3>;
76 using Matrix6s = Eigen::Matrix<Scalar, 6, 6>;
77 using Vector6s = Eigen::Matrix<Scalar, 6, 1>;
78
89
93 Eigen::PartialPivLU<Eigen::Matrix<Scalar, 6, 6>> PivLU_;
94
96};
97
98} // namespace dynamics
99} // namespace aligator
100
101#include "aligator/modelling/dynamics/kinodynamics-fwd.hxx"
Main package namespace.
Defines a class representing ODEs.
Data struct for ContinuousDynamicsAbstractTpl.
Definition fwd.hpp:15
typename math_types< Scalar >::Matrix6Xs Matrix6Xs
KinodynamicsFwdDataTpl(const KinodynamicsFwdDynamicsTpl< Scalar > *model)
typename math_types< Scalar >::VectorXs VectorXs
Eigen::PartialPivLU< Eigen::Matrix< Scalar, 6, 6 > > PivLU_
typename math_types< Scalar >::Matrix3Xs Matrix3Xs
Nonlinear centroidal and full kinematics forward dynamics.
proxsuite::nlp::MultibodyPhaseSpace< Scalar > Manifold
void dForward(const ConstVectorRef &x, const ConstVectorRef &u, BaseData &data) const
Evaluate the vector field Jacobians.
std::vector< pinocchio::FrameIndex > contact_ids_
KinodynamicsFwdDynamicsTpl(const Manifold &state, const Model &model, const Vector3s &gravity, const std::vector< bool > &contact_states, const std::vector< pinocchio::FrameIndex > &contact_ids, const int force_size)
void forward(const ConstVectorRef &x, const ConstVectorRef &u, BaseData &data) const
Evaluate the ODE vector field: this returns the value of .
shared_ptr< ContDataAbstract > createData() const
Create a data holder instance.
Base class for ODE dynamics .