2929
3030namespace dynamicgraph {
3131namespace sot {
32- namespace dg = dynamicgraph;
32+
33+ typedef pinocchio::CartesianProductOperation<
34+ pinocchio::VectorSpaceOperationTpl<3 , double >,
35+ pinocchio::SpecialOrthogonalOperationTpl<3 , double > >
36+ R3xSO3_t;
37+ typedef pinocchio::SpecialEuclideanOperationTpl<3 , double > SE3_t;
38+
39+ namespace internal {
40+ template <Representation_t representation> struct LG_t {
41+ typedef typename boost::mpl::if_c<representation == SE3Representation, SE3_t,
42+ R3xSO3_t>::type type;
43+ };
44+ }
3345
3446/* --------------------------------------------------------------------- */
3547/* --- CLASS ----------------------------------------------------------- */
@@ -142,7 +154,7 @@ Vector7 toVector(const MatrixHomogeneous &M) {
142154
143155template <Representation_t representation>
144156Matrix &FeaturePose<representation>::computeJacobian(Matrix &J, int time) {
145- typedef typename LG_t<representation>::type LieGroup_t;
157+ typedef typename internal:: LG_t<representation>::type LieGroup_t;
146158
147159 check (*this );
148160
@@ -227,7 +239,7 @@ Vector7 &FeaturePose<representation>::computeQfaMfbDes(Vector7 &res, int time) {
227239
228240template <Representation_t representation>
229241Vector &FeaturePose<representation>::computeError(Vector &error, int time) {
230- typedef typename LG_t<representation>::type LieGroup_t;
242+ typedef typename internal:: LG_t<representation>::type LieGroup_t;
231243 check (*this );
232244
233245 const Flags &fl = selectionSIN (time);
@@ -247,7 +259,7 @@ Vector &FeaturePose<representation>::computeError(Vector &error, int time) {
247259// This function is responsible of converting the input velocity expressed with
248260// SE(3) convention onto a velocity expressed with the convention of this
249261// feature (R^3xSO(3) or SE(3)), in the right frame.
250- template <typename LG_t>
262+ template <typename internal:: LG_t>
251263Vector6d convertVelocity (const MatrixHomogeneous &M,
252264 const MatrixHomogeneous &Mdes,
253265 const Vector &faNufafbDes) {
@@ -270,7 +282,7 @@ Vector6d convertVelocity<R3xSO3_t>(const MatrixHomogeneous &M,
270282template <Representation_t representation>
271283Vector &FeaturePose<representation>::computeErrorDot(Vector &errordot,
272284 int time) {
273- typedef typename LG_t<representation>::type LieGroup_t;
285+ typedef typename internal:: LG_t<representation>::type LieGroup_t;
274286 check (*this );
275287
276288 errordot.resize (dimensionSOUT (time));
0 commit comments