aligator  0.10.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
4#ifdef PROXSUITE_NLP_WITH_PINOCCHIO
6#include <pinocchio/multibody/fwd.hpp>
7#include <proxsuite-nlp/modelling/spaces/multibody.hpp>
8#include <pinocchio/multibody/model.hpp>
10
11namespace aligator {
12namespace python {
13void exposeKinodynamics() {
14 using namespace aligator::dynamics;
15 using context::Scalar;
22 using KinodynamicsFwdData = KinodynamicsFwdDataTpl<Scalar>;
23 using KinodynamicsFwdDynamics = KinodynamicsFwdDynamicsTpl<Scalar>;
24 using Manifold = proxsuite::nlp::MultibodyPhaseSpace<Scalar>;
25 using Vector3s = typename math_types<Scalar>::Vector3s;
26
27 using Model = pinocchio::ModelTpl<Scalar>;
28
29 const PolymorphicMultiBaseVisitor<ODEAbstract, ContinuousDynamicsAbstract>
30 ode_visitor;
31
32 bp::class_<KinodynamicsFwdDynamics, bp::bases<ODEAbstract>>(
33 "KinodynamicsFwdDynamics",
34 "Centroidal forward dynamics + kinematics using Pinocchio.",
35 bp::init<const Manifold &, const Model &, const Vector3s &,
36 const std::vector<bool> &,
37 const std::vector<pinocchio::FrameIndex> &, const int>(
38 "Constructor.",
39 bp::args("self", "space", "model", "gravity", "contact_states",
40 "contact_ids", "force_size")))
41 .def_readwrite("contact_states",
42 &KinodynamicsFwdDynamics::contact_states_)
43 .def(ode_visitor);
44
45 bp::register_ptr_to_python<shared_ptr<KinodynamicsFwdData>>();
46
47 bp::class_<KinodynamicsFwdData, bp::bases<ODEData>>("KinodynamicsFwdData",
48 bp::no_init)
49 .def_readwrite("pin_data", &KinodynamicsFwdData::pin_data_);
50}
51} // namespace python
52} // namespace aligator
53#endif
dynamics::ContinuousDynamicsDataTpl< Scalar > ODEData
Definition context.hpp:16
dynamics::ContinuousDynamicsAbstractTpl< Scalar > ContinuousDynamicsAbstract
Definition context.hpp:9
dynamics::ODEAbstractTpl< Scalar > ODEAbstract
Definition context.hpp:14
Namespace for modelling system dynamics.
typename math_types< Scalar >::Vector3s Vector3s
Main package namespace.
Base struct for function data.
Definition fwd.hpp:59
Class representing ternary functions .
Definition fwd.hpp:53
Represents unary functions of the form , with no control (or next-state) arguments.
Definition fwd.hpp:56
Continuous dynamics described by differential-algebraic equations (DAEs) .
Definition fwd.hpp:12
Data struct for ContinuousDynamicsAbstractTpl.
Definition fwd.hpp:15
Base class for ODE dynamics .