aligator 0.18.0
A versatile and efficient C++ library for real-time constrained trajectory optimization.
Loading...
Searching...
No Matches
expose-freefwd.cpp
Go to the documentation of this file.
1
2#ifdef ALIGATOR_WITH_PINOCCHIO
3
4// Boost.Python 1.74 include manually mpl/vector/vector20.hpp
5// that prevent us to define mpl::list and mpl::vector with
6// the right size.
7// To avoid this issue this header should be included first.
8#include <pinocchio/fwd.hpp>
9
13
15
16namespace aligator {
17namespace python {
19 using namespace aligator::dynamics;
20 using context::Scalar;
24 using MultibodyFreeFwdData = MultibodyFreeFwdDataTpl<Scalar>;
25 using MultibodyFreeFwdDynamics = MultibodyFreeFwdDynamicsTpl<Scalar>;
27
29 ode_visitor;
30
31 bp::class_<MultibodyFreeFwdDynamics, bp::bases<ODEAbstract>>(
32 "MultibodyFreeFwdDynamics",
33 "Free-space forward dynamics on multibodies using Pinocchio's ABA "
34 "algorithm.",
35 bp::init<MultibodyPhaseSpace, const context::MatrixXs &>(
36 "Constructor where the actuation matrix is provided.",
37 ("self"_a, "space", "actuation_matrix")))
38 .def(bp::init<MultibodyPhaseSpace>(
39 "Constructor without actuation matrix (assumed to be the (nu,nu) "
40 "identity matrix).",
41 ("self"_a, "space")))
42 .add_property("ntau", &MultibodyFreeFwdDynamics::ntau,
43 "Torque dimension.")
44 .add_property(
45 "isUnderactuated", &MultibodyFreeFwdDynamics::isUnderactuated,
46 "Whether the system is underactuated, i.e. if the actuation matrix "
47 "rank is lower than the acceleration vector's dimension.")
48 .add_property("actuationMatrixRank",
49 &MultibodyFreeFwdDynamics::getActuationMatrixRank,
50 "Get the rank of the actuation matrix.")
51 .def(ode_visitor);
52
53 bp::register_ptr_to_python<shared_ptr<MultibodyFreeFwdData>>();
54
55 bp::class_<MultibodyFreeFwdData, bp::bases<ODEData>>("MultibodyFreeFwdData",
56 bp::no_init)
57 .def_readwrite("tau", &MultibodyFreeFwdData::tau_)
58 .def_readwrite("dtau_dx", &MultibodyFreeFwdData::dtau_dx_)
59 .def_readwrite("dtau_du", &MultibodyFreeFwdData::dtau_du_)
60 .def_readwrite("pin_data", &MultibodyFreeFwdData::pin_data_);
61}
62} // namespace python
63} // namespace aligator
64#endif
dynamics::ContinuousDynamicsDataTpl< Scalar > ODEData
Definition context.hpp:16
dynamics::ContinuousDynamicsAbstractTpl< Scalar > ContinuousDynamicsAbstract
Definition context.hpp:9
MultibodyPhaseSpace< Scalar > MultibodyPhaseSpace
Definition fwd.hpp:27
dynamics::ODEAbstractTpl< Scalar > ODEAbstract
Definition context.hpp:14
Namespace for modelling system dynamics.
The Python bindings.
Definition blk-matrix.hpp:7
Main package namespace.
Continuous dynamics described by differential-algebraic equations (DAEs) .
Data struct for ContinuousDynamicsAbstractTpl.
Free-space multibody forward dynamics, using Pinocchio.
Base class for ODE dynamics .