aligator  0.9.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
4
7
8namespace aligator {
9namespace python {
11 using namespace aligator::dynamics;
12 using context::Scalar;
14 using ODEAbstract = ODEAbstractTpl<Scalar>;
15 using ContinuousDynamicsAbstract = ContinuousDynamicsAbstractTpl<Scalar>;
16 using MultibodyFreeFwdData = MultibodyFreeFwdDataTpl<Scalar>;
17 using MultibodyFreeFwdDynamics = MultibodyFreeFwdDynamicsTpl<Scalar>;
18 using proxsuite::nlp::MultibodyPhaseSpace;
19
20 using StateManifold = MultibodyPhaseSpace<Scalar>;
21
23 ode_visitor;
24
25 bp::class_<MultibodyFreeFwdDynamics, bp::bases<ODEAbstract>>(
26 "MultibodyFreeFwdDynamics",
27 "Free-space forward dynamics on multibodies using Pinocchio's ABA "
28 "algorithm.",
29 bp::init<StateManifold, const context::MatrixXs &>(
30 "Constructor where the actuation matrix is provided.",
31 ("self"_a, "space", "actuation_matrix")))
32 .def(bp::init<StateManifold>(
33 "Constructor without actuation matrix (assumed to be the (nu,nu) "
34 "identity matrix).",
35 ("self"_a, "space")))
36 .add_property("ntau", &MultibodyFreeFwdDynamics::ntau,
37 "Torque dimension.")
38 .add_property(
39 "isUnderactuated", &MultibodyFreeFwdDynamics::isUnderactuated,
40 "Whether the system is underactuated, i.e. if the actuation matrix "
41 "rank is lower than the acceleration vector's dimension.")
42 .add_property("actuationMatrixRank",
43 &MultibodyFreeFwdDynamics::getActuationMatrixRank,
44 "Get the rank of the actuation matrix.")
45 .def(ode_visitor);
46
47 bp::register_ptr_to_python<shared_ptr<MultibodyFreeFwdData>>();
48
49 bp::class_<MultibodyFreeFwdData, bp::bases<ODEData>>("MultibodyFreeFwdData",
50 bp::no_init)
51 .def_readwrite("tau", &MultibodyFreeFwdData::tau_)
52 .def_readwrite("dtau_dx", &MultibodyFreeFwdData::dtau_dx_)
53 .def_readwrite("dtau_du", &MultibodyFreeFwdData::dtau_du_)
54 .def_readwrite("pin_data", &MultibodyFreeFwdData::pin_data_);
55}
56} // namespace python
57} // namespace aligator
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
Free-space multibody forward dynamics, using Pinocchio.
Base class for ODE dynamics .