aligator  0.9.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
expose-kinodynamics.cpp
Go to the documentation of this file.
1
3
5#include <pinocchio/multibody/fwd.hpp>
6#include <proxsuite-nlp/modelling/spaces/multibody.hpp>
7#include <pinocchio/multibody/model.hpp>
9
10namespace aligator {
11namespace python {
13 using namespace aligator::dynamics;
14 using context::Scalar;
19 using ODEAbstract = ODEAbstractTpl<Scalar>;
20 using ContinuousDynamicsAbstract = ContinuousDynamicsAbstractTpl<Scalar>;
21 using KinodynamicsFwdData = KinodynamicsFwdDataTpl<Scalar>;
22 using KinodynamicsFwdDynamics = KinodynamicsFwdDynamicsTpl<Scalar>;
23 using Manifold = proxsuite::nlp::MultibodyPhaseSpace<Scalar>;
24 using Vector3s = typename math_types<Scalar>::Vector3s;
25
26 using Model = pinocchio::ModelTpl<Scalar>;
27
29 ode_visitor;
30
31 bp::class_<KinodynamicsFwdDynamics, bp::bases<ODEAbstract>>(
32 "KinodynamicsFwdDynamics",
33 "Centroidal forward dynamics + kinematics using Pinocchio.",
34 bp::init<const Manifold &, const Model &, const Vector3s &,
35 const std::vector<bool> &,
36 const std::vector<pinocchio::FrameIndex> &, const int>(
37 "Constructor.",
38 bp::args("self", "space", "model", "gravity", "contact_states",
39 "contact_ids", "force_size")))
40 .def_readwrite("contact_states",
41 &KinodynamicsFwdDynamics::contact_states_)
42 .def(ode_visitor);
43
44 bp::register_ptr_to_python<shared_ptr<KinodynamicsFwdData>>();
45
46 bp::class_<KinodynamicsFwdData, bp::bases<ODEData>>("KinodynamicsFwdData",
47 bp::no_init)
48 .def_readwrite("pin_data", &KinodynamicsFwdData::pin_data_);
49}
50} // namespace python
51} // namespace aligator
Namespace for modelling system dynamics.
typename math_types< Scalar >::Vector3s Vector3s
Main package namespace.
Base struct for function data.
Definition fwd.hpp:62
Class representing ternary functions .
Definition fwd.hpp:56
Represents unary functions of the form , with no control (or next-state) arguments.
Definition fwd.hpp:59
Continuous dynamics described by differential-algebraic equations (DAEs) .
Definition fwd.hpp:12
Data struct for ContinuousDynamicsAbstractTpl.
Definition fwd.hpp:15
Nonlinear centroidal and full kinematics forward dynamics.
Base class for ODE dynamics .