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
2
3// Boost.Python 1.74 include manually mpl/vector/vector20.hpp
4// that prevent us to define mpl::list and mpl::vector with
5// the right size.
6// To avoid this issue this header should be included first.
7#include <pinocchio/fwd.hpp>
8
11
14
15namespace aligator::python {
17using context::Scalar;
18using PolyManifold = xyz::polymorphic<Manifold>;
19
22template <typename LieGroup>
23void exposeLieGroup(const char *name, const char *docstring) {
24 bp::class_<PinocchioLieGroup<LieGroup>, bp::bases<Manifold>>(
25 name, docstring, bp::init<>("self"_a))
27 .enable_pickling_(true);
28}
29
31template <typename M>
32bp::class_<TangentBundleTpl<M>, bp::bases<Manifold>>
33exposeTangentBundle(const char *name, const char *docstring) {
34 using OutType = TangentBundleTpl<M>;
35 return bp::class_<OutType, bp::bases<Manifold>>(
36 name, docstring, bp::init<const M &>(("self"_a, "base")))
37 .add_property("base",
38 bp::make_function(&OutType::getBaseSpace,
39 bp::return_internal_reference<>()),
40 "Get the base space.")
42}
43
45template <typename M, class Init>
46bp::class_<TangentBundleTpl<M>, bp::bases<Manifold>>
47exposeTangentBundle(const char *name, const char *docstring, Init init) {
48 return exposeTangentBundle<M>(name, docstring).def(init);
49}
50
52 bp::scope scope = get_namespace("manifolds");
53
54 namespace pin = pinocchio;
55 using pin::ModelTpl;
56 using pin::SpecialEuclideanOperationTpl;
57 using pin::SpecialOrthogonalOperationTpl;
58 using pin::VectorSpaceOperationTpl;
59
60 using DynSizeEuclideanSpace = VectorSpaceOperationTpl<Eigen::Dynamic, Scalar>;
61 bp::class_<PinocchioLieGroup<DynSizeEuclideanSpace>, bp::bases<Manifold>>(
62 "EuclideanSpace", "Pinocchio's n-dimensional Euclidean vector space.",
63 bp::no_init)
64 .def(bp::init<int>(("self"_a, "dim")))
66
68 "R", "One-dimensional Euclidean space AKA real number line.");
70 "R2", "Two-dimensional Euclidean space.");
72 "R3", "Three-dimensional Euclidean space.");
74 "R4", "Four-dimensional Euclidean space.");
76 "SO2", "SO(2) special orthogonal group.");
78 "SO3", "SO(3) special orthogonal group.");
80 "SE2", "SE(2) special Euclidean group.");
82 "SE3", "SE(3) special Euclidean group.");
83
88
89 /* Expose tangent bundles */
90
91 exposeTangentBundle<SO2>("TSO2", "Tangent bundle of the SO(2) group.")
92 .def(bp::init<>(bp::args("self")));
93 exposeTangentBundle<SO3>("TSO3", "Tangent bundle of the SO(3) group.")
94 .def(bp::init<>(bp::args("self")));
95 exposeTangentBundle<SE2>("TSE2", "Tangent bundle of the SE(2) group.")
96 .def(bp::init<>(bp::args("self")));
97 exposeTangentBundle<SE3>("TSE3", "Tangent bundle of the SE(3) group.")
98 .def(bp::init<>(bp::args("self")));
99
100 /* Groups associated w/ Pinocchio models */
101 using Multibody = MultibodyConfiguration<Scalar>;
102 using Model = ModelTpl<Scalar>;
103 bp::class_<Multibody, bp::bases<Manifold>>(
104 "MultibodyConfiguration", "Configuration group of a multibody",
105 bp::init<const Model &>(bp::args("self", "model")))
106 .add_property("model",
107 bp::make_function(&Multibody::getModel,
108 bp::return_internal_reference<>()),
109 "Return the Pinocchio model instance.")
111 .enable_pickling_(true);
112
113 using MultiPhase = MultibodyPhaseSpace<Scalar>;
114 bp::class_<MultiPhase, bp::bases<Manifold>>(
115 "MultibodyPhaseSpace",
116 "Tangent space of the multibody configuration group.",
117 bp::init<const Model &>(("self"_a, "model")))
118 .add_property("model",
119 bp::make_function(&MultiPhase::getModel,
120 bp::return_internal_reference<>()),
121 "Return the Pinocchio model instance.")
122 .add_property("base", bp::make_function(
123 +[](const MultiPhase &m) -> const Multibody & {
124 return m.getBaseSpace();
125 },
126 bp::return_internal_reference<>()))
128 .enable_pickling_(true);
129}
130
131} // namespace aligator::python
132
133#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.