aligator  0.6.1
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>
8
9namespace aligator {
10namespace python {
12 using namespace aligator::dynamics;
13 using context::Scalar;
17 using ODEData = ODEDataTpl<Scalar>;
18 using ODEAbstract = ODEAbstractTpl<Scalar>;
19 using KinodynamicsFwdData = KinodynamicsFwdDataTpl<Scalar>;
20 using KinodynamicsFwdDynamics = KinodynamicsFwdDynamicsTpl<Scalar>;
21 using Manifold = proxsuite::nlp::MultibodyPhaseSpace<Scalar>;
22 using ManifoldPtr = shared_ptr<Manifold>;
23 using Vector3s = typename math_types<Scalar>::Vector3s;
24
25 using Model = pinocchio::ModelTpl<Scalar>;
26
27 bp::class_<KinodynamicsFwdDynamics, bp::bases<ODEAbstract>>(
28 "KinodynamicsFwdDynamics",
29 "Centroidal forward dynamics + kinematics using Pinocchio.",
30 bp::init<const ManifoldPtr &, const Model &, const Vector3s &,
31 const std::vector<bool> &,
32 const std::vector<pinocchio::FrameIndex> &, const int>(
33 "Constructor.",
34 bp::args("self", "space", "model", "gravity", "contact_states",
35 "contact_ids", "force_size")))
36 .def_readwrite("contact_states",
37 &KinodynamicsFwdDynamics::contact_states_);
38
39 bp::register_ptr_to_python<shared_ptr<KinodynamicsFwdData>>();
40
41 bp::class_<KinodynamicsFwdData, bp::bases<ODEData>>("KinodynamicsFwdData",
42 bp::no_init)
43 .def_readwrite("pin_data", &KinodynamicsFwdData::pin_data_);
44}
45} // namespace python
46} // namespace aligator
Namespace for modelling system dynamics.
typename math_types< Scalar >::Vector3s Vector3s
shared_ptr< Manifold > ManifoldPtr
Main package namespace.