aligator 0.17.1
A versatile and efficient C++ library for real-time constrained trajectory optimization.
Loading...
Searching...
No Matches
expose-constrained-fwd.cpp
Go to the documentation of this file.
1
3#ifdef ALIGATOR_WITH_PINOCCHIO
5
9
10namespace aligator {
11namespace python {
12namespace {
13
15 pinocchio::RigidConstraintModelTpl<context::Scalar, 0>;
17 pinocchio::RigidConstraintDataTpl<context::Scalar, 0>;
18
20 PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel);
22 PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData);
23
24} // namespace
25
27 using namespace aligator::dynamics;
30 using context::ODEData;
31 using context::Scalar;
32 using MultibodyConstraintFwdData = MultibodyConstraintFwdDataTpl<Scalar>;
33 using MultibodyConstraintFwdDynamics =
35
37 ode_visitor;
38 bp::class_<MultibodyConstraintFwdDynamics, bp::bases<ODEAbstract>>(
39 "MultibodyConstraintFwdDynamics",
40 "Constraint forward dynamics using Pinocchio.",
41 bp::init<const MultibodyPhaseSpace<Scalar> &, const context::MatrixXs &,
43 const pinocchio::ProximalSettingsTpl<Scalar> &>(
44 ("self"_a, "space", "actuation_matrix", "constraint_models",
45 "prox_settings")))
46 .def(ode_visitor)
47 .def_readwrite("constraint_models",
48 &MultibodyConstraintFwdDynamics::constraint_models_)
49 .add_property("ntau", &MultibodyConstraintFwdDynamics::ntau,
50 "Torque dimension.");
51
52 bp::register_ptr_to_python<shared_ptr<MultibodyConstraintFwdData>>();
53
54 bp::class_<MultibodyConstraintFwdData, bp::bases<ODEData>>(
55 "MultibodyConstraintFwdData", bp::no_init)
56 .def_readwrite("tau", &MultibodyConstraintFwdData::tau_)
57 .def_readwrite("dtau_dx", &MultibodyConstraintFwdData::dtau_dx_)
58 .def_readwrite("dtau_du", &MultibodyConstraintFwdData::dtau_du_)
59 .def_readwrite("pin_data", &MultibodyConstraintFwdData::pin_data_)
60 .def_readwrite("constraint_datas",
61 &MultibodyConstraintFwdData::constraint_datas_);
62}
63} // namespace python
64} // namespace aligator
65
66#endif // ifdef ALIGATOR_WITH_PINOCCHIO
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:7
PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) RigidConstraintModelVector
pinocchio::RigidConstraintModelTpl< context::Scalar, 0 > RigidConstraintModel
PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) RigidConstraintDataVector
pinocchio::RigidConstraintDataTpl< context::Scalar, 0 > RigidConstraintData
Main package namespace.
Constraint multibody forward dynamics, using Pinocchio.