aligator  0.10.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
expose-freefwd.cpp
Go to the documentation of this file.
1
2#ifdef ALIGATOR_WITH_PINOCCHIO
5
8
9namespace aligator {
10namespace python {
11void exposeFreeFwdDynamics() {
12 using namespace aligator::dynamics;
13 using context::Scalar;
17 using MultibodyFreeFwdData = MultibodyFreeFwdDataTpl<Scalar>;
18 using MultibodyFreeFwdDynamics = MultibodyFreeFwdDynamicsTpl<Scalar>;
19 using proxsuite::nlp::MultibodyPhaseSpace;
20
21 using StateManifold = MultibodyPhaseSpace<Scalar>;
22
23 PolymorphicMultiBaseVisitor<ODEAbstract, ContinuousDynamicsAbstract>
24 ode_visitor;
25
26 bp::class_<MultibodyFreeFwdDynamics, bp::bases<ODEAbstract>>(
27 "MultibodyFreeFwdDynamics",
28 "Free-space forward dynamics on multibodies using Pinocchio's ABA "
29 "algorithm.",
30 bp::init<StateManifold, const context::MatrixXs &>(
31 "Constructor where the actuation matrix is provided.",
32 ("self"_a, "space", "actuation_matrix")))
33 .def(bp::init<StateManifold>(
34 "Constructor without actuation matrix (assumed to be the (nu,nu) "
35 "identity matrix).",
36 ("self"_a, "space")))
37 .add_property("ntau", &MultibodyFreeFwdDynamics::ntau,
38 "Torque dimension.")
39 .add_property(
40 "isUnderactuated", &MultibodyFreeFwdDynamics::isUnderactuated,
41 "Whether the system is underactuated, i.e. if the actuation matrix "
42 "rank is lower than the acceleration vector's dimension.")
43 .add_property("actuationMatrixRank",
44 &MultibodyFreeFwdDynamics::getActuationMatrixRank,
45 "Get the rank of the actuation matrix.")
46 .def(ode_visitor);
47
48 bp::register_ptr_to_python<shared_ptr<MultibodyFreeFwdData>>();
49
50 bp::class_<MultibodyFreeFwdData, bp::bases<ODEData>>("MultibodyFreeFwdData",
51 bp::no_init)
52 .def_readwrite("tau", &MultibodyFreeFwdData::tau_)
53 .def_readwrite("dtau_dx", &MultibodyFreeFwdData::dtau_dx_)
54 .def_readwrite("dtau_du", &MultibodyFreeFwdData::dtau_du_)
55 .def_readwrite("pin_data", &MultibodyFreeFwdData::pin_data_);
56}
57} // namespace python
58} // namespace aligator
59#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.
Main package namespace.
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 .