36 m_coords[0] = m(0, 3);
37 m_coords[1] = m(1, 3);
38 m_coords[2] = m(2, 3);
40 m_rotvec = rotVecFromRotMat(m);
43 CPose3DRotVec::CPose3DRotVec(
const CPose3D& m)
50 m_rotvec = rotVecFromRotMat(
R);
55 CPose3DRotVec::CPose3DRotVec(
62 const double a = sqrt(
q.x() *
q.x() +
q.y() *
q.y() +
q.z() *
q.z());
63 const double TH = 0.001;
64 const double k =
a <
TH ? 2 : 2 * acos(
q.r()) / sqrt(1 -
q.r() *
q.r());
65 m_rotvec[0] = k *
q.x();
66 m_rotvec[1] = k *
q.y();
67 m_rotvec[2] = k *
q.z();
70 uint8_t CPose3DRotVec::serializeGetVersion()
const {
return 0; }
73 out << m_coords[0] << m_coords[1] << m_coords[2] << m_rotvec[0]
74 << m_rotvec[1] << m_rotvec[2];
76 void CPose3DRotVec::serializeFrom(
83 in >> m_coords[0] >> m_coords[1] >> m_coords[2] >> m_rotvec[0] >>
84 m_rotvec[1] >> m_rotvec[2];
92 void CPose3DRotVec::setFromXYZAndAngles(
93 const double x,
const double y,
const double z,
const double yaw,
116 const std::streamsize old_pre = o.precision();
117 const std::ios_base::fmtflags old_flags = o.flags();
118 o <<
"(x,y,z,vx,vy,vz)=(" << std::fixed << std::setprecision(4)
119 <<
p.m_coords[0] <<
"," <<
p.m_coords[1] <<
"," <<
p.m_coords[2] <<
","
120 <<
p.m_rotvec[0] <<
"," <<
p.m_rotvec[1] <<
"," <<
p.m_rotvec[2] <<
")";
122 o.precision(old_pre);
137 void CPose3DRotVec::sphericalCoordinates(
138 const TPoint3D& point,
double& out_range,
double& out_yaw,
139 double& out_pitch)
const
143 this->inverseComposePoint(
147 out_range =
local.norm();
157 out_pitch = -asin(
local.z / out_range);
165 void CPose3DRotVec::composePoint(
166 double lx,
double ly,
double lz,
double& gx,
double& gy,
double& gz,
170 const double angle = this->m_rotvec.norm();
171 const double K1 = sin(angle) / angle;
172 const double K2 = (1 - cos(angle)) / (angle * angle);
174 const double tx = this->m_coords[0];
175 const double ty = this->m_coords[1];
176 const double tz = this->m_coords[2];
178 const double w1 = this->m_rotvec[0];
179 const double w2 = this->m_rotvec[1];
180 const double w3 = this->m_rotvec[2];
182 const double w1_2 =
w1 *
w1;
183 const double w2_2 =
w2 *
w2;
184 const double w3_2 = w3 * w3;
186 gx = lx * (1 - K2 * (w2_2 + w3_2)) + ly * (K2 *
w1 *
w2 - K1 * w3) +
187 lz * (K1 *
w2 + K2 *
w1 * w3) + tx;
188 gy = lx * (K1 * w3 + K2 *
w1 *
w2) + ly * (1 - K2 * (w1_2 + w3_2)) +
189 lz * (K2 *
w2 * w3 - K1 *
w1) +
ty;
190 gz = lx * (K2 *
w1 * w3 - K1 *
w2) + ly * (K1 *
w1 + K2 *
w2 * w3) +
191 lz * (1 - K2 * (w1_2 + w2_2)) +
tz;
193 if (out_jacobian_df_dpoint || out_jacobian_df_dpose)
206 b.getInverseHomogeneousMatrix(B_INV);
228 b.m_coords[0],
b.m_coords[1],
b.m_coords[2], outPoint.
m_coords[0],
242 b.m_coords[0],
b.m_coords[1], 0, outPoint.
m_coords[0],
251 q.m_coords[1] = this->m_coords[1];
252 q.m_coords[2] = this->m_coords[2];
254 const double a = sqrt(
255 this->m_rotvec[0] * this->m_rotvec[0] +
256 this->m_rotvec[1] * this->m_rotvec[1] +
257 this->m_rotvec[2] * this->m_rotvec[2]);
261 q.m_quat.x(0.5 * this->m_rotvec[0]);
262 q.m_quat.y(0.5 * this->m_rotvec[1]);
263 q.m_quat.z(0.5 * this->m_rotvec[2]);
269 q.m_quat.fromRodriguesVector(this->m_rotvec);
295 void CPose3DRotVec::composeFrom(
306 if (
a1 < 0.01 &&
a2 < 0.01)
314 if (out_jacobian_drvtC_drvtA || out_jacobian_drvtC_drvtB)
316 if (out_jacobian_drvtC_drvtA)
318 out_jacobian_drvtC_drvtA->setIdentity(6, 6);
319 out_jacobian_drvtC_drvtA->insertMatrix(
323 if (out_jacobian_drvtC_drvtB)
325 out_jacobian_drvtC_drvtB->setIdentity(6, 6);
326 out_jacobian_drvtC_drvtB->insertMatrix(
328 (*out_jacobian_drvtC_drvtB)(3, 3) = (*out_jacobian_drvtC_drvtB)(
329 4, 4) = (*out_jacobian_drvtC_drvtB)(5, 5) = 1;
345 else if (A_is_small) this->m_rotvec = B.
m_rotvec;
346 else if (B_is_small) this->m_rotvec = A.
m_rotvec;
349 const double a1_inv = 1/
a1;
350 const double a2_inv = 1/
a2;
352 const double sin_a1_2 = sin(0.5*
a1);
353 const double cos_a1_2 = cos(0.5*
a1);
354 const double sin_a2_2 = sin(0.5*
a2);
355 const double cos_a2_2 = cos(0.5*
a2);
357 const double KA = sin_a1_2*sin_a2_2;
358 const double KB = sin_a1_2*cos_a2_2;
359 const double KC = cos_a1_2*sin_a2_2;
360 const double KD = cos_a1_2*cos_a2_2;
362 const double r11 = a1_inv*A.
m_rotvec[0];
363 const double r12 = a1_inv*A.
m_rotvec[1];
364 const double r13 = a1_inv*A.
m_rotvec[2];
366 const double r21 = a2_inv*B.
m_rotvec[0];
367 const double r22 = a2_inv*B.
m_rotvec[1];
368 const double r23 = a2_inv*B.
m_rotvec[2];
370 const double q3[] = {
371 KD - KA*(r11*r21+r12*r22+r13*r23),
372 KC*r21 + KB*r11 + KA*(r22*r13-r23*r12),
373 KC*r22 + KB*r12 + KA*(r23*r11-r21*r13),
374 KC*r23 + KB*r13 + KA*(r21*r12-r22*r11)
377 const double param = 2*acos(q3[0])/sqrt(1-q3[0]*q3[0]);
378 this->m_rotvec[0] =
param*q3[1];
379 this->m_rotvec[1] =
param*q3[2];
380 this->m_rotvec[2] =
param*q3[3];
396 if (out_jacobian_drvtC_drvtA || out_jacobian_drvtC_drvtB)
401 const double& qCr = qC.
m_quat[0];
402 const double& qCx = qC.
m_quat[1];
403 const double& qCy = qC.
m_quat[2];
404 const double& qCz = qC.
m_quat[3];
406 const double& r1 = this->m_rotvec[0];
407 const double& r2 = this->m_rotvec[1];
408 const double& r3 = this->m_rotvec[2];
410 const double C = 1 / (1 - qCr * qCr);
411 const double D = acos(qCr) / sqrt(1 - qCr * qCr);
414 2 * C * qCx * (D * qCr - 1), 2 * D, 0, 0,
415 2 * C * qCy * (D * qCr - 1), 0, 2 * D, 0,
416 2 * C * qCz * (D * qCr - 1), 0, 0, 2 * D};
420 const double alpha = sqrt(r1 * r1 + r2 * r2 + r3 * r3);
425 -r1 * alpha2 * sin(
alpha / 2),
426 -r2 * alpha2 * sin(
alpha / 2),
427 -r3 * alpha2 * sin(
alpha / 2),
428 2 * alpha2 * sin(
alpha / 2) + r1 * r1 * KA,
432 2 * alpha2 * sin(
alpha / 2) + r2 * r2 * KA,
436 2 * alpha2 * sin(
alpha / 2) + r3 * r3 * KA};
440 if (out_jacobian_drvtC_drvtB)
444 const double& qAr = qA.
m_quat[0];
445 const double& qAx = qA.
m_quat[1];
446 const double& qAy = qA.
m_quat[2];
447 const double& qAz = qA.
m_quat[3];
450 qAr, -qAx, -qAy, -qAz, qAx, qAr, qAz, -qAy,
451 qAy, -qAz, qAr, qAx, qAz, qAy, -qAx, qAr};
455 jac_rot_B.multiply_ABC(H, QA,
G);
457 out_jacobian_drvtC_drvtB->fill(0);
458 out_jacobian_drvtC_drvtB->insertMatrix(0, 0, jac_rot_B);
459 out_jacobian_drvtC_drvtB->insertMatrix(3, 3, RA);
461 if (out_jacobian_drvtC_drvtA)
465 const double& qBr = qB.
m_quat[0];
466 const double& qBx = qB.
m_quat[1];
467 const double& qBy = qB.
m_quat[2];
468 const double& qBz = qB.
m_quat[3];
471 qBr, -qBx, -qBy, -qBz, qBx, qBr, -qBz, qBy,
472 qBy, qBz, qBr, -qBx, qBz, -qBy, qBx, qBr};
476 jac_rot_A.multiply_ABC(H, QB,
G);
479 out_jacobian_drvtC_drvtA->fill(0);
480 out_jacobian_drvtC_drvtA->insertMatrix(0, 0, jac_rot_A);
481 out_jacobian_drvtC_drvtB->insertMatrix(3, 3, id3);
490 this->getInverseHomogeneousMatrix(B_INV);
491 this->setFromTransformationMatrix(B_INV);
499 this->getInverseHomogeneousMatrix(B_INV);
510 void CPose3DRotVec::inverseComposeFrom(
526 HM_C.multiply_AB(HM_B_inv, HM_A);
528 this->m_rotvec = this->rotVecFromRotMat(HM_C);
530 this->m_coords[0] = HM_C(0, 3);
531 this->m_coords[1] = HM_C(1, 3);
532 this->m_coords[2] = HM_C(2, 3);
538 void CPose3DRotVec::inverseComposePoint(
539 const double gx,
const double gy,
const double gz,
double& lx,
double& ly,
568 result.head<3>() = m_coords;
569 result.tail<3>() = m_rotvec;
572 void CPose3DRotVec::setToNaN()
574 for (
int i = 0; i < 3; i++)
576 m_coords[i] = std::numeric_limits<double>::quiet_NaN();
577 m_rotvec[i] = std::numeric_limits<double>::quiet_NaN();