aligator  0.10.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
expose-constraintfwd.cpp
Go to the documentation of this file.
1
4
5#ifdef ALIGATOR_PINOCCHIO_V3
6
10
11namespace aligator {
12namespace python {
13namespace {
14
15using RigidConstraintModel =
16 pinocchio::RigidConstraintModelTpl<context::Scalar, 0>;
17using RigidConstraintData =
18 pinocchio::RigidConstraintDataTpl<context::Scalar, 0>;
19
20using RigidConstraintModelVector =
21 PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel);
22using RigidConstraintDataVector =
23 PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData);
24
25} // namespace
26
27void exposeConstrainedFwdDynamics() {
28 using namespace aligator::dynamics;
31 using context::ODEData;
32 using context::Scalar;
33 using MultibodyConstraintFwdData = MultibodyConstraintFwdDataTpl<Scalar>;
34 using MultibodyConstraintFwdDynamics =
36
37 PolymorphicMultiBaseVisitor<ODEAbstract, ContinuousDynamicsAbstract>
38 ode_visitor;
39 bp::class_<MultibodyConstraintFwdDynamics, bp::bases<ODEAbstract>>(
40 "MultibodyConstraintFwdDynamics",
41 "Constraint forward dynamics using Pinocchio.",
42 bp::init<const proxsuite::nlp::MultibodyPhaseSpace<Scalar> &,
43 const context::MatrixXs &, const RigidConstraintModelVector &,
44 const pinocchio::ProximalSettingsTpl<Scalar> &>(
45 ("self"_a, "space", "actuation_matrix", "constraint_models",
46 "prox_settings")))
47 .def(ode_visitor)
48 .def_readwrite("constraint_models",
49 &MultibodyConstraintFwdDynamics::constraint_models_)
50 .add_property("ntau", &MultibodyConstraintFwdDynamics::ntau,
51 "Torque dimension.");
52
53 bp::register_ptr_to_python<shared_ptr<MultibodyConstraintFwdData>>();
54
55 bp::class_<MultibodyConstraintFwdData, bp::bases<ODEData>>(
56 "MultibodyConstraintFwdData", bp::no_init)
57 .def_readwrite("tau", &MultibodyConstraintFwdData::tau_)
58 .def_readwrite("dtau_dx", &MultibodyConstraintFwdData::dtau_dx_)
59 .def_readwrite("dtau_du", &MultibodyConstraintFwdData::dtau_du_)
60 .def_readwrite("pin_data", &MultibodyConstraintFwdData::pin_data_)
61 .def_readwrite("constraint_datas",
62 &MultibodyConstraintFwdData::constraint_datas_);
63}
64} // namespace python
65} // namespace aligator
66
67#endif
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
Constraint multibody forward dynamics, using Pinocchio.
Base class for ODE dynamics .