51 const double& q0 = q.w();
52 const double& q1 = q.x();
53 const double& q2 = q.y();
54 const double& q3 = q.z();
56 std::atan2(2 * (q0 * q1 + q2 * q3), 1 - 2 * (q1 * q1 + q2 * q2));
57 double pitch = std::asin(2 * (q0 * q2 - q3 * q1));
58 double yaw = std::atan2(2 * (q0 * q3 + q1 * q2), 1 - 2 * (q2 * q2 + q3 * q3));
59 return Vector3(roll, pitch, yaw);
67 double sy = std::sin(yaw *
cst(0.5));
68 double cy = std::cos(yaw *
cst(0.5));
69 double sp = std::sin(pitch *
cst(0.5));
70 double cp = std::cos(pitch *
cst(0.5));
71 double sr = std::sin(roll *
cst(0.5));
72 double cr = std::cos(roll *
cst(0.5));
73 double w = cr * cp * cy + sr * sp * sy;
74 double x = sr * cp * cy - cr * sp * sy;
75 double y = cr * sp * cy + sr * cp * sy;
76 double z = cr * cp * sy - sr * sp * cy;
77 return Quaternion(w, x, y, z).toRotationMatrix();
84 return q.coeffs().head<3>();
88 double w = 1 - v.squaredNorm();
90 return Matrix3::Identity();
93 return Quaternion(w, v[0], v[1], v[2]).toRotationMatrix();
100 v.block<3, 1>(0, 0) = t.translation();
107 v.block<3, 1>(0, 0) = t.translation();
119 v.block<3, 1>(0, 0) = t.translation();
126 t.translation() = v.block<3, 1>(0, 0);
133 t.translation() = v.block<3, 1>(0, 0);
139 t =
Quaternion(v[6], v[3], v[4], v[5]).toRotationMatrix();
140 t.translation() = v.head<3>();
145 SE3Quat result(t.matrix().topLeftCorner<3, 3>(), t.translation());
const Quaternion & rotation() const
const Vector3 & translation() const
some general case utility functions
Isometry3 fromVectorQT(const Vector7 &v)
SE3Quat toSE3Quat(const Isometry3 &t)
Vector3 toEuler(const Matrix3 &R)
Isometry3 fromVectorMQT(const Vector6 &v)
Vector6 toVectorMQT(const Isometry3 &t)
Vector3 toCompactQuaternion(const Matrix3 &R)
Quaternion normalized(const Quaternion &q)
Matrix3 fromCompactQuaternion(const Vector3 &v)
Quaternion & normalize(Quaternion &q)
Matrix3 fromEuler(const Vector3 &v)
Vector6 toVectorET(const Isometry3 &t)
Vector7 toVectorQT(const Isometry3 &t)
Isometry3 fromVectorET(const Vector6 &v)
Isometry3 fromSE3Quat(const SE3Quat &t)
Isometry3::ConstLinearPart extractRotation(const Isometry3 &A)
constexpr double cst(long double v)
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3
Eigen::Quaternion< double > Quaternion