aligator 0.17.1
A versatile and efficient C++ library for real-time constrained trajectory optimization.
Loading...
Searching...
No Matches
expose-pinocchio-manifolds.cpp
Go to the documentation of this file.
1#ifdef ALIGATOR_WITH_PINOCCHIO
4
7
8namespace aligator::python {
10using context::Scalar;
11using PolyManifold = xyz::polymorphic<Manifold>;
12
15template <typename LieGroup>
16void exposeLieGroup(const char *name, const char *docstring) {
17 bp::class_<PinocchioLieGroup<LieGroup>, bp::bases<Manifold>>(
18 name, docstring, bp::init<>("self"_a))
20 .enable_pickling_(true);
21}
22
24template <typename M>
25bp::class_<TangentBundleTpl<M>, bp::bases<Manifold>>
26exposeTangentBundle(const char *name, const char *docstring) {
27 using OutType = TangentBundleTpl<M>;
28 return bp::class_<OutType, bp::bases<Manifold>>(
29 name, docstring, bp::init<const M &>(("self"_a, "base")))
30 .add_property("base",
31 bp::make_function(&OutType::getBaseSpace,
32 bp::return_internal_reference<>()),
33 "Get the base space.")
35}
36
38template <typename M, class Init>
39bp::class_<TangentBundleTpl<M>, bp::bases<Manifold>>
40exposeTangentBundle(const char *name, const char *docstring, Init init) {
41 return exposeTangentBundle<M>(name, docstring).def(init);
42}
43
45 bp::scope scope = get_namespace("manifolds");
46
47 namespace pin = pinocchio;
48 using pin::ModelTpl;
49 using pin::SpecialEuclideanOperationTpl;
50 using pin::SpecialOrthogonalOperationTpl;
51 using pin::VectorSpaceOperationTpl;
52
53 using DynSizeEuclideanSpace = VectorSpaceOperationTpl<Eigen::Dynamic, Scalar>;
54 bp::class_<PinocchioLieGroup<DynSizeEuclideanSpace>, bp::bases<Manifold>>(
55 "EuclideanSpace", "Pinocchio's n-dimensional Euclidean vector space.",
56 bp::no_init)
57 .def(bp::init<int>(("self"_a, "dim")))
59
61 "R", "One-dimensional Euclidean space AKA real number line.");
63 "R2", "Two-dimensional Euclidean space.");
65 "R3", "Three-dimensional Euclidean space.");
67 "R4", "Four-dimensional Euclidean space.");
69 "SO2", "SO(2) special orthogonal group.");
71 "SO3", "SO(3) special orthogonal group.");
73 "SE2", "SE(2) special Euclidean group.");
75 "SE3", "SE(3) special Euclidean group.");
76
81
82 /* Expose tangent bundles */
83
84 exposeTangentBundle<SO2>("TSO2", "Tangent bundle of the SO(2) group.")
85 .def(bp::init<>(bp::args("self")));
86 exposeTangentBundle<SO3>("TSO3", "Tangent bundle of the SO(3) group.")
87 .def(bp::init<>(bp::args("self")));
88 exposeTangentBundle<SE2>("TSE2", "Tangent bundle of the SE(2) group.")
89 .def(bp::init<>(bp::args("self")));
90 exposeTangentBundle<SE3>("TSE3", "Tangent bundle of the SE(3) group.")
91 .def(bp::init<>(bp::args("self")));
92
93 /* Groups associated w/ Pinocchio models */
94 using Multibody = MultibodyConfiguration<Scalar>;
95 using Model = ModelTpl<Scalar>;
96 bp::class_<Multibody, bp::bases<Manifold>>(
97 "MultibodyConfiguration", "Configuration group of a multibody",
98 bp::init<const Model &>(bp::args("self", "model")))
99 .add_property("model",
100 bp::make_function(&Multibody::getModel,
101 bp::return_internal_reference<>()),
102 "Return the Pinocchio model instance.")
104 .enable_pickling_(true);
105
106 using MultiPhase = MultibodyPhaseSpace<Scalar>;
107 bp::class_<MultiPhase, bp::bases<Manifold>>(
108 "MultibodyPhaseSpace",
109 "Tangent space of the multibody configuration group.",
110 bp::init<const Model &>(("self"_a, "model")))
111 .add_property("model",
112 bp::make_function(&MultiPhase::getModel,
113 bp::return_internal_reference<>()),
114 "Return the Pinocchio model instance.")
115 .add_property("base", bp::make_function(
116 +[](const MultiPhase &m) -> const Multibody & {
117 return m.getBaseSpace();
118 },
119 bp::return_internal_reference<>()))
121 .enable_pickling_(true);
122}
123
124} // namespace aligator::python
125
126#endif // ifdef ALIGATOR_WITH_PINOCCHIO
ManifoldAbstractTpl< Scalar > Manifold
Definition context.hpp:14
MultibodyPhaseSpace< Scalar > MultibodyPhaseSpace
Definition fwd.hpp:27
The Python bindings.
Definition blk-matrix.hpp:7
xyz::polymorphic< Manifold > PolyManifold
void exposeLieGroup(const char *name, const char *docstring)
bp::class_< TangentBundleTpl< M >, bp::bases< Manifold > > exposeTangentBundle(const char *name, const char *docstring)
Expose the tangent bundle of a manifold type M.
bp::object get_namespace(const std::string &name)
Create or retrieve a Python scope (that is, a class or module namespace).
Definition utils.hpp:22
Multibody configuration group , defined using the Pinocchio library.
Definition multibody.hpp:17
Wrap a Pinocchio Lie group into a ManifoldAbstractTpl object.
Tangent bundle of a base manifold M.