@@ -57,42 +57,13 @@ REGISTER_UNARY_OP(InverserQuaternion, Inverse_of_unitquat);
57
57
/* --- SE3/SO3 conversions ----------------------------------------------- */
58
58
/* ----------------------------------------------------------------------- */
59
59
60
- REGISTER_UNARY_OP (HomogeneousMatrixToVector, MatrixHomoToPoseUTheta);
61
-
62
- struct HomogeneousMatrixToSE3Vector
63
- : public UnaryOpHeader<MatrixHomogeneous, dg::Vector> {
64
- void operator ()(const MatrixHomogeneous &M, dg::Vector &res) {
65
- res.resize (12 );
66
- res.head <3 >() = M.translation ();
67
- res.segment (3 , 3 ) = M.linear ().row (0 );
68
- res.segment (6 , 3 ) = M.linear ().row (1 );
69
- res.segment (9 , 3 ) = M.linear ().row (2 );
70
- }
71
- };
72
- REGISTER_UNARY_OP (HomogeneousMatrixToSE3Vector, MatrixHomoToSE3Vector);
73
-
74
- struct SE3VectorToHomogeneousMatrix
75
- : public UnaryOpHeader<dg::Vector, MatrixHomogeneous> {
76
- void operator ()(const dg::Vector &vect, MatrixHomogeneous &Mres) {
77
- Mres.translation () = vect.head <3 >();
78
- Mres.linear ().row (0 ) = vect.segment (3 , 3 );
79
- Mres.linear ().row (1 ) = vect.segment (6 , 3 );
80
- Mres.linear ().row (2 ) = vect.segment (9 , 3 );
81
- }
82
- };
83
- REGISTER_UNARY_OP (SE3VectorToHomogeneousMatrix, SE3VectorToMatrixHomo);
60
+ REGISTER_UNARY_OP (MatrixHomoToPoseUTheta, MatrixHomoToPoseUTheta);
61
+ REGISTER_UNARY_OP (MatrixHomoToSE3Vector, MatrixHomoToSE3Vector);
62
+ REGISTER_UNARY_OP (SE3VectorToMatrixHomo, SE3VectorToMatrixHomo);
84
63
REGISTER_UNARY_OP (SkewSymToVector, SkewSymToVector);
85
64
REGISTER_UNARY_OP (PoseUThetaToMatrixHomo, PoseUThetaToMatrixHomo);
86
65
REGISTER_UNARY_OP (MatrixHomoToPoseQuaternion, MatrixHomoToPoseQuaternion);
87
-
88
- struct PoseQuaternionToMatrixHomo
89
- : public UnaryOpHeader<Vector, MatrixHomogeneous> {
90
- void operator ()(const dg::Vector &vect, MatrixHomogeneous &Mres) {
91
- Mres.translation () = vect.head <3 >();
92
- Mres.linear () = VectorQuaternion (vect.tail <4 >()).toRotationMatrix ();
93
- }
94
- };
95
- REGISTER_UNARY_OP (PoseQuaternionToMatrixHomo, PoseQuatToMatrixHomo);
66
+ REGISTER_UNARY_OP (PoseQuaternionToMatrixHomo, PoseQuaternionToMatrixHomo);
96
67
REGISTER_UNARY_OP (MatrixHomoToPoseRollPitchYaw, MatrixHomoToPoseRollPitchYaw);
97
68
REGISTER_UNARY_OP (PoseRollPitchYawToMatrixHomo, PoseRollPitchYawToMatrixHomo);
98
69
REGISTER_UNARY_OP (PoseRollPitchYawToPoseUTheta, PoseRollPitchYawToPoseUTheta);
0 commit comments