Cheetah Software  1.0
orientation_tools.h
Go to the documentation of this file.
1 
16 #ifndef LIBBIOMIMETICS_ORIENTATION_TOOLS_H
17 #define LIBBIOMIMETICS_ORIENTATION_TOOLS_H
18 
19 #include "Math/MathUtilities.h"
20 #include "cppTypes.h"
21 
22 #include <eigen3/Eigen/Dense>
23 
24 #include <cmath>
25 #include <iostream>
26 #include <type_traits>
27 
28 namespace ori {
29 
30 static constexpr double quaternionDerviativeStabilization = 0.1;
31 
32 enum class CoordinateAxis { X, Y, Z };
33 
37 template <typename T>
38 T rad2deg(T rad) {
39  static_assert(std::is_floating_point<T>::value,
40  "must use floating point value");
41  return rad * T(180) / T(M_PI);
42 }
43 
47 template <typename T>
48 T deg2rad(T deg) {
49  static_assert(std::is_floating_point<T>::value,
50  "must use floating point value");
51  return deg * T(M_PI) / T(180);
52 }
53 
59 template <typename T>
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);
65 
66  Mat3<T> R;
67 
68  if (axis == CoordinateAxis::X) {
69  R << 1, 0, 0, 0, c, s, 0, -s, c;
70  } else if (axis == CoordinateAxis::Y) {
71  R << c, 0, -s, 0, 1, 0, s, 0, c;
72  } else if (axis == CoordinateAxis::Z) {
73  R << c, s, 0, -s, c, 0, 0, 0, 1;
74  }
75 
76  return R;
77 }
78 
82 template <typename T>
83 Mat3<typename T::Scalar> rpyToRotMat(const Eigen::MatrixBase<T>& v) {
84  static_assert(T::ColsAtCompileTime == 1 && T::RowsAtCompileTime == 3,
85  "must have 3x1 vector");
89  return m;
90 }
91 
95 template <typename T>
96 Mat3<typename T::Scalar> vectorToSkewMat(const Eigen::MatrixBase<T>& v) {
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;
101  return m;
102 }
103 
107 template <typename T>
108 Vec3<typename T::Scalar> matToSkewVec(const Eigen::MatrixBase<T>& m) {
109  static_assert(T::ColsAtCompileTime == 3 && T::RowsAtCompileTime == 3,
110  "Must have 3x3 matrix");
111  return 0.5 * Vec3<typename T::Scalar>(m(2, 1) - m(1, 2), m(0, 2) - m(2, 0),
112  (m(1, 0) - m(0, 1)));
113 }
114 
118 template <typename T>
120  const Eigen::MatrixBase<T>& r1) {
121  static_assert(T::ColsAtCompileTime == 3 && T::RowsAtCompileTime == 3,
122  "Must have 3x3 matrix");
124  Mat3<typename T::Scalar> r = r1.transpose();
125  typename T::Scalar tr = r.trace();
126  if (tr > 0.0) {
127  typename T::Scalar S = sqrt(tr + 1.0) * 2.0;
128  q(0) = 0.25 * S;
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;
135  q(1) = 0.25 * 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;
142  q(2) = 0.25 * S;
143  q(3) = (r(1, 2) + r(2, 1)) / S;
144  } else {
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;
149  q(3) = 0.25 * S;
150  }
151  return q;
152 }
153 
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);
168 
170 
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();
177  return R;
178 }
179 
184 template <typename T>
185 Vec3<typename T::Scalar> quatToRPY(const Eigen::MatrixBase<T>& q) {
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);
190  rpy(2) =
191  std::atan2(2 * (q[1] * q[2] + q[0] * q[3]),
192  square(q[0]) + square(q[1]) - square(q[2]) - square(q[3]));
193  rpy(1) = std::asin(as);
194  rpy(0) =
195  std::atan2(2 * (q[2] * q[3] + q[0] * q[1]),
196  square(q[0]) - square(q[1]) - square(q[2]) + square(q[3]));
197  return rpy;
198 }
199 
200 template <typename T>
201 Quat<typename T::Scalar> rpyToQuat(const Eigen::MatrixBase<T>& rpy) {
202  static_assert(T::ColsAtCompileTime == 1 && T::RowsAtCompileTime == 3,
203  "Must have 3x1 vec");
206  return q;
207 }
208 
212 template <typename T>
213 Vec3<typename T::Scalar> quatToso3(const Eigen::MatrixBase<T>& q) {
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.);
221  return so3;
222 }
223 
224 template <typename T>
225 Vec3<typename T::Scalar> rotationMatrixToRPY(const Eigen::MatrixBase<T>& R) {
226  static_assert(T::ColsAtCompileTime == 3 && T::RowsAtCompileTime == 3,
227  "Must have 3x3 matrix");
230  return rpy;
231 }
239 template <typename T, typename T2>
240 Quat<typename T::Scalar> quatDerivative(const Eigen::MatrixBase<T>& q,
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");
246  // first case in rqd
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];
250 
252  quaternionDerviativeStabilization * omega.norm() * (1 - q.norm()),
253  omega[0], omega[1], omega[2]);
254  Quat<typename T::Scalar> dq = 0.5 * Q * qq;
255  return dq;
256 }
257 
261 template <typename T>
262 Quat<typename T::Scalar> quatProduct(const Eigen::MatrixBase<T>& q1,
263  const Eigen::MatrixBase<T>& q2) {
264  typename T::Scalar r1 = q1[0];
265  typename T::Scalar r2 = q2[0];
266  Vec3<typename T::Scalar> v1(q1[1], q1[2], q1[3]);
267  Vec3<typename T::Scalar> v2(q2[1], q2[2], q2[3]);
268 
269  typename T::Scalar r = r1 * r2 - v1.dot(v2);
270  Vec3<typename T::Scalar> v = r1 * v2 + r2 * v1 + v1.cross(v2);
271  Quat<typename T::Scalar> q(r, v[0], v[1], v[2]);
272  return q;
273 }
274 
282 template <typename T, typename T2, typename T3>
283 Quat<typename T::Scalar> integrateQuat(const Eigen::MatrixBase<T>& quat,
284  const Eigen::MatrixBase<T2>& omega,
285  T3 dt) {
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();
292  if (ang > 0) {
293  axis = omega / ang;
294  } else {
295  axis = Vec3<typename T::Scalar>(1, 0, 0);
296  }
297 
298  ang *= dt;
299  Vec3<typename T::Scalar> ee = std::sin(ang / 2) * axis;
300  Quat<typename T::Scalar> quatD(std::cos(ang / 2), ee[0], ee[1], ee[2]);
301 
302  Quat<typename T::Scalar> quatNew = quatProduct(quatD, quat);
303  quatNew = quatNew / quatNew.norm();
304  return quatNew;
305 }
306 
314 template <typename T, typename T2, typename T3>
316  const Eigen::MatrixBase<T>& quat, const Eigen::MatrixBase<T2>& omega,
317  T3 dt) {
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();
324  if (ang > 0) {
325  axis = omega / ang;
326  } else {
327  axis = Vec3<typename T::Scalar>(1, 0, 0);
328  }
329 
330  ang *= dt;
331  Vec3<typename T::Scalar> ee = std::sin(ang / 2) * axis;
332  Quat<typename T::Scalar> quatD(std::cos(ang / 2), ee[0], ee[1], ee[2]);
333 
334  Quat<typename T::Scalar> quatNew = quatProduct(quat, quatD);
335  quatNew = quatNew / quatNew.norm();
336  return quatNew;
337 }
338 
339 template <typename T>
340 void quaternionToso3(const Quat<T> quat, Vec3<T>& so3) {
341  so3[0] = quat[1];
342  so3[1] = quat[2];
343  so3[2] = quat[3];
344 
345  T theta =
346  2.0 * asin(sqrt(so3[0] * so3[0] + so3[1] * so3[1] + so3[2] * so3[2]));
347 
348  if (fabs(theta) < 0.0000001) {
349  so3.setZero();
350  return;
351  }
352  so3 /= sin(theta / 2.0);
353  so3 *= theta;
354 }
355 template <typename T>
357  Quat<T> quat;
358 
359  T theta = sqrt(so3[0] * so3[0] + so3[1] * so3[1] + so3[2] * so3[2]);
360 
361  if (fabs(theta) < 1.e-6) {
362  quat.setZero();
363  quat[0] = 1.;
364  return quat;
365  }
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.);
370  return quat;
371 }
372 } // namespace ori
373 
374 #endif // LIBBIOMIMETICS_ORIENTATION_TOOLS_H
Quat< typename T::Scalar > integrateQuatImplicit(const Eigen::MatrixBase< T > &quat, const Eigen::MatrixBase< T2 > &omega, T3 dt)
T rad2deg(T rad)
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)
T square(T a)
Definition: MathUtilities.h:15
typename Eigen::Matrix< T, 3, 3 > Mat3
Definition: cppTypes.h:54
typename Eigen::Matrix< T, 4, 4 > Mat4
Definition: cppTypes.h:94
typename Eigen::Matrix< T, 4, 1 > Quat
Definition: cppTypes.h:58
typename Eigen::Matrix< T, 3, 1 > Vec3
Definition: cppTypes.h:26
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)
T deg2rad(T deg)
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)