16 #ifndef LIBBIOMIMETICS_ORIENTATION_TOOLS_H 17 #define LIBBIOMIMETICS_ORIENTATION_TOOLS_H 22 #include <eigen3/Eigen/Dense> 26 #include <type_traits> 39 static_assert(std::is_floating_point<T>::value,
40 "must use floating point value");
41 return rad * T(180) / T(M_PI);
49 static_assert(std::is_floating_point<T>::value,
50 "must use floating point value");
51 return deg * T(M_PI) / T(180);
61 static_assert(std::is_floating_point<T>::value,
62 "must use floating point value");
63 T s = std::sin(theta);
64 T c = std::cos(theta);
69 R << 1, 0, 0, 0, c, s, 0, -s, c;
71 R << c, 0, -s, 0, 1, 0, s, 0, c;
73 R << c, s, 0, -s, c, 0, 0, 0, 1;
84 static_assert(T::ColsAtCompileTime == 1 && T::RowsAtCompileTime == 3,
85 "must have 3x1 vector");
97 static_assert(T::ColsAtCompileTime == 1 && T::RowsAtCompileTime == 3,
98 "Must have 3x1 matrix");
100 m << 0, -v[2], v[1], v[2], 0, -v[0], -v[1], v[0], 0;
107 template <
typename T>
109 static_assert(T::ColsAtCompileTime == 3 && T::RowsAtCompileTime == 3,
110 "Must have 3x3 matrix");
112 (m(1, 0) - m(0, 1)));
118 template <
typename T>
120 const Eigen::MatrixBase<T>& r1) {
121 static_assert(T::ColsAtCompileTime == 3 && T::RowsAtCompileTime == 3,
122 "Must have 3x3 matrix");
125 typename T::Scalar tr = r.trace();
127 typename T::Scalar S = sqrt(tr + 1.0) * 2.0;
129 q(1) = (r(2, 1) - r(1, 2)) / S;
130 q(2) = (r(0, 2) - r(2, 0)) / S;
131 q(3) = (r(1, 0) - r(0, 1)) / S;
132 }
else if ((r(0, 0) > r(1, 1)) && (r(0, 0) > r(2, 2))) {
133 typename T::Scalar S = sqrt(1.0 + r(0, 0) - r(1, 1) - r(2, 2)) * 2.0;
134 q(0) = (r(2, 1) - r(1, 2)) / S;
136 q(2) = (r(0, 1) + r(1, 0)) / S;
137 q(3) = (r(0, 2) + r(2, 0)) / S;
138 }
else if (r(1, 1) > r(2, 2)) {
139 typename T::Scalar S = sqrt(1.0 + r(1, 1) - r(0, 0) - r(2, 2)) * 2.0;
140 q(0) = (r(0, 2) - r(2, 0)) / S;
141 q(1) = (r(0, 1) + r(1, 0)) / S;
143 q(3) = (r(1, 2) + r(2, 1)) / S;
145 typename T::Scalar S = sqrt(1.0 + r(2, 2) - r(0, 0) - r(1, 1)) * 2.0;
146 q(0) = (r(1, 0) - r(0, 1)) / S;
147 q(1) = (r(0, 2) + r(2, 0)) / S;
148 q(2) = (r(1, 2) + r(2, 1)) / S;
159 template <
typename T>
161 const Eigen::MatrixBase<T>& q) {
162 static_assert(T::ColsAtCompileTime == 1 && T::RowsAtCompileTime == 4,
163 "Must have 4x1 quat");
164 typename T::Scalar e0 = q(0);
165 typename T::Scalar e1 = q(1);
166 typename T::Scalar e2 = q(2);
167 typename T::Scalar e3 = q(3);
171 R << 1 - 2 * (e2 * e2 + e3 * e3), 2 * (e1 * e2 - e0 * e3),
172 2 * (e1 * e3 + e0 * e2), 2 * (e1 * e2 + e0 * e3),
173 1 - 2 * (e1 * e1 + e3 * e3), 2 * (e2 * e3 - e0 * e1),
174 2 * (e1 * e3 - e0 * e2), 2 * (e2 * e3 + e0 * e1),
175 1 - 2 * (e1 * e1 + e2 * e2);
176 R.transposeInPlace();
184 template <
typename T>
186 static_assert(T::ColsAtCompileTime == 1 && T::RowsAtCompileTime == 4,
187 "Must have 4x1 quat");
189 typename T::Scalar as = std::min(-2. * (q[1] * q[3] - q[0] * q[2]), .99999);
191 std::atan2(2 * (q[1] * q[2] + q[0] * q[3]),
193 rpy(1) = std::asin(as);
195 std::atan2(2 * (q[2] * q[3] + q[0] * q[1]),
200 template <
typename T>
202 static_assert(T::ColsAtCompileTime == 1 && T::RowsAtCompileTime == 3,
203 "Must have 3x1 vec");
212 template <
typename T>
214 static_assert(T::ColsAtCompileTime == 1 && T::RowsAtCompileTime == 4,
215 "Must have 4x1 quat");
217 typename T::Scalar theta = 2. * std::acos(q[0]);
218 so3[0] = theta * q[1] / std::sin(theta / 2.);
219 so3[1] = theta * q[2] / std::sin(theta / 2.);
220 so3[2] = theta * q[3] / std::sin(theta / 2.);
224 template <
typename T>
226 static_assert(T::ColsAtCompileTime == 3 && T::RowsAtCompileTime == 3,
227 "Must have 3x3 matrix");
239 template <
typename T,
typename T2>
241 const Eigen::MatrixBase<T2>& omega) {
242 static_assert(T::ColsAtCompileTime == 1 && T::RowsAtCompileTime == 4,
243 "Must have 4x1 quat");
244 static_assert(T2::ColsAtCompileTime == 1 && T2::RowsAtCompileTime == 3,
245 "Must have 3x1 omega");
248 Q << q[0], -q[1], -q[2], -q[3], q[1], q[0], -q[3], q[2], q[2], q[3], q[0],
249 -q[1], q[3], -q[2], q[1], q[0];
252 quaternionDerviativeStabilization * omega.norm() * (1 - q.norm()),
253 omega[0], omega[1], omega[2]);
261 template <
typename T>
263 const Eigen::MatrixBase<T>& q2) {
264 typename T::Scalar r1 = q1[0];
265 typename T::Scalar r2 = q2[0];
269 typename T::Scalar r = r1 * r2 - v1.dot(v2);
282 template <
typename T,
typename T2,
typename T3>
284 const Eigen::MatrixBase<T2>& omega,
286 static_assert(T::ColsAtCompileTime == 1 && T::RowsAtCompileTime == 4,
287 "Must have 4x1 quat");
288 static_assert(T2::ColsAtCompileTime == 1 && T2::RowsAtCompileTime == 3,
289 "Must have 3x1 omega");
291 typename T::Scalar ang = omega.norm();
303 quatNew = quatNew / quatNew.norm();
314 template <
typename T,
typename T2,
typename T3>
316 const Eigen::MatrixBase<T>& quat,
const Eigen::MatrixBase<T2>& omega,
318 static_assert(T::ColsAtCompileTime == 1 && T::RowsAtCompileTime == 4,
319 "Must have 4x1 quat");
320 static_assert(T2::ColsAtCompileTime == 1 && T2::RowsAtCompileTime == 3,
321 "Must have 3x1 omega");
323 typename T::Scalar ang = omega.norm();
335 quatNew = quatNew / quatNew.norm();
339 template <
typename T>
346 2.0 * asin(sqrt(so3[0] * so3[0] + so3[1] * so3[1] + so3[2] * so3[2]));
348 if (fabs(theta) < 0.0000001) {
352 so3 /= sin(theta / 2.0);
355 template <
typename T>
359 T theta = sqrt(so3[0] * so3[0] + so3[1] * so3[1] + so3[2] * so3[2]);
361 if (fabs(theta) < 1.e-6) {
366 quat[0] = cos(theta / 2.);
367 quat[1] = so3[0] / theta * sin(theta / 2.);
368 quat[2] = so3[1] / theta * sin(theta / 2.);
369 quat[3] = so3[2] / theta * sin(theta / 2.);
374 #endif // LIBBIOMIMETICS_ORIENTATION_TOOLS_H Quat< typename T::Scalar > integrateQuatImplicit(const Eigen::MatrixBase< T > &quat, const Eigen::MatrixBase< T2 > &omega, T3 dt)
Mat3< T > coordinateRotation(CoordinateAxis axis, T theta)
Mat3< typename T::Scalar > rpyToRotMat(const Eigen::MatrixBase< T > &v)
void quaternionToso3(const Quat< T > quat, Vec3< T > &so3)
typename Eigen::Matrix< T, 3, 3 > Mat3
typename Eigen::Matrix< T, 4, 4 > Mat4
typename Eigen::Matrix< T, 4, 1 > Quat
typename Eigen::Matrix< T, 3, 1 > Vec3
Quat< T > so3ToQuat(Vec3< T > &so3)
Quat< typename T::Scalar > integrateQuat(const Eigen::MatrixBase< T > &quat, const Eigen::MatrixBase< T2 > &omega, T3 dt)
Vec3< typename T::Scalar > quatToRPY(const Eigen::MatrixBase< T > &q)
static constexpr double quaternionDerviativeStabilization
Quat< typename T::Scalar > rotationMatrixToQuaternion(const Eigen::MatrixBase< T > &r1)
Quat< typename T::Scalar > quatProduct(const Eigen::MatrixBase< T > &q1, const Eigen::MatrixBase< T > &q2)
Vec3< typename T::Scalar > quatToso3(const Eigen::MatrixBase< T > &q)
Quat< typename T::Scalar > rpyToQuat(const Eigen::MatrixBase< T > &rpy)
Utility functions for math.
Mat3< typename T::Scalar > vectorToSkewMat(const Eigen::MatrixBase< T > &v)
Vec3< typename T::Scalar > matToSkewVec(const Eigen::MatrixBase< T > &m)
Vec3< typename T::Scalar > rotationMatrixToRPY(const Eigen::MatrixBase< T > &R)
Mat3< typename T::Scalar > quaternionToRotationMatrix(const Eigen::MatrixBase< T > &q)
Quat< typename T::Scalar > quatDerivative(const Eigen::MatrixBase< T > &q, const Eigen::MatrixBase< T2 > &omega)