29#ifndef HPP_PINOCCHIO_LIEGROUP_HH
30#define HPP_PINOCCHIO_LIEGROUP_HH
37#include <pinocchio/multibody/joint/joints.hpp>
49 template <
typename Jo
intModel>
60 template <
typename Jo
intModel>
68template <
typename Scalar,
int Options,
int Axis>
70 ::pinocchio::JointModelRevoluteTpl<Scalar, Options, Axis> > {
73template <
typename Scalar,
int Options,
int Axis>
74struct RnxSOnLieGroupMap::operation<
75 ::pinocchio::JointModelRevoluteUnboundedTpl<Scalar, Options, Axis> > {
76 typedef liegroup::SpecialOrthogonalOperation<2> type;
78template <
typename Scalar,
int Options>
79struct RnxSOnLieGroupMap::operation<
80 ::pinocchio::JointModelRevoluteUnalignedTpl<Scalar, Options> > {
81 typedef liegroup::VectorSpaceOperation<1, true> type;
83template <
typename Scalar,
int Options>
84struct RnxSOnLieGroupMap::operation<
85 ::pinocchio::JointModelRevoluteUnboundedUnalignedTpl<Scalar, Options> > {
86 typedef liegroup::SpecialOrthogonalOperation<2> type;
90template <
typename Scalar,
int Options,
int Axis>
91struct RnxSOnLieGroupMap::operation<
92 ::pinocchio::JointModelPrismaticTpl<Scalar, Options, Axis> > {
93 typedef liegroup::VectorSpaceOperation<1, false> type;
95template <
typename Scalar,
int Options>
96struct RnxSOnLieGroupMap::operation<
97 ::pinocchio::JointModelPrismaticUnalignedTpl<Scalar, Options> > {
98 typedef liegroup::VectorSpaceOperation<1, false> type;
100template <
typename Scalar,
int Options>
101struct RnxSOnLieGroupMap::operation<
102 ::pinocchio::JointModelTranslationTpl<Scalar, Options> > {
103 typedef liegroup::VectorSpaceOperation<3, false> type;
107template <
typename Scalar,
int Options>
108struct RnxSOnLieGroupMap::operation<
109 ::pinocchio::JointModelSphericalTpl<Scalar, Options> > {
110 typedef liegroup::SpecialOrthogonalOperation<3> type;
112template <
typename Scalar,
int Options>
113struct RnxSOnLieGroupMap::operation<
114 ::pinocchio::JointModelSphericalZYXTpl<Scalar, Options> > {
115 typedef liegroup::VectorSpaceOperation<3, true> type;
119template <
typename Scalar,
int Options>
120struct RnxSOnLieGroupMap::operation<
121 ::pinocchio::JointModelFreeFlyerTpl<Scalar, Options> > {
122 typedef liegroup::CartesianProductOperation<
123 liegroup::VectorSpaceOperation<3, false>,
124 liegroup::SpecialOrthogonalOperation<3> >
127template <
typename Scalar,
int Options>
128struct RnxSOnLieGroupMap::operation<
129 ::pinocchio::JointModelPlanarTpl<Scalar, Options> > {
130 typedef liegroup::CartesianProductOperation<
131 liegroup::VectorSpaceOperation<2, false>,
132 liegroup::SpecialOrthogonalOperation<2> >
140template <
typename Scalar,
int Options,
int Axis>
141struct DefaultLieGroupMap::operation<
142 ::pinocchio::JointModelRevoluteTpl<Scalar, Options, Axis> > {
143 typedef liegroup::VectorSpaceOperation<1, true> type;
145template <
typename Scalar,
int Options,
int Axis>
146struct DefaultLieGroupMap::operation<
147 ::pinocchio::JointModelRevoluteUnboundedTpl<Scalar, Options, Axis> > {
148 typedef liegroup::SpecialOrthogonalOperation<2> type;
150template <
typename Scalar,
int Options>
151struct DefaultLieGroupMap::operation<
152 ::pinocchio::JointModelRevoluteUnalignedTpl<Scalar, Options> > {
153 typedef liegroup::VectorSpaceOperation<1, true> type;
155template <
typename Scalar,
int Options>
156struct DefaultLieGroupMap::operation<
157 ::pinocchio::JointModelRevoluteUnboundedUnalignedTpl<Scalar, Options> > {
158 typedef liegroup::SpecialOrthogonalOperation<2> type;
162template <
typename Scalar,
int Options,
int Axis>
163struct DefaultLieGroupMap::operation<
164 ::pinocchio::JointModelPrismaticTpl<Scalar, Options, Axis> > {
165 typedef liegroup::VectorSpaceOperation<1, false> type;
167template <
typename Scalar,
int Options>
168struct DefaultLieGroupMap::operation<
169 ::pinocchio::JointModelPrismaticUnalignedTpl<Scalar, Options> > {
170 typedef liegroup::VectorSpaceOperation<1, false> type;
172template <
typename Scalar,
int Options>
173struct DefaultLieGroupMap::operation<
174 ::pinocchio::JointModelTranslationTpl<Scalar, Options> > {
175 typedef liegroup::VectorSpaceOperation<3, false> type;
179template <
typename Scalar,
int Options>
180struct DefaultLieGroupMap::operation<
181 ::pinocchio::JointModelSphericalTpl<Scalar, Options> > {
182 typedef liegroup::SpecialOrthogonalOperation<3> type;
184template <
typename Scalar,
int Options>
185struct DefaultLieGroupMap::operation<
186 ::pinocchio::JointModelSphericalZYXTpl<Scalar, Options> > {
187 typedef liegroup::VectorSpaceOperation<3, true> type;
191template <
typename Scalar,
int Options>
192struct DefaultLieGroupMap::operation<
193 ::pinocchio::JointModelFreeFlyerTpl<Scalar, Options> > {
194 typedef liegroup::SpecialEuclideanOperation<3> type;
196template <
typename Scalar,
int Options>
197struct DefaultLieGroupMap::operation<
198 ::pinocchio::JointModelPlanarTpl<Scalar, Options> > {
199 typedef liegroup::SpecialEuclideanOperation<2> type;
Utility functions.
Definition body.hh:39
Definition collision-object.hh:40
Definition liegroup.hh:61
Definition liegroup.hh:59
Definition liegroup.hh:50
Definition liegroup.hh:48
Definition vector-space.hh:60