rotation.h 30 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861
  1. // Ceres Solver - A fast non-linear least squares minimizer
  2. // Copyright 2023 Google Inc. All rights reserved.
  3. // http://ceres-solver.org/
  4. //
  5. // Redistribution and use in source and binary forms, with or without
  6. // modification, are permitted provided that the following conditions are met:
  7. //
  8. // * Redistributions of source code must retain the above copyright notice,
  9. // this list of conditions and the following disclaimer.
  10. // * Redistributions in binary form must reproduce the above copyright notice,
  11. // this list of conditions and the following disclaimer in the documentation
  12. // and/or other materials provided with the distribution.
  13. // * Neither the name of Google Inc. nor the names of its contributors may be
  14. // used to endorse or promote products derived from this software without
  15. // specific prior written permission.
  16. //
  17. // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
  18. // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
  19. // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
  20. // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
  21. // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
  22. // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
  23. // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
  24. // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
  25. // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
  26. // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  27. // POSSIBILITY OF SUCH DAMAGE.
  28. //
  29. // Author: keir@google.com (Keir Mierle)
  30. // sameeragarwal@google.com (Sameer Agarwal)
  31. //
  32. // Templated functions for manipulating rotations. The templated
  33. // functions are useful when implementing functors for automatic
  34. // differentiation.
  35. //
  36. // In the following, the Quaternions are laid out as 4-vectors, thus:
  37. //
  38. // q[0] scalar part.
  39. // q[1] coefficient of i.
  40. // q[2] coefficient of j.
  41. // q[3] coefficient of k.
  42. //
  43. // where: i*i = j*j = k*k = -1 and i*j = k, j*k = i, k*i = j.
  44. #ifndef CERES_PUBLIC_ROTATION_H_
  45. #define CERES_PUBLIC_ROTATION_H_
  46. #include <algorithm>
  47. #include <cmath>
  48. #include "ceres/constants.h"
  49. #include "ceres/internal/euler_angles.h"
  50. #include "glog/logging.h"
  51. namespace ceres {
  52. // Trivial wrapper to index linear arrays as matrices, given a fixed
  53. // column and row stride. When an array "T* array" is wrapped by a
  54. //
  55. // (const) MatrixAdapter<T, row_stride, col_stride> M"
  56. //
  57. // the expression M(i, j) is equivalent to
  58. //
  59. // array[i * row_stride + j * col_stride]
  60. //
  61. // Conversion functions to and from rotation matrices accept
  62. // MatrixAdapters to permit using row-major and column-major layouts,
  63. // and rotation matrices embedded in larger matrices (such as a 3x4
  64. // projection matrix).
  65. template <typename T, int row_stride, int col_stride>
  66. struct MatrixAdapter;
  67. // Convenience functions to create a MatrixAdapter that treats the
  68. // array pointed to by "pointer" as a 3x3 (contiguous) column-major or
  69. // row-major matrix.
  70. template <typename T>
  71. MatrixAdapter<T, 1, 3> ColumnMajorAdapter3x3(T* pointer);
  72. template <typename T>
  73. MatrixAdapter<T, 3, 1> RowMajorAdapter3x3(T* pointer);
  74. // Convert a value in combined axis-angle representation to a quaternion.
  75. // The value angle_axis is a triple whose norm is an angle in radians,
  76. // and whose direction is aligned with the axis of rotation,
  77. // and quaternion is a 4-tuple that will contain the resulting quaternion.
  78. // The implementation may be used with auto-differentiation up to the first
  79. // derivative, higher derivatives may have unexpected results near the origin.
  80. template <typename T>
  81. void AngleAxisToQuaternion(const T* angle_axis, T* quaternion);
  82. // Convert a quaternion to the equivalent combined axis-angle representation.
  83. // The value quaternion must be a unit quaternion - it is not normalized first,
  84. // and angle_axis will be filled with a value whose norm is the angle of
  85. // rotation in radians, and whose direction is the axis of rotation.
  86. // The implementation may be used with auto-differentiation up to the first
  87. // derivative, higher derivatives may have unexpected results near the origin.
  88. template <typename T>
  89. void QuaternionToAngleAxis(const T* quaternion, T* angle_axis);
  90. // Conversions between 3x3 rotation matrix (in column major order) and
  91. // quaternion rotation representations. Templated for use with
  92. // autodifferentiation.
  93. template <typename T>
  94. void RotationMatrixToQuaternion(const T* R, T* quaternion);
  95. template <typename T, int row_stride, int col_stride>
  96. void RotationMatrixToQuaternion(
  97. const MatrixAdapter<const T, row_stride, col_stride>& R, T* quaternion);
  98. // Conversions between 3x3 rotation matrix (in column major order) and
  99. // axis-angle rotation representations. Templated for use with
  100. // autodifferentiation.
  101. template <typename T>
  102. void RotationMatrixToAngleAxis(const T* R, T* angle_axis);
  103. template <typename T, int row_stride, int col_stride>
  104. void RotationMatrixToAngleAxis(
  105. const MatrixAdapter<const T, row_stride, col_stride>& R, T* angle_axis);
  106. template <typename T>
  107. void AngleAxisToRotationMatrix(const T* angle_axis, T* R);
  108. template <typename T, int row_stride, int col_stride>
  109. void AngleAxisToRotationMatrix(
  110. const T* angle_axis, const MatrixAdapter<T, row_stride, col_stride>& R);
  111. // Conversions between 3x3 rotation matrix (in row major order) and
  112. // Euler angle (in degrees) rotation representations.
  113. //
  114. // The {pitch,roll,yaw} Euler angles are rotations around the {x,y,z}
  115. // axes, respectively. They are applied in that same order, so the
  116. // total rotation R is Rz * Ry * Rx.
  117. template <typename T>
  118. void EulerAnglesToRotationMatrix(const T* euler, int row_stride, T* R);
  119. template <typename T, int row_stride, int col_stride>
  120. void EulerAnglesToRotationMatrix(
  121. const T* euler, const MatrixAdapter<T, row_stride, col_stride>& R);
  122. // Convert a generic Euler Angle sequence (in radians) to a 3x3 rotation matrix.
  123. //
  124. // Euler Angles define a sequence of 3 rotations about a sequence of axes,
  125. // typically taken to be the X, Y, or Z axes. The last axis may be the same as
  126. // the first axis (e.g. ZYZ) per Euler's original definition of his angles
  127. // (proper Euler angles) or not (e.g. ZYX / yaw-pitch-roll), per common usage in
  128. // the nautical and aerospace fields (Tait-Bryan angles). The three rotations
  129. // may be in a global frame of reference (Extrinsic) or in a body fixed frame of
  130. // reference (Intrinsic) that moves with the rotating object.
  131. //
  132. // Internally, Euler Axis sequences are classified by Ken Shoemake's scheme from
  133. // "Euler angle conversion", Graphics Gems IV, where a choice of axis for the
  134. // first rotation and 3 binary choices:
  135. // 1. Parity of the axis permutation. The axis sequence has Even parity if the
  136. // second axis of rotation is 'greater-than' the first axis of rotation
  137. // according to the order X<Y<Z<X, otherwise it has Odd parity.
  138. // 2. Proper Euler Angles v.s. Tait-Bryan Angles
  139. // 3. Extrinsic Rotations v.s. Intrinsic Rotations
  140. // compactly represent all 24 possible Euler Angle Conventions
  141. //
  142. // One template parameter: EulerSystem must be explicitly given. This parameter
  143. // is a tag named by 'Extrinsic' or 'Intrinsic' followed by three characters in
  144. // the set '[XYZ]', specifying the axis sequence, e.g. ceres::ExtrinsicYZY
  145. // (robotic arms), ceres::IntrinsicZYX (for aerospace), etc.
  146. //
  147. // The order of elements in the input array 'euler' follows the axis sequence
  148. template <typename EulerSystem, typename T>
  149. inline void EulerAnglesToRotation(const T* euler, T* R);
  150. template <typename EulerSystem, typename T, int row_stride, int col_stride>
  151. void EulerAnglesToRotation(const T* euler,
  152. const MatrixAdapter<T, row_stride, col_stride>& R);
  153. // Convert a 3x3 rotation matrix to a generic Euler Angle sequence (in radians)
  154. //
  155. // Euler Angles define a sequence of 3 rotations about a sequence of axes,
  156. // typically taken to be the X, Y, or Z axes. The last axis may be the same as
  157. // the first axis (e.g. ZYZ) per Euler's original definition of his angles
  158. // (proper Euler angles) or not (e.g. ZYX / yaw-pitch-roll), per common usage in
  159. // the nautical and aerospace fields (Tait-Bryan angles). The three rotations
  160. // may be in a global frame of reference (Extrinsic) or in a body fixed frame of
  161. // reference (Intrinsic) that moves with the rotating object.
  162. //
  163. // Internally, Euler Axis sequences are classified by Ken Shoemake's scheme from
  164. // "Euler angle conversion", Graphics Gems IV, where a choice of axis for the
  165. // first rotation and 3 binary choices:
  166. // 1. Oddness of the axis permutation, that defines whether the second axis is
  167. // 'greater-than' the first axis according to the order X>Y>Z>X)
  168. // 2. Proper Euler Angles v.s. Tait-Bryan Angles
  169. // 3. Extrinsic Rotations v.s. Intrinsic Rotations
  170. // compactly represent all 24 possible Euler Angle Conventions
  171. //
  172. // One template parameter: EulerSystem must be explicitly given. This parameter
  173. // is a tag named by 'Extrinsic' or 'Intrinsic' followed by three characters in
  174. // the set '[XYZ]', specifying the axis sequence, e.g. ceres::ExtrinsicYZY
  175. // (robotic arms), ceres::IntrinsicZYX (for aerospace), etc.
  176. //
  177. // The order of elements in the output array 'euler' follows the axis sequence
  178. template <typename EulerSystem, typename T>
  179. inline void RotationMatrixToEulerAngles(const T* R, T* euler);
  180. template <typename EulerSystem, typename T, int row_stride, int col_stride>
  181. void RotationMatrixToEulerAngles(
  182. const MatrixAdapter<const T, row_stride, col_stride>& R, T* euler);
  183. // Convert a 4-vector to a 3x3 scaled rotation matrix.
  184. //
  185. // The choice of rotation is such that the quaternion [1 0 0 0] goes to an
  186. // identity matrix and for small a, b, c the quaternion [1 a b c] goes to
  187. // the matrix
  188. //
  189. // [ 0 -c b ]
  190. // I + 2 [ c 0 -a ] + higher order terms
  191. // [ -b a 0 ]
  192. //
  193. // which corresponds to a Rodrigues approximation, the last matrix being
  194. // the cross-product matrix of [a b c]. Together with the property that
  195. // R(q1 * q2) = R(q1) * R(q2) this uniquely defines the mapping from q to R.
  196. //
  197. // No normalization of the quaternion is performed, i.e.
  198. // R = ||q||^2 * Q, where Q is an orthonormal matrix
  199. // such that det(Q) = 1 and Q*Q' = I
  200. //
  201. // WARNING: The rotation matrix is ROW MAJOR
  202. template <typename T>
  203. inline void QuaternionToScaledRotation(const T q[4], T R[3 * 3]);
  204. template <typename T, int row_stride, int col_stride>
  205. inline void QuaternionToScaledRotation(
  206. const T q[4], const MatrixAdapter<T, row_stride, col_stride>& R);
  207. // Same as above except that the rotation matrix is normalized by the
  208. // Frobenius norm, so that R * R' = I (and det(R) = 1).
  209. //
  210. // WARNING: The rotation matrix is ROW MAJOR
  211. template <typename T>
  212. inline void QuaternionToRotation(const T q[4], T R[3 * 3]);
  213. template <typename T, int row_stride, int col_stride>
  214. inline void QuaternionToRotation(
  215. const T q[4], const MatrixAdapter<T, row_stride, col_stride>& R);
  216. // Rotates a point pt by a quaternion q:
  217. //
  218. // result = R(q) * pt
  219. //
  220. // Assumes the quaternion is unit norm. This assumption allows us to
  221. // write the transform as (something)*pt + pt, as is clear from the
  222. // formula below. If you pass in a quaternion with |q|^2 = 2 then you
  223. // WILL NOT get back 2 times the result you get for a unit quaternion.
  224. //
  225. // Inplace rotation is not supported. pt and result must point to different
  226. // memory locations, otherwise the result will be undefined.
  227. template <typename T>
  228. inline void UnitQuaternionRotatePoint(const T q[4], const T pt[3], T result[3]);
  229. // With this function you do not need to assume that q has unit norm.
  230. // It does assume that the norm is non-zero.
  231. //
  232. // Inplace rotation is not supported. pt and result must point to different
  233. // memory locations, otherwise the result will be undefined.
  234. template <typename T>
  235. inline void QuaternionRotatePoint(const T q[4], const T pt[3], T result[3]);
  236. // zw = z * w, where * is the Quaternion product between 4 vectors.
  237. //
  238. // Inplace quaternion product is not supported. The resulting quaternion zw must
  239. // not share the memory with the input quaternion z and w, otherwise the result
  240. // will be undefined.
  241. template <typename T>
  242. inline void QuaternionProduct(const T z[4], const T w[4], T zw[4]);
  243. // xy = x cross y;
  244. //
  245. // Inplace cross product is not supported. The resulting vector x_cross_y must
  246. // not share the memory with the input vectors x and y, otherwise the result
  247. // will be undefined.
  248. template <typename T>
  249. inline void CrossProduct(const T x[3], const T y[3], T x_cross_y[3]);
  250. template <typename T>
  251. inline T DotProduct(const T x[3], const T y[3]);
  252. // y = R(angle_axis) * x;
  253. //
  254. // Inplace rotation is not supported. pt and result must point to different
  255. // memory locations, otherwise the result will be undefined.
  256. template <typename T>
  257. inline void AngleAxisRotatePoint(const T angle_axis[3],
  258. const T pt[3],
  259. T result[3]);
  260. // --- IMPLEMENTATION
  261. template <typename T, int row_stride, int col_stride>
  262. struct MatrixAdapter {
  263. T* pointer_;
  264. explicit MatrixAdapter(T* pointer) : pointer_(pointer) {}
  265. T& operator()(int r, int c) const {
  266. return pointer_[r * row_stride + c * col_stride];
  267. }
  268. };
  269. template <typename T>
  270. MatrixAdapter<T, 1, 3> ColumnMajorAdapter3x3(T* pointer) {
  271. return MatrixAdapter<T, 1, 3>(pointer);
  272. }
  273. template <typename T>
  274. MatrixAdapter<T, 3, 1> RowMajorAdapter3x3(T* pointer) {
  275. return MatrixAdapter<T, 3, 1>(pointer);
  276. }
  277. template <typename T>
  278. inline void AngleAxisToQuaternion(const T* angle_axis, T* quaternion) {
  279. using std::fpclassify;
  280. using std::hypot;
  281. const T& a0 = angle_axis[0];
  282. const T& a1 = angle_axis[1];
  283. const T& a2 = angle_axis[2];
  284. const T theta = hypot(a0, a1, a2);
  285. // For points not at the origin, the full conversion is numerically stable.
  286. if (fpclassify(theta) != FP_ZERO) {
  287. const T half_theta = theta * T(0.5);
  288. const T k = sin(half_theta) / theta;
  289. quaternion[0] = cos(half_theta);
  290. quaternion[1] = a0 * k;
  291. quaternion[2] = a1 * k;
  292. quaternion[3] = a2 * k;
  293. } else {
  294. // At the origin, sqrt() will produce NaN in the derivative since
  295. // the argument is zero. By approximating with a Taylor series,
  296. // and truncating at one term, the value and first derivatives will be
  297. // computed correctly when Jets are used.
  298. const T k(0.5);
  299. quaternion[0] = T(1.0);
  300. quaternion[1] = a0 * k;
  301. quaternion[2] = a1 * k;
  302. quaternion[3] = a2 * k;
  303. }
  304. }
  305. template <typename T>
  306. inline void QuaternionToAngleAxis(const T* quaternion, T* angle_axis) {
  307. using std::fpclassify;
  308. using std::hypot;
  309. const T& q1 = quaternion[1];
  310. const T& q2 = quaternion[2];
  311. const T& q3 = quaternion[3];
  312. const T sin_theta = hypot(q1, q2, q3);
  313. // For quaternions representing non-zero rotation, the conversion
  314. // is numerically stable.
  315. if (fpclassify(sin_theta) != FP_ZERO) {
  316. const T& cos_theta = quaternion[0];
  317. // If cos_theta is negative, theta is greater than pi/2, which
  318. // means that angle for the angle_axis vector which is 2 * theta
  319. // would be greater than pi.
  320. //
  321. // While this will result in the correct rotation, it does not
  322. // result in a normalized angle-axis vector.
  323. //
  324. // In that case we observe that 2 * theta ~ 2 * theta - 2 * pi,
  325. // which is equivalent saying
  326. //
  327. // theta - pi = atan(sin(theta - pi), cos(theta - pi))
  328. // = atan(-sin(theta), -cos(theta))
  329. //
  330. const T two_theta =
  331. T(2.0) * ((cos_theta < T(0.0)) ? atan2(-sin_theta, -cos_theta)
  332. : atan2(sin_theta, cos_theta));
  333. const T k = two_theta / sin_theta;
  334. angle_axis[0] = q1 * k;
  335. angle_axis[1] = q2 * k;
  336. angle_axis[2] = q3 * k;
  337. } else {
  338. // For zero rotation, sqrt() will produce NaN in the derivative since
  339. // the argument is zero. By approximating with a Taylor series,
  340. // and truncating at one term, the value and first derivatives will be
  341. // computed correctly when Jets are used.
  342. const T k(2.0);
  343. angle_axis[0] = q1 * k;
  344. angle_axis[1] = q2 * k;
  345. angle_axis[2] = q3 * k;
  346. }
  347. }
  348. template <typename T>
  349. void RotationMatrixToQuaternion(const T* R, T* quaternion) {
  350. RotationMatrixToQuaternion(ColumnMajorAdapter3x3(R), quaternion);
  351. }
  352. // This algorithm comes from "Quaternion Calculus and Fast Animation",
  353. // Ken Shoemake, 1987 SIGGRAPH course notes
  354. template <typename T, int row_stride, int col_stride>
  355. void RotationMatrixToQuaternion(
  356. const MatrixAdapter<const T, row_stride, col_stride>& R, T* quaternion) {
  357. const T trace = R(0, 0) + R(1, 1) + R(2, 2);
  358. if (trace >= 0.0) {
  359. T t = sqrt(trace + T(1.0));
  360. quaternion[0] = T(0.5) * t;
  361. t = T(0.5) / t;
  362. quaternion[1] = (R(2, 1) - R(1, 2)) * t;
  363. quaternion[2] = (R(0, 2) - R(2, 0)) * t;
  364. quaternion[3] = (R(1, 0) - R(0, 1)) * t;
  365. } else {
  366. int i = 0;
  367. if (R(1, 1) > R(0, 0)) {
  368. i = 1;
  369. }
  370. if (R(2, 2) > R(i, i)) {
  371. i = 2;
  372. }
  373. const int j = (i + 1) % 3;
  374. const int k = (j + 1) % 3;
  375. T t = sqrt(R(i, i) - R(j, j) - R(k, k) + T(1.0));
  376. quaternion[i + 1] = T(0.5) * t;
  377. t = T(0.5) / t;
  378. quaternion[0] = (R(k, j) - R(j, k)) * t;
  379. quaternion[j + 1] = (R(j, i) + R(i, j)) * t;
  380. quaternion[k + 1] = (R(k, i) + R(i, k)) * t;
  381. }
  382. }
  383. // The conversion of a rotation matrix to the angle-axis form is
  384. // numerically problematic when then rotation angle is close to zero
  385. // or to Pi. The following implementation detects when these two cases
  386. // occurs and deals with them by taking code paths that are guaranteed
  387. // to not perform division by a small number.
  388. template <typename T>
  389. inline void RotationMatrixToAngleAxis(const T* R, T* angle_axis) {
  390. RotationMatrixToAngleAxis(ColumnMajorAdapter3x3(R), angle_axis);
  391. }
  392. template <typename T, int row_stride, int col_stride>
  393. void RotationMatrixToAngleAxis(
  394. const MatrixAdapter<const T, row_stride, col_stride>& R, T* angle_axis) {
  395. T quaternion[4];
  396. RotationMatrixToQuaternion(R, quaternion);
  397. QuaternionToAngleAxis(quaternion, angle_axis);
  398. return;
  399. }
  400. template <typename T>
  401. inline void AngleAxisToRotationMatrix(const T* angle_axis, T* R) {
  402. AngleAxisToRotationMatrix(angle_axis, ColumnMajorAdapter3x3(R));
  403. }
  404. template <typename T, int row_stride, int col_stride>
  405. void AngleAxisToRotationMatrix(
  406. const T* angle_axis, const MatrixAdapter<T, row_stride, col_stride>& R) {
  407. using std::fpclassify;
  408. using std::hypot;
  409. static const T kOne = T(1.0);
  410. const T theta = hypot(angle_axis[0], angle_axis[1], angle_axis[2]);
  411. if (fpclassify(theta) != FP_ZERO) {
  412. // We want to be careful to only evaluate the square root if the
  413. // norm of the angle_axis vector is greater than zero. Otherwise
  414. // we get a division by zero.
  415. const T wx = angle_axis[0] / theta;
  416. const T wy = angle_axis[1] / theta;
  417. const T wz = angle_axis[2] / theta;
  418. const T costheta = cos(theta);
  419. const T sintheta = sin(theta);
  420. // clang-format off
  421. R(0, 0) = costheta + wx*wx*(kOne - costheta);
  422. R(1, 0) = wz*sintheta + wx*wy*(kOne - costheta);
  423. R(2, 0) = -wy*sintheta + wx*wz*(kOne - costheta);
  424. R(0, 1) = wx*wy*(kOne - costheta) - wz*sintheta;
  425. R(1, 1) = costheta + wy*wy*(kOne - costheta);
  426. R(2, 1) = wx*sintheta + wy*wz*(kOne - costheta);
  427. R(0, 2) = wy*sintheta + wx*wz*(kOne - costheta);
  428. R(1, 2) = -wx*sintheta + wy*wz*(kOne - costheta);
  429. R(2, 2) = costheta + wz*wz*(kOne - costheta);
  430. // clang-format on
  431. } else {
  432. // At zero, we switch to using the first order Taylor expansion.
  433. R(0, 0) = kOne;
  434. R(1, 0) = angle_axis[2];
  435. R(2, 0) = -angle_axis[1];
  436. R(0, 1) = -angle_axis[2];
  437. R(1, 1) = kOne;
  438. R(2, 1) = angle_axis[0];
  439. R(0, 2) = angle_axis[1];
  440. R(1, 2) = -angle_axis[0];
  441. R(2, 2) = kOne;
  442. }
  443. }
  444. template <typename EulerSystem, typename T>
  445. inline void EulerAnglesToRotation(const T* euler, T* R) {
  446. EulerAnglesToRotation<EulerSystem>(euler, RowMajorAdapter3x3(R));
  447. }
  448. template <typename EulerSystem, typename T, int row_stride, int col_stride>
  449. void EulerAnglesToRotation(const T* euler,
  450. const MatrixAdapter<T, row_stride, col_stride>& R) {
  451. using std::cos;
  452. using std::sin;
  453. const auto [i, j, k] = EulerSystem::kAxes;
  454. T ea[3];
  455. ea[1] = euler[1];
  456. if constexpr (EulerSystem::kIsIntrinsic) {
  457. ea[0] = euler[2];
  458. ea[2] = euler[0];
  459. } else {
  460. ea[0] = euler[0];
  461. ea[2] = euler[2];
  462. }
  463. if constexpr (EulerSystem::kIsParityOdd) {
  464. ea[0] = -ea[0];
  465. ea[1] = -ea[1];
  466. ea[2] = -ea[2];
  467. }
  468. const T ci = cos(ea[0]);
  469. const T cj = cos(ea[1]);
  470. const T ch = cos(ea[2]);
  471. const T si = sin(ea[0]);
  472. const T sj = sin(ea[1]);
  473. const T sh = sin(ea[2]);
  474. const T cc = ci * ch;
  475. const T cs = ci * sh;
  476. const T sc = si * ch;
  477. const T ss = si * sh;
  478. if constexpr (EulerSystem::kIsProperEuler) {
  479. R(i, i) = cj;
  480. R(i, j) = sj * si;
  481. R(i, k) = sj * ci;
  482. R(j, i) = sj * sh;
  483. R(j, j) = -cj * ss + cc;
  484. R(j, k) = -cj * cs - sc;
  485. R(k, i) = -sj * ch;
  486. R(k, j) = cj * sc + cs;
  487. R(k, k) = cj * cc - ss;
  488. } else {
  489. R(i, i) = cj * ch;
  490. R(i, j) = sj * sc - cs;
  491. R(i, k) = sj * cc + ss;
  492. R(j, i) = cj * sh;
  493. R(j, j) = sj * ss + cc;
  494. R(j, k) = sj * cs - sc;
  495. R(k, i) = -sj;
  496. R(k, j) = cj * si;
  497. R(k, k) = cj * ci;
  498. }
  499. }
  500. template <typename EulerSystem, typename T>
  501. inline void RotationMatrixToEulerAngles(const T* R, T* euler) {
  502. RotationMatrixToEulerAngles<EulerSystem>(RowMajorAdapter3x3(R), euler);
  503. }
  504. template <typename EulerSystem, typename T, int row_stride, int col_stride>
  505. void RotationMatrixToEulerAngles(
  506. const MatrixAdapter<const T, row_stride, col_stride>& R, T* euler) {
  507. using std::atan2;
  508. using std::fpclassify;
  509. using std::hypot;
  510. const auto [i, j, k] = EulerSystem::kAxes;
  511. T ea[3];
  512. if constexpr (EulerSystem::kIsProperEuler) {
  513. const T sy = hypot(R(i, j), R(i, k));
  514. if (fpclassify(sy) != FP_ZERO) {
  515. ea[0] = atan2(R(i, j), R(i, k));
  516. ea[1] = atan2(sy, R(i, i));
  517. ea[2] = atan2(R(j, i), -R(k, i));
  518. } else {
  519. ea[0] = atan2(-R(j, k), R(j, j));
  520. ea[1] = atan2(sy, R(i, i));
  521. ea[2] = T(0.0);
  522. }
  523. } else {
  524. const T cy = hypot(R(i, i), R(j, i));
  525. if (fpclassify(cy) != FP_ZERO) {
  526. ea[0] = atan2(R(k, j), R(k, k));
  527. ea[1] = atan2(-R(k, i), cy);
  528. ea[2] = atan2(R(j, i), R(i, i));
  529. } else {
  530. ea[0] = atan2(-R(j, k), R(j, j));
  531. ea[1] = atan2(-R(k, i), cy);
  532. ea[2] = T(0.0);
  533. }
  534. }
  535. if constexpr (EulerSystem::kIsParityOdd) {
  536. ea[0] = -ea[0];
  537. ea[1] = -ea[1];
  538. ea[2] = -ea[2];
  539. }
  540. euler[1] = ea[1];
  541. if constexpr (EulerSystem::kIsIntrinsic) {
  542. euler[0] = ea[2];
  543. euler[2] = ea[0];
  544. } else {
  545. euler[0] = ea[0];
  546. euler[2] = ea[2];
  547. }
  548. // Proper euler angles are defined for angles in
  549. // [-pi, pi) x [0, pi / 2) x [-pi, pi)
  550. // which is enforced here
  551. if constexpr (EulerSystem::kIsProperEuler) {
  552. const T kPi(constants::pi);
  553. const T kTwoPi(2.0 * kPi);
  554. if (euler[1] < T(0.0) || ea[1] > kPi) {
  555. euler[0] += kPi;
  556. euler[1] = -euler[1];
  557. euler[2] -= kPi;
  558. }
  559. for (int i = 0; i < 3; ++i) {
  560. if (euler[i] < -kPi) {
  561. euler[i] += kTwoPi;
  562. } else if (euler[i] > kPi) {
  563. euler[i] -= kTwoPi;
  564. }
  565. }
  566. }
  567. }
  568. template <typename T>
  569. inline void EulerAnglesToRotationMatrix(const T* euler,
  570. const int row_stride_parameter,
  571. T* R) {
  572. EulerAnglesToRotationMatrix(euler, RowMajorAdapter3x3(R));
  573. }
  574. template <typename T, int row_stride, int col_stride>
  575. void EulerAnglesToRotationMatrix(
  576. const T* euler, const MatrixAdapter<T, row_stride, col_stride>& R) {
  577. const double kPi = 3.14159265358979323846;
  578. const T degrees_to_radians(kPi / 180.0);
  579. const T pitch(euler[0] * degrees_to_radians);
  580. const T roll(euler[1] * degrees_to_radians);
  581. const T yaw(euler[2] * degrees_to_radians);
  582. const T c1 = cos(yaw);
  583. const T s1 = sin(yaw);
  584. const T c2 = cos(roll);
  585. const T s2 = sin(roll);
  586. const T c3 = cos(pitch);
  587. const T s3 = sin(pitch);
  588. R(0, 0) = c1 * c2;
  589. R(0, 1) = -s1 * c3 + c1 * s2 * s3;
  590. R(0, 2) = s1 * s3 + c1 * s2 * c3;
  591. R(1, 0) = s1 * c2;
  592. R(1, 1) = c1 * c3 + s1 * s2 * s3;
  593. R(1, 2) = -c1 * s3 + s1 * s2 * c3;
  594. R(2, 0) = -s2;
  595. R(2, 1) = c2 * s3;
  596. R(2, 2) = c2 * c3;
  597. }
  598. template <typename T>
  599. inline void QuaternionToScaledRotation(const T q[4], T R[3 * 3]) {
  600. QuaternionToScaledRotation(q, RowMajorAdapter3x3(R));
  601. }
  602. template <typename T, int row_stride, int col_stride>
  603. inline void QuaternionToScaledRotation(
  604. const T q[4], const MatrixAdapter<T, row_stride, col_stride>& R) {
  605. // Make convenient names for elements of q.
  606. T a = q[0];
  607. T b = q[1];
  608. T c = q[2];
  609. T d = q[3];
  610. // This is not to eliminate common sub-expression, but to
  611. // make the lines shorter so that they fit in 80 columns!
  612. T aa = a * a;
  613. T ab = a * b;
  614. T ac = a * c;
  615. T ad = a * d;
  616. T bb = b * b;
  617. T bc = b * c;
  618. T bd = b * d;
  619. T cc = c * c;
  620. T cd = c * d;
  621. T dd = d * d;
  622. // clang-format off
  623. R(0, 0) = aa + bb - cc - dd; R(0, 1) = T(2) * (bc - ad); R(0, 2) = T(2) * (ac + bd);
  624. R(1, 0) = T(2) * (ad + bc); R(1, 1) = aa - bb + cc - dd; R(1, 2) = T(2) * (cd - ab);
  625. R(2, 0) = T(2) * (bd - ac); R(2, 1) = T(2) * (ab + cd); R(2, 2) = aa - bb - cc + dd;
  626. // clang-format on
  627. }
  628. template <typename T>
  629. inline void QuaternionToRotation(const T q[4], T R[3 * 3]) {
  630. QuaternionToRotation(q, RowMajorAdapter3x3(R));
  631. }
  632. template <typename T, int row_stride, int col_stride>
  633. inline void QuaternionToRotation(
  634. const T q[4], const MatrixAdapter<T, row_stride, col_stride>& R) {
  635. QuaternionToScaledRotation(q, R);
  636. T normalizer = q[0] * q[0] + q[1] * q[1] + q[2] * q[2] + q[3] * q[3];
  637. normalizer = T(1) / normalizer;
  638. for (int i = 0; i < 3; ++i) {
  639. for (int j = 0; j < 3; ++j) {
  640. R(i, j) *= normalizer;
  641. }
  642. }
  643. }
  644. template <typename T>
  645. inline void UnitQuaternionRotatePoint(const T q[4],
  646. const T pt[3],
  647. T result[3]) {
  648. DCHECK_NE(pt, result) << "Inplace rotation is not supported.";
  649. // clang-format off
  650. T uv0 = q[2] * pt[2] - q[3] * pt[1];
  651. T uv1 = q[3] * pt[0] - q[1] * pt[2];
  652. T uv2 = q[1] * pt[1] - q[2] * pt[0];
  653. uv0 += uv0;
  654. uv1 += uv1;
  655. uv2 += uv2;
  656. result[0] = pt[0] + q[0] * uv0;
  657. result[1] = pt[1] + q[0] * uv1;
  658. result[2] = pt[2] + q[0] * uv2;
  659. result[0] += q[2] * uv2 - q[3] * uv1;
  660. result[1] += q[3] * uv0 - q[1] * uv2;
  661. result[2] += q[1] * uv1 - q[2] * uv0;
  662. // clang-format on
  663. }
  664. template <typename T>
  665. inline void QuaternionRotatePoint(const T q[4], const T pt[3], T result[3]) {
  666. DCHECK_NE(pt, result) << "Inplace rotation is not supported.";
  667. // 'scale' is 1 / norm(q).
  668. const T scale =
  669. T(1) / sqrt(q[0] * q[0] + q[1] * q[1] + q[2] * q[2] + q[3] * q[3]);
  670. // Make unit-norm version of q.
  671. const T unit[4] = {
  672. scale * q[0],
  673. scale * q[1],
  674. scale * q[2],
  675. scale * q[3],
  676. };
  677. UnitQuaternionRotatePoint(unit, pt, result);
  678. }
  679. template <typename T>
  680. inline void QuaternionProduct(const T z[4], const T w[4], T zw[4]) {
  681. DCHECK_NE(z, zw) << "Inplace quaternion product is not supported.";
  682. DCHECK_NE(w, zw) << "Inplace quaternion product is not supported.";
  683. // clang-format off
  684. zw[0] = z[0] * w[0] - z[1] * w[1] - z[2] * w[2] - z[3] * w[3];
  685. zw[1] = z[0] * w[1] + z[1] * w[0] + z[2] * w[3] - z[3] * w[2];
  686. zw[2] = z[0] * w[2] - z[1] * w[3] + z[2] * w[0] + z[3] * w[1];
  687. zw[3] = z[0] * w[3] + z[1] * w[2] - z[2] * w[1] + z[3] * w[0];
  688. // clang-format on
  689. }
  690. // xy = x cross y;
  691. template <typename T>
  692. inline void CrossProduct(const T x[3], const T y[3], T x_cross_y[3]) {
  693. DCHECK_NE(x, x_cross_y) << "Inplace cross product is not supported.";
  694. DCHECK_NE(y, x_cross_y) << "Inplace cross product is not supported.";
  695. x_cross_y[0] = x[1] * y[2] - x[2] * y[1];
  696. x_cross_y[1] = x[2] * y[0] - x[0] * y[2];
  697. x_cross_y[2] = x[0] * y[1] - x[1] * y[0];
  698. }
  699. template <typename T>
  700. inline T DotProduct(const T x[3], const T y[3]) {
  701. return (x[0] * y[0] + x[1] * y[1] + x[2] * y[2]);
  702. }
  703. template <typename T>
  704. inline void AngleAxisRotatePoint(const T angle_axis[3],
  705. const T pt[3],
  706. T result[3]) {
  707. DCHECK_NE(pt, result) << "Inplace rotation is not supported.";
  708. using std::fpclassify;
  709. using std::hypot;
  710. const T theta = hypot(angle_axis[0], angle_axis[1], angle_axis[2]);
  711. if (fpclassify(theta) != FP_ZERO) {
  712. // Away from zero, use the rodriguez formula
  713. //
  714. // result = pt costheta +
  715. // (w x pt) * sintheta +
  716. // w (w . pt) (1 - costheta)
  717. //
  718. // We want to be careful to only evaluate the square root if the
  719. // norm of the angle_axis vector is greater than zero. Otherwise
  720. // we get a division by zero.
  721. //
  722. const T costheta = cos(theta);
  723. const T sintheta = sin(theta);
  724. const T theta_inverse = T(1.0) / theta;
  725. const T w[3] = {angle_axis[0] * theta_inverse,
  726. angle_axis[1] * theta_inverse,
  727. angle_axis[2] * theta_inverse};
  728. // Explicitly inlined evaluation of the cross product for
  729. // performance reasons.
  730. const T w_cross_pt[3] = {w[1] * pt[2] - w[2] * pt[1],
  731. w[2] * pt[0] - w[0] * pt[2],
  732. w[0] * pt[1] - w[1] * pt[0]};
  733. const T tmp =
  734. (w[0] * pt[0] + w[1] * pt[1] + w[2] * pt[2]) * (T(1.0) - costheta);
  735. result[0] = pt[0] * costheta + w_cross_pt[0] * sintheta + w[0] * tmp;
  736. result[1] = pt[1] * costheta + w_cross_pt[1] * sintheta + w[1] * tmp;
  737. result[2] = pt[2] * costheta + w_cross_pt[2] * sintheta + w[2] * tmp;
  738. } else {
  739. // At zero, the first order Taylor approximation of the rotation
  740. // matrix R corresponding to a vector w and angle theta is
  741. //
  742. // R = I + hat(w) * sin(theta)
  743. //
  744. // But sintheta ~ theta and theta * w = angle_axis, which gives us
  745. //
  746. // R = I + hat(angle_axis)
  747. //
  748. // and actually performing multiplication with the point pt, gives us
  749. // R * pt = pt + angle_axis x pt.
  750. //
  751. // Switching to the Taylor expansion at zero provides meaningful
  752. // derivatives when evaluated using Jets.
  753. //
  754. // Explicitly inlined evaluation of the cross product for
  755. // performance reasons.
  756. const T w_cross_pt[3] = {angle_axis[1] * pt[2] - angle_axis[2] * pt[1],
  757. angle_axis[2] * pt[0] - angle_axis[0] * pt[2],
  758. angle_axis[0] * pt[1] - angle_axis[1] * pt[0]};
  759. result[0] = pt[0] + w_cross_pt[0];
  760. result[1] = pt[1] + w_cross_pt[1];
  761. result[2] = pt[2] + w_cross_pt[2];
  762. }
  763. }
  764. } // namespace ceres
  765. #endif // CERES_PUBLIC_ROTATION_H_