28 return bp::class_<OutType, bp::bases<Manifold>>(
29 name, docstring, bp::init<const M &>((
"self"_a,
"base")))
31 bp::make_function(&OutType::getBaseSpace,
32 bp::return_internal_reference<>()),
33 "Get the base space.")
47 namespace pin = pinocchio;
49 using pin::SpecialEuclideanOperationTpl;
50 using pin::SpecialOrthogonalOperationTpl;
51 using pin::VectorSpaceOperationTpl;
53 using DynSizeEuclideanSpace = VectorSpaceOperationTpl<Eigen::Dynamic, Scalar>;
54 bp::class_<PinocchioLieGroup<DynSizeEuclideanSpace>, bp::bases<Manifold>>(
55 "EuclideanSpace",
"Pinocchio's n-dimensional Euclidean vector space.",
57 .def(bp::init<int>((
"self"_a,
"dim")))
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.");
85 .def(bp::init<>(bp::args(
"self")));
87 .def(bp::init<>(bp::args(
"self")));
89 .def(bp::init<>(bp::args(
"self")));
91 .def(bp::init<>(bp::args(
"self")));
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);
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();
119 bp::return_internal_reference<>()))
121 .enable_pickling_(
true);
ManifoldAbstractTpl< Scalar > Manifold
MultibodyPhaseSpace< Scalar > MultibodyPhaseSpace
Multibody configuration group , defined using the Pinocchio library.