35 return bp::class_<OutType, bp::bases<Manifold>>(
36 name, docstring, bp::init<const M &>((
"self"_a,
"base")))
38 bp::make_function(&OutType::getBaseSpace,
39 bp::return_internal_reference<>()),
40 "Get the base space.")
54 namespace pin = pinocchio;
56 using pin::SpecialEuclideanOperationTpl;
57 using pin::SpecialOrthogonalOperationTpl;
58 using pin::VectorSpaceOperationTpl;
60 using DynSizeEuclideanSpace = VectorSpaceOperationTpl<Eigen::Dynamic, Scalar>;
61 bp::class_<PinocchioLieGroup<DynSizeEuclideanSpace>, bp::bases<Manifold>>(
62 "EuclideanSpace",
"Pinocchio's n-dimensional Euclidean vector space.",
64 .def(bp::init<int>((
"self"_a,
"dim")))
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.");
92 .def(bp::init<>(bp::args(
"self")));
94 .def(bp::init<>(bp::args(
"self")));
96 .def(bp::init<>(bp::args(
"self")));
98 .def(bp::init<>(bp::args(
"self")));
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);
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();
126 bp::return_internal_reference<>()))
128 .enable_pickling_(
true);
ManifoldAbstractTpl< Scalar > Manifold
MultibodyPhaseSpace< Scalar > MultibodyPhaseSpace
Multibody configuration group , defined using the Pinocchio library.