52 #include <visp/vpConfig.h>
54 #if VISP_VERSION_INT > (2<<16 | 6<<8 | 1)
55 # include <visp/vpQuaternionVector.h>
57 # include <visp/vpRotationMatrix.h>
60 #include <visp/vpTranslationVector.h>
66 #if VISP_VERSION_INT > VP_VERSION_INT(2,6,1)
68 vpHomogeneousMatrix mat;
69 vpTranslationVector vec(pose.position.x,pose.position.y,pose.position.z);
70 vpQuaternionVector q(pose.orientation.x,pose.orientation.y,pose.orientation.z,pose.orientation.w);
72 #if VISP_VERSION_INT > VP_VERSION_INT(3,6,0)
82 vpHomogeneousMatrix mat;
83 vpTranslationVector vec(trans.translation.x,trans.translation.y,trans.translation.z);
84 vpQuaternionVector q(trans.rotation.x,trans.rotation.y,trans.rotation.z,trans.rotation.w);
85 #if VISP_VERSION_INT > VP_VERSION_INT(3,6,0)
95 geometry_msgs::Transform trans;
98 trans.rotation.
x = q.
x();
99 trans.rotation.y = q.
y();
100 trans.rotation.z = q.
z();
101 trans.rotation.w = q.
w();
104 trans.translation.x = mat[0][3];
105 trans.translation.y = mat[1][3];
106 trans.translation.z = mat[2][3];
112 geometry_msgs::Pose pose;
114 vpThetaUVector tu(mat);
117 tu.extract(theta, u);
121 double sinTheta_2 = sin(theta);
123 pose.orientation.x = u[0] * sinTheta_2;
124 pose.orientation.y = u[1] * sinTheta_2;
125 pose.orientation.z = u[2] * sinTheta_2;
126 pose.orientation.w = cos(theta);
128 pose.position.x = mat[0][3];
129 pose.position.y = mat[1][3];
130 pose.position.z = mat[2][3];
138 vpHomogeneousMatrix mat;
139 vpTranslationVector vec(trans.translation.x,trans.translation.y,trans.translation.z);
140 vpRotationMatrix rmat;
142 double a = trans.rotation.x;
143 double b = trans.rotation.y;
144 double c = trans.rotation.z;
145 double d = trans.rotation.w;
146 rmat[0][0] = a*a+b*b-c*c-
d*
d;
147 rmat[0][1] = 2*b*c-2*a*
d;
148 rmat[0][2] = 2*a*c+2*b*
d;
150 rmat[1][0] = 2*a*
d+2*b*c;
151 rmat[1][1] = a*a-b*b+c*c-
d*
d;
152 rmat[1][2] = 2*c*
d-2*a*b;
154 rmat[2][0] = 2*b*
d-2*a*c;
155 rmat[2][1] = 2*a*b+2*c*
d;
156 rmat[2][2] = a*a-b*b-c*c+
d*
d;
158 #if VISP_VERSION_INT > VP_VERSION_INT(3,6,0)
161 mat.buildFrom(vec,rmat);
168 geometry_msgs::Transform trans;
169 vpRotationMatrix rmat;
173 trans.rotation.x = q.
x();
174 trans.rotation.y = q.
y();
175 trans.rotation.z = q.
z();
176 trans.rotation.w = q.
w();
179 trans.translation.x = mat[0][3];
180 trans.translation.y = mat[1][3];
181 trans.translation.z = mat[2][3];
187 vpHomogeneousMatrix mat;
188 vpTranslationVector vec(pose.position.x,pose.position.y,pose.position.z);
189 vpRotationMatrix rmat;
191 double a = pose.orientation.x;
192 double b = pose.orientation.y;
193 double c = pose.orientation.z;
194 double d = pose.orientation.w;
195 rmat[0][0] = a*a+b*b-c*c-
d*
d;
196 rmat[0][1] = 2*b*c-2*a*
d;
197 rmat[0][2] = 2*a*c+2*b*
d;
199 rmat[1][0] = 2*a*
d+2*b*c;
200 rmat[1][1] = a*a-b*b+c*c-
d*
d;
201 rmat[1][2] = 2*c*
d-2*a*b;
203 rmat[2][0] = 2*b*
d-2*a*c;
204 rmat[2][1] = 2*a*b+2*c*
d;
205 rmat[2][2] = a*a-b*b-c*c+
d*
d;
207 #if VISP_VERSION_INT > VP_VERSION_INT(3,6,0)
210 mat.buildFrom(vec,rmat);