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 > (2<<16 | 6<<8 | 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);
77 vpHomogeneousMatrix mat;
78 vpTranslationVector vec(trans.translation.x,trans.translation.y,trans.translation.z);
79 vpQuaternionVector q(trans.rotation.x,trans.rotation.y,trans.rotation.z,trans.rotation.w);
86 geometry_msgs::Transform trans;
89 trans.rotation.
x = q.
x();
90 trans.rotation.y = q.
y();
91 trans.rotation.z = q.
z();
92 trans.rotation.w = q.
w();
95 trans.translation.x = mat[0][3];
96 trans.translation.y = mat[1][3];
97 trans.translation.z = mat[2][3];
103 geometry_msgs::Pose pose;
105 vpThetaUVector tu(mat);
108 tu.extract(theta, u);
112 double sinTheta_2 = sin(theta);
114 pose.orientation.x = u[0] * sinTheta_2;
115 pose.orientation.y = u[1] * sinTheta_2;
116 pose.orientation.z = u[2] * sinTheta_2;
117 pose.orientation.w = cos(theta);
119 pose.position.x = mat[0][3];
120 pose.position.y = mat[1][3];
121 pose.position.z = mat[2][3];
129 vpHomogeneousMatrix mat;
130 vpTranslationVector vec(trans.translation.x,trans.translation.y,trans.translation.z);
131 vpRotationMatrix rmat;
133 double a = trans.rotation.x;
134 double b = trans.rotation.y;
135 double c = trans.rotation.z;
136 double d = trans.rotation.w;
137 rmat[0][0] = a*a+b*b-c*c-d*d;
138 rmat[0][1] = 2*b*c-2*a*d;
139 rmat[0][2] = 2*a*c+2*b*d;
141 rmat[1][0] = 2*a*d+2*b*c;
142 rmat[1][1] = a*a-b*b+c*c-d*d;
143 rmat[1][2] = 2*c*d-2*a*b;
145 rmat[2][0] = 2*b*d-2*a*c;
146 rmat[2][1] = 2*a*b+2*c*d;
147 rmat[2][2] = a*a-b*b-c*c+d*d;
149 mat.buildFrom(vec,rmat);
155 geometry_msgs::Transform trans;
156 vpRotationMatrix rmat;
160 trans.rotation.x = q.
x();
161 trans.rotation.y = q.
y();
162 trans.rotation.z = q.
z();
163 trans.rotation.w = q.
w();
166 trans.translation.x = mat[0][3];
167 trans.translation.y = mat[1][3];
168 trans.translation.z = mat[2][3];
174 vpHomogeneousMatrix mat;
175 vpTranslationVector vec(pose.position.x,pose.position.y,pose.position.z);
176 vpRotationMatrix rmat;
178 double a = pose.orientation.x;
179 double b = pose.orientation.y;
180 double c = pose.orientation.z;
181 double d = pose.orientation.w;
182 rmat[0][0] = a*a+b*b-c*c-d*d;
183 rmat[0][1] = 2*b*c-2*a*d;
184 rmat[0][2] = 2*a*c+2*b*d;
186 rmat[1][0] = 2*a*d+2*b*c;
187 rmat[1][1] = a*a-b*b+c*c-d*d;
188 rmat[1][2] = 2*c*d-2*a*b;
190 rmat[2][0] = 2*b*d-2*a*c;
191 rmat[2][1] = 2*a*b+2*c*d;
192 rmat[2][2] = a*a-b*b-c*c+d*d;
194 mat.buildFrom(vec,rmat);
vpHomogeneousMatrix toVispHomogeneousMatrix(const geometry_msgs::Transform &trans)
Converts a geometry_msgs::Transform to a ViSP homogeneous matrix (vpHomogeneousMatrix).
double y() const
returns y-component of the quaternion
Class that consider the case of a quaternion and basic operations on it.
double w() const
returns w-component of the quaternion
geometry_msgs::Pose toGeometryMsgsPose(const vpHomogeneousMatrix &mat)
Converts a ViSP homogeneous matrix (vpHomogeneousMatrix) to a geometry_msgs::Pose.
conversions between ROS and ViSP structures representing a 3D pose
double z() const
returns z-component of the quaternion
double x() const
returns x-component of the quaternion
Defines a quaternion and its basic operations.
geometry_msgs::Transform toGeometryMsgsTransform(const vpHomogeneousMatrix &mat)
Converts a ViSP homogeneous matrix (vpHomogeneousMatrix) to a geometry_msgs::Transform.