2929
3030namespace dynamicgraph {
3131namespace sot {
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- }
32+ namespace dg = dynamicgraph;
4533
4634/* --------------------------------------------------------------------- */
4735/* --- CLASS ----------------------------------------------------------- */
@@ -154,7 +142,7 @@ Vector7 toVector(const MatrixHomogeneous &M) {
154142
155143template <Representation_t representation>
156144Matrix &FeaturePose<representation>::computeJacobian(Matrix &J, int time) {
157- typedef typename internal:: LG_t<representation>::type LieGroup_t;
145+ typedef typename LG_t<representation>::type LieGroup_t;
158146
159147 check (*this );
160148
@@ -239,7 +227,7 @@ Vector7 &FeaturePose<representation>::computeQfaMfbDes(Vector7 &res, int time) {
239227
240228template <Representation_t representation>
241229Vector &FeaturePose<representation>::computeError(Vector &error, int time) {
242- typedef typename internal:: LG_t<representation>::type LieGroup_t;
230+ typedef typename LG_t<representation>::type LieGroup_t;
243231 check (*this );
244232
245233 const Flags &fl = selectionSIN (time);
@@ -259,7 +247,7 @@ Vector &FeaturePose<representation>::computeError(Vector &error, int time) {
259247// This function is responsible of converting the input velocity expressed with
260248// SE(3) convention onto a velocity expressed with the convention of this
261249// feature (R^3xSO(3) or SE(3)), in the right frame.
262- template <typename internal:: LG_t>
250+ template <typename LG_t>
263251Vector6d convertVelocity (const MatrixHomogeneous &M,
264252 const MatrixHomogeneous &Mdes,
265253 const Vector &faNufafbDes) {
@@ -282,7 +270,7 @@ Vector6d convertVelocity<R3xSO3_t>(const MatrixHomogeneous &M,
282270template <Representation_t representation>
283271Vector &FeaturePose<representation>::computeErrorDot(Vector &errordot,
284272 int time) {
285- typedef typename internal:: LG_t<representation>::type LieGroup_t;
273+ typedef typename LG_t<representation>::type LieGroup_t;
286274 check (*this );
287275
288276 errordot.resize (dimensionSOUT (time));
0 commit comments