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>
13void exposeKinodynamics() {
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;
27 using Model = pinocchio::ModelTpl<Scalar>;
29 const PolymorphicMultiBaseVisitor<ODEAbstract, ContinuousDynamicsAbstract>
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>(
39 bp::args(
"self",
"space",
"model",
"gravity",
"contact_states",
40 "contact_ids",
"force_size")))
41 .def_readwrite(
"contact_states",
42 &KinodynamicsFwdDynamics::contact_states_)
45 bp::register_ptr_to_python<shared_ptr<KinodynamicsFwdData>>();
47 bp::class_<KinodynamicsFwdData, bp::bases<ODEData>>(
"KinodynamicsFwdData",
49 .def_readwrite(
"pin_data", &KinodynamicsFwdData::pin_data_);
dynamics::ContinuousDynamicsDataTpl< Scalar > ODEData
dynamics::ContinuousDynamicsAbstractTpl< Scalar > ContinuousDynamicsAbstract
dynamics::ODEAbstractTpl< Scalar > ODEAbstract
Namespace for modelling system dynamics.
typename math_types< Scalar >::Vector3s Vector3s
Base struct for function data.
Class representing ternary functions .
Represents unary functions of the form , with no control (or next-state) arguments.
Continuous dynamics described by differential-algebraic equations (DAEs) .
Data struct for ContinuousDynamicsAbstractTpl.
Base class for ODE dynamics .