22 #ifndef OV_CORE_QUAT_OPS_H
23 #define OV_CORE_QUAT_OPS_H
65 #include <Eigen/Eigen>
88 inline Eigen::Matrix<double, 4, 1>
rot_2_quat(
const Eigen::Matrix<double, 3, 3> &rot) {
89 Eigen::Matrix<double, 4, 1> q;
90 double T = rot.trace();
91 if ((rot(0, 0) >= T) && (rot(0, 0) >= rot(1, 1)) && (rot(0, 0) >= rot(2, 2))) {
92 q(0) = sqrt((1 + (2 * rot(0, 0)) - T) / 4);
93 q(1) = (1 / (4 * q(0))) * (rot(0, 1) + rot(1, 0));
94 q(2) = (1 / (4 * q(0))) * (rot(0, 2) + rot(2, 0));
95 q(3) = (1 / (4 * q(0))) * (rot(1, 2) - rot(2, 1));
97 }
else if ((rot(1, 1) >= T) && (rot(1, 1) >= rot(0, 0)) && (rot(1, 1) >= rot(2, 2))) {
98 q(1) = sqrt((1 + (2 * rot(1, 1)) - T) / 4);
99 q(0) = (1 / (4 * q(1))) * (rot(0, 1) + rot(1, 0));
100 q(2) = (1 / (4 * q(1))) * (rot(1, 2) + rot(2, 1));
101 q(3) = (1 / (4 * q(1))) * (rot(2, 0) - rot(0, 2));
102 }
else if ((rot(2, 2) >= T) && (rot(2, 2) >= rot(0, 0)) && (rot(2, 2) >= rot(1, 1))) {
103 q(2) = sqrt((1 + (2 * rot(2, 2)) - T) / 4);
104 q(0) = (1 / (4 * q(2))) * (rot(0, 2) + rot(2, 0));
105 q(1) = (1 / (4 * q(2))) * (rot(1, 2) + rot(2, 1));
106 q(3) = (1 / (4 * q(2))) * (rot(0, 1) - rot(1, 0));
108 q(3) = sqrt((1 + T) / 4);
109 q(0) = (1 / (4 * q(3))) * (rot(1, 2) - rot(2, 1));
110 q(1) = (1 / (4 * q(3))) * (rot(2, 0) - rot(0, 2));
111 q(2) = (1 / (4 * q(3))) * (rot(0, 1) - rot(1, 0));
135 inline Eigen::Matrix<double, 3, 3>
skew_x(
const Eigen::Matrix<double, 3, 1> &w) {
136 Eigen::Matrix<double, 3, 3> w_x;
137 w_x << 0, -w(2), w(1), w(2), 0, -w(0), -w(1), w(0), 0;
152 inline Eigen::Matrix<double, 3, 3>
quat_2_Rot(
const Eigen::Matrix<double, 4, 1> &q) {
153 Eigen::Matrix<double, 3, 3> q_x =
skew_x(q.block(0, 0, 3, 1));
154 Eigen::MatrixXd Rot = (2 * std::pow(q(3, 0), 2) - 1) * Eigen::MatrixXd::Identity(3, 3) - 2 * q(3, 0) * q_x +
155 2 * q.block(0, 0, 3, 1) * (q.block(0, 0, 3, 1).transpose());
180 inline Eigen::Matrix<double, 4, 1>
quat_multiply(
const Eigen::Matrix<double, 4, 1> &q,
const Eigen::Matrix<double, 4, 1> &p) {
181 Eigen::Matrix<double, 4, 1> q_t;
182 Eigen::Matrix<double, 4, 4> Qm;
184 Qm.block(0, 0, 3, 3) = q(3, 0) * Eigen::MatrixXd::Identity(3, 3) -
skew_x(q.block(0, 0, 3, 1));
185 Qm.block(0, 3, 3, 1) = q.block(0, 0, 3, 1);
186 Qm.block(3, 0, 1, 3) = -q.block(0, 0, 3, 1).transpose();
194 return q_t / q_t.norm();
205 inline Eigen::Matrix<double, 3, 1>
vee(
const Eigen::Matrix<double, 3, 3> &w_x) {
206 Eigen::Matrix<double, 3, 1> w;
207 w << w_x(2, 1), w_x(0, 2), w_x(1, 0);
231 inline Eigen::Matrix<double, 3, 3>
exp_so3(
const Eigen::Matrix<double, 3, 1> &w) {
233 Eigen::Matrix<double, 3, 3> w_x =
skew_x(w);
234 double theta = w.norm();
241 A = sin(theta) / theta;
242 B = (1 - cos(theta)) / (theta * theta);
245 Eigen::Matrix<double, 3, 3> R;
247 R = Eigen::MatrixXd::Identity(3, 3);
249 R = Eigen::MatrixXd::Identity(3, 3) + A * w_x + B * w_x * w_x;
273 inline Eigen::Matrix<double, 3, 1>
log_so3(
const Eigen::Matrix<double, 3, 3> &R) {
276 double R11 = R(0, 0), R12 = R(0, 1), R13 = R(0, 2);
277 double R21 = R(1, 0), R22 = R(1, 1), R23 = R(1, 2);
278 double R31 = R(2, 0), R32 = R(2, 1), R33 = R(2, 2);
281 const double tr = R.trace();
282 Eigen::Vector3d omega;
286 if (tr + 1.0 < 1e-10) {
287 if (std::abs(R33 + 1.0) > 1e-5)
288 omega = (M_PI / sqrt(2.0 + 2.0 * R33)) * Eigen::Vector3d(R13, R23, 1.0 + R33);
289 else if (std::abs(R22 + 1.0) > 1e-5)
290 omega = (M_PI / sqrt(2.0 + 2.0 * R22)) * Eigen::Vector3d(R12, 1.0 + R22, R32);
293 omega = (M_PI / sqrt(2.0 + 2.0 * R11)) * Eigen::Vector3d(1.0 + R11, R21, R31);
296 const double tr_3 = tr - 3.0;
298 double theta = acos((tr - 1.0) / 2.0);
299 magnitude = theta / (2.0 * sin(theta));
304 magnitude = 0.5 - tr_3 / 12.0;
306 omega = magnitude * Eigen::Vector3d(R32 - R23, R13 - R31, R21 - R12);
332 inline Eigen::Matrix4d
exp_se3(Eigen::Matrix<double, 6, 1> vec) {
335 Eigen::Vector3d w = vec.head(3);
336 Eigen::Vector3d u = vec.tail(3);
337 double theta = sqrt(w.dot(w));
338 Eigen::Matrix3d wskew;
339 wskew << 0, -w(2), w(1), w(2), 0, -w(0), -w(1), w(0), 0;
348 A = sin(theta) / theta;
349 B = (1 - cos(theta)) / (theta * theta);
350 C = (1 - A) / (theta * theta);
354 Eigen::Matrix3d I_33 = Eigen::Matrix3d::Identity();
355 Eigen::Matrix3d V = I_33 + B * wskew + C * wskew * wskew;
358 Eigen::Matrix4d mat = Eigen::Matrix4d::Zero();
359 mat.block(0, 0, 3, 3) = I_33 + A * wskew + B * wskew * wskew;
360 mat.block(0, 3, 3, 1) = V * u;
388 inline Eigen::Matrix<double, 6, 1>
log_se3(Eigen::Matrix4d mat) {
389 Eigen::Vector3d w =
log_so3(mat.block<3, 3>(0, 0));
390 Eigen::Vector3d T = mat.block<3, 1>(0, 3);
391 const double t = w.norm();
393 Eigen::Matrix<double, 6, 1> log;
397 Eigen::Matrix3d W =
skew_x(w / t);
400 double Tan = tan(0.5 * t);
401 Eigen::Vector3d WT = W * T;
402 Eigen::Vector3d u = T - (0.5 * t) * WT + (1 - t / (2. * Tan)) * (W * WT);
403 Eigen::Matrix<double, 6, 1> log;
419 inline Eigen::Matrix4d
hat_se3(
const Eigen::Matrix<double, 6, 1> &vec) {
420 Eigen::Matrix4d mat = Eigen::Matrix4d::Zero();
421 mat.block(0, 0, 3, 3) =
skew_x(vec.head(3));
422 mat.block(0, 3, 3, 1) = vec.tail(3);
439 inline Eigen::Matrix4d
Inv_se3(
const Eigen::Matrix4d &T) {
440 Eigen::Matrix4d Tinv = Eigen::Matrix4d::Identity();
441 Tinv.block(0, 0, 3, 3) = T.block(0, 0, 3, 3).transpose();
442 Tinv.block(0, 3, 3, 1) = -Tinv.block(0, 0, 3, 3) * T.block(0, 3, 3, 1);
457 inline Eigen::Matrix<double, 4, 1>
Inv(Eigen::Matrix<double, 4, 1> q) {
458 Eigen::Matrix<double, 4, 1> qinv;
459 qinv.block(0, 0, 3, 1) = -q.block(0, 0, 3, 1);
460 qinv(3, 0) = q(3, 0);
482 inline Eigen::Matrix<double, 4, 4>
Omega(Eigen::Matrix<double, 3, 1> w) {
483 Eigen::Matrix<double, 4, 4> mat;
484 mat.block(0, 0, 3, 3) = -
skew_x(w);
485 mat.block(3, 0, 1, 3) = -w.transpose();
486 mat.block(0, 3, 3, 1) = w;
496 inline Eigen::Matrix<double, 4, 1>
quatnorm(Eigen::Matrix<double, 4, 1> q_t) {
500 return q_t / q_t.norm();
515 inline Eigen::Matrix<double, 3, 3>
Jl_so3(
const Eigen::Matrix<double, 3, 1> &w) {
516 double theta = w.norm();
518 return Eigen::MatrixXd::Identity(3, 3);
520 Eigen::Matrix<double, 3, 1> a = w / theta;
521 Eigen::Matrix<double, 3, 3> J = sin(theta) / theta * Eigen::MatrixXd::Identity(3, 3) + (1 - sin(theta) / theta) * a * a.transpose() +
522 ((1 - cos(theta)) / theta) *
skew_x(a);
537 inline Eigen::Matrix<double, 3, 3>
Jr_so3(
const Eigen::Matrix<double, 3, 1> &w) {
return Jl_so3(-w); }
549 inline Eigen::Matrix<double, 3, 1>
rot2rpy(
const Eigen::Matrix<double, 3, 3> &rot) {
550 Eigen::Matrix<double, 3, 1> rpy;
551 rpy(1, 0) = atan2(-rot(2, 0), sqrt(rot(0, 0) * rot(0, 0) + rot(1, 0) * rot(1, 0)));
552 if (std::abs(cos(rpy(1, 0))) > 1.0e-12) {
553 rpy(2, 0) = atan2(rot(1, 0) / cos(rpy(1, 0)), rot(0, 0) / cos(rpy(1, 0)));
554 rpy(0, 0) = atan2(rot(2, 1) / cos(rpy(1, 0)), rot(2, 2) / cos(rpy(1, 0)));
557 rpy(0, 0) = atan2(rot(0, 1), rot(1, 1));
577 inline Eigen::Matrix<double, 3, 3>
rot_x(
double t) {
578 Eigen::Matrix<double, 3, 3> r;
581 r << 1.0, 0.0, 0.0, 0.0, ct, -st, 0.0, st, ct;
600 inline Eigen::Matrix<double, 3, 3>
rot_y(
double t) {
601 Eigen::Matrix<double, 3, 3> r;
604 r << ct, 0.0, st, 0.0, 1.0, 0.0, -st, 0.0, ct;
623 inline Eigen::Matrix<double, 3, 3>
rot_z(
double t) {
624 Eigen::Matrix<double, 3, 3> r;
627 r << ct, -st, 0.0, st, ct, 0.0, 0.0, 0.0, 1.0;