aligator  0.14.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
 
Loading...
Searching...
No Matches
expose-constrained-fwd.cpp
Go to the documentation of this file.
1
4
8
9namespace aligator {
10namespace python {
11namespace {
12
13using RigidConstraintModel =
14 pinocchio::RigidConstraintModelTpl<context::Scalar, 0>;
15using RigidConstraintData =
16 pinocchio::RigidConstraintDataTpl<context::Scalar, 0>;
17
18using RigidConstraintModelVector =
19 PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel);
20using RigidConstraintDataVector =
21 PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData);
22
23} // namespace
24
26 using namespace aligator::dynamics;
29 using context::ODEData;
30 using context::Scalar;
31 using MultibodyConstraintFwdData = MultibodyConstraintFwdDataTpl<Scalar>;
32 using MultibodyConstraintFwdDynamics =
34
36 ode_visitor;
37 bp::class_<MultibodyConstraintFwdDynamics, bp::bases<ODEAbstract>>(
38 "MultibodyConstraintFwdDynamics",
39 "Constraint forward dynamics using Pinocchio.",
40 bp::init<const MultibodyPhaseSpace<Scalar> &, const context::MatrixXs &,
41 const RigidConstraintModelVector &,
42 const pinocchio::ProximalSettingsTpl<Scalar> &>(
43 ("self"_a, "space", "actuation_matrix", "constraint_models",
44 "prox_settings")))
45 .def(ode_visitor)
46 .def_readwrite("constraint_models",
47 &MultibodyConstraintFwdDynamics::constraint_models_)
48 .add_property("ntau", &MultibodyConstraintFwdDynamics::ntau,
49 "Torque dimension.");
50
51 bp::register_ptr_to_python<shared_ptr<MultibodyConstraintFwdData>>();
52
53 bp::class_<MultibodyConstraintFwdData, bp::bases<ODEData>>(
54 "MultibodyConstraintFwdData", bp::no_init)
55 .def_readwrite("tau", &MultibodyConstraintFwdData::tau_)
56 .def_readwrite("dtau_dx", &MultibodyConstraintFwdData::dtau_dx_)
57 .def_readwrite("dtau_du", &MultibodyConstraintFwdData::dtau_du_)
58 .def_readwrite("pin_data", &MultibodyConstraintFwdData::pin_data_)
59 .def_readwrite("constraint_datas",
60 &MultibodyConstraintFwdData::constraint_datas_);
61}
62} // namespace python
63} // namespace aligator
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.
The Python bindings.
Definition blk-matrix.hpp:5
Main package namespace.
Constraint multibody forward dynamics, using Pinocchio.