so3.hpp 28 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855
  1. /// @file
  2. /// Special orthogonal group SO(3) - rotation in 3d.
  3. #ifndef SOPHUS_SO3_HPP
  4. #define SOPHUS_SO3_HPP
  5. #include "rotation_matrix.hpp"
  6. #include "so2.hpp"
  7. #include "types.hpp"
  8. // Include only the selective set of Eigen headers that we need.
  9. // This helps when using Sophus with unusual compilers, like nvcc.
  10. #include <Eigen/src/Geometry/OrthoMethods.h>
  11. #include <Eigen/src/Geometry/Quaternion.h>
  12. #include <Eigen/src/Geometry/RotationBase.h>
  13. namespace Sophus {
  14. template <class Scalar_, int Options = 0>
  15. class SO3;
  16. using SO3d = SO3<double>;
  17. using SO3f = SO3<float>;
  18. } // namespace Sophus
  19. namespace Eigen {
  20. namespace internal {
  21. template <class Scalar_, int Options_>
  22. struct traits<Sophus::SO3<Scalar_, Options_>> {
  23. static constexpr int Options = Options_;
  24. using Scalar = Scalar_;
  25. using QuaternionType = Eigen::Quaternion<Scalar, Options>;
  26. };
  27. template <class Scalar_, int Options_>
  28. struct traits<Map<Sophus::SO3<Scalar_>, Options_>>
  29. : traits<Sophus::SO3<Scalar_, Options_>> {
  30. static constexpr int Options = Options_;
  31. using Scalar = Scalar_;
  32. using QuaternionType = Map<Eigen::Quaternion<Scalar>, Options>;
  33. };
  34. template <class Scalar_, int Options_>
  35. struct traits<Map<Sophus::SO3<Scalar_> const, Options_>>
  36. : traits<Sophus::SO3<Scalar_, Options_> const> {
  37. static constexpr int Options = Options_;
  38. using Scalar = Scalar_;
  39. using QuaternionType = Map<Eigen::Quaternion<Scalar> const, Options>;
  40. };
  41. } // namespace internal
  42. } // namespace Eigen
  43. namespace Sophus {
  44. /// SO3 base type - implements SO3 class but is storage agnostic.
  45. ///
  46. /// SO(3) is the group of rotations in 3d. As a matrix group, it is the set of
  47. /// matrices which are orthogonal such that ``R * R' = I`` (with ``R'`` being
  48. /// the transpose of ``R``) and have a positive determinant. In particular, the
  49. /// determinant is 1. Internally, the group is represented as a unit quaternion.
  50. /// Unit quaternion can be seen as members of the special unitary group SU(2).
  51. /// SU(2) is a double cover of SO(3). Hence, for every rotation matrix ``R``,
  52. /// there exist two unit quaternions: ``(r, v)`` and ``(-r, -v)``, with ``r``
  53. /// the real part and ``v`` being the imaginary 3-vector part of the quaternion.
  54. ///
  55. /// SO(3) is a compact, but non-commutative group. First it is compact since the
  56. /// set of rotation matrices is a closed and bounded set. Second it is
  57. /// non-commutative since the equation ``R_1 * R_2 = R_2 * R_1`` does not hold
  58. /// in general. For example rotating an object by some degrees about its
  59. /// ``x``-axis and then by some degrees about its y axis, does not lead to the
  60. /// same orientation when rotation first about ``y`` and then about ``x``.
  61. ///
  62. /// Class invariant: The 2-norm of ``unit_quaternion`` must be close to 1.
  63. /// Technically speaking, it must hold that:
  64. ///
  65. /// ``|unit_quaternion().squaredNorm() - 1| <= Constants::epsilon()``.
  66. template <class Derived>
  67. class SO3Base {
  68. public:
  69. static constexpr int Options = Eigen::internal::traits<Derived>::Options;
  70. using Scalar = typename Eigen::internal::traits<Derived>::Scalar;
  71. using QuaternionType =
  72. typename Eigen::internal::traits<Derived>::QuaternionType;
  73. using QuaternionTemporaryType = Eigen::Quaternion<Scalar, Options>;
  74. /// Degrees of freedom of group, number of dimensions in tangent space.
  75. static int constexpr DoF = 3;
  76. /// Number of internal parameters used (quaternion is a 4-tuple).
  77. static int constexpr num_parameters = 4;
  78. /// Group transformations are 3x3 matrices.
  79. static int constexpr N = 3;
  80. using Transformation = Matrix<Scalar, N, N>;
  81. using Point = Vector3<Scalar>;
  82. using HomogeneousPoint = Vector4<Scalar>;
  83. using Line = ParametrizedLine3<Scalar>;
  84. using Tangent = Vector<Scalar, DoF>;
  85. using Adjoint = Matrix<Scalar, DoF, DoF>;
  86. struct TangentAndTheta {
  87. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  88. Tangent tangent;
  89. Scalar theta;
  90. };
  91. /// For binary operations the return type is determined with the
  92. /// ScalarBinaryOpTraits feature of Eigen. This allows mixing concrete and Map
  93. /// types, as well as other compatible scalar types such as Ceres::Jet and
  94. /// double scalars with SO3 operations.
  95. template <typename OtherDerived>
  96. using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<
  97. Scalar, typename OtherDerived::Scalar>::ReturnType;
  98. template <typename OtherDerived>
  99. using SO3Product = SO3<ReturnScalar<OtherDerived>>;
  100. template <typename PointDerived>
  101. using PointProduct = Vector3<ReturnScalar<PointDerived>>;
  102. template <typename HPointDerived>
  103. using HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived>>;
  104. /// Adjoint transformation
  105. //
  106. /// This function return the adjoint transformation ``Ad`` of the group
  107. /// element ``A`` such that for all ``x`` it holds that
  108. /// ``hat(Ad_A * x) = A * hat(x) A^{-1}``. See hat-operator below.
  109. //
  110. /// For SO(3), it simply returns the rotation matrix corresponding to ``A``.
  111. ///
  112. SOPHUS_FUNC Adjoint Adj() const { return matrix(); }
  113. /// Extract rotation angle about canonical X-axis
  114. ///
  115. template <class S = Scalar>
  116. SOPHUS_FUNC enable_if_t<std::is_floating_point<S>::value, S> angleX() const {
  117. Sophus::Matrix3<Scalar> R = matrix();
  118. Sophus::Matrix2<Scalar> Rx = R.template block<2, 2>(1, 1);
  119. return SO2<Scalar>(makeRotationMatrix(Rx)).log();
  120. }
  121. /// Extract rotation angle about canonical Y-axis
  122. ///
  123. template <class S = Scalar>
  124. SOPHUS_FUNC enable_if_t<std::is_floating_point<S>::value, S> angleY() const {
  125. Sophus::Matrix3<Scalar> R = matrix();
  126. Sophus::Matrix2<Scalar> Ry;
  127. // clang-format off
  128. Ry <<
  129. R(0, 0), R(2, 0),
  130. R(0, 2), R(2, 2);
  131. // clang-format on
  132. return SO2<Scalar>(makeRotationMatrix(Ry)).log();
  133. }
  134. /// Extract rotation angle about canonical Z-axis
  135. ///
  136. template <class S = Scalar>
  137. SOPHUS_FUNC enable_if_t<std::is_floating_point<S>::value, S> angleZ() const {
  138. Sophus::Matrix3<Scalar> R = matrix();
  139. Sophus::Matrix2<Scalar> Rz = R.template block<2, 2>(0, 0);
  140. return SO2<Scalar>(makeRotationMatrix(Rz)).log();
  141. }
  142. /// Returns copy of instance casted to NewScalarType.
  143. ///
  144. template <class NewScalarType>
  145. SOPHUS_FUNC SO3<NewScalarType> cast() const {
  146. return SO3<NewScalarType>(unit_quaternion().template cast<NewScalarType>());
  147. }
  148. /// This provides unsafe read/write access to internal data. SO(3) is
  149. /// represented by an Eigen::Quaternion (four parameters). When using direct
  150. /// write access, the user needs to take care of that the quaternion stays
  151. /// normalized.
  152. ///
  153. /// Note: The first three Scalars represent the imaginary parts, while the
  154. /// forth Scalar represent the real part.
  155. ///
  156. SOPHUS_FUNC Scalar* data() {
  157. return unit_quaternion_nonconst().coeffs().data();
  158. }
  159. /// Const version of data() above.
  160. ///
  161. SOPHUS_FUNC Scalar const* data() const {
  162. return unit_quaternion().coeffs().data();
  163. }
  164. /// Returns derivative of this * SO3::exp(x) wrt. x at x=0.
  165. ///
  166. SOPHUS_FUNC Matrix<Scalar, num_parameters, DoF> Dx_this_mul_exp_x_at_0()
  167. const {
  168. Matrix<Scalar, num_parameters, DoF> J;
  169. Eigen::Quaternion<Scalar> const q = unit_quaternion();
  170. Scalar const c0 = Scalar(0.5) * q.w();
  171. Scalar const c1 = Scalar(0.5) * q.z();
  172. Scalar const c2 = -c1;
  173. Scalar const c3 = Scalar(0.5) * q.y();
  174. Scalar const c4 = Scalar(0.5) * q.x();
  175. Scalar const c5 = -c4;
  176. Scalar const c6 = -c3;
  177. J(0, 0) = c0;
  178. J(0, 1) = c2;
  179. J(0, 2) = c3;
  180. J(1, 0) = c1;
  181. J(1, 1) = c0;
  182. J(1, 2) = c5;
  183. J(2, 0) = c6;
  184. J(2, 1) = c4;
  185. J(2, 2) = c0;
  186. J(3, 0) = c5;
  187. J(3, 1) = c6;
  188. J(3, 2) = c2;
  189. return J;
  190. }
  191. /// Returns internal parameters of SO(3).
  192. ///
  193. /// It returns (q.imag[0], q.imag[1], q.imag[2], q.real), with q being the
  194. /// unit quaternion.
  195. ///
  196. SOPHUS_FUNC Sophus::Vector<Scalar, num_parameters> params() const {
  197. return unit_quaternion().coeffs();
  198. }
  199. /// Returns group inverse.
  200. ///
  201. SOPHUS_FUNC SO3<Scalar> inverse() const {
  202. return SO3<Scalar>(unit_quaternion().conjugate());
  203. }
  204. /// Logarithmic map
  205. ///
  206. /// Computes the logarithm, the inverse of the group exponential which maps
  207. /// element of the group (rotation matrices) to elements of the tangent space
  208. /// (rotation-vector).
  209. ///
  210. /// To be specific, this function computes ``vee(logmat(.))`` with
  211. /// ``logmat(.)`` being the matrix logarithm and ``vee(.)`` the vee-operator
  212. /// of SO(3).
  213. ///
  214. SOPHUS_FUNC Tangent log() const { return logAndTheta().tangent; }
  215. /// As above, but also returns ``theta = |omega|``.
  216. ///
  217. SOPHUS_FUNC TangentAndTheta logAndTheta() const {
  218. TangentAndTheta J;
  219. using std::abs;
  220. using std::atan;
  221. using std::sqrt;
  222. Scalar squared_n = unit_quaternion().vec().squaredNorm();
  223. Scalar w = unit_quaternion().w();
  224. Scalar two_atan_nbyw_by_n;
  225. /// Atan-based log thanks to
  226. ///
  227. /// C. Hertzberg et al.:
  228. /// "Integrating Generic Sensor Fusion Algorithms with Sound State
  229. /// Representation through Encapsulation of Manifolds"
  230. /// Information Fusion, 2011
  231. if (squared_n < Constants<Scalar>::epsilon() * Constants<Scalar>::epsilon()) {
  232. // If quaternion is normalized and n=0, then w should be 1;
  233. // w=0 should never happen here!
  234. SOPHUS_ENSURE(abs(w) >= Constants<Scalar>::epsilon(),
  235. "Quaternion (%) should be normalized!",
  236. unit_quaternion().coeffs().transpose());
  237. Scalar squared_w = w * w;
  238. two_atan_nbyw_by_n =
  239. Scalar(2) / w - Scalar(2.0/3.0) * (squared_n) / (w * squared_w);
  240. J.theta = Scalar(2) * squared_n / w;
  241. } else {
  242. Scalar n = sqrt(squared_n);
  243. if (abs(w) < Constants<Scalar>::epsilon()) {
  244. if (w > Scalar(0)) {
  245. two_atan_nbyw_by_n = Constants<Scalar>::pi() / n;
  246. } else {
  247. two_atan_nbyw_by_n = -Constants<Scalar>::pi() / n;
  248. }
  249. } else {
  250. two_atan_nbyw_by_n = Scalar(2) * atan(n / w) / n;
  251. }
  252. J.theta = two_atan_nbyw_by_n * n;
  253. }
  254. J.tangent = two_atan_nbyw_by_n * unit_quaternion().vec();
  255. return J;
  256. }
  257. /// It re-normalizes ``unit_quaternion`` to unit length.
  258. ///
  259. /// Note: Because of the class invariant, there is typically no need to call
  260. /// this function directly.
  261. ///
  262. SOPHUS_FUNC void normalize() {
  263. Scalar length = unit_quaternion_nonconst().norm();
  264. SOPHUS_ENSURE(length >= Constants<Scalar>::epsilon(),
  265. "Quaternion (%) should not be close to zero!",
  266. unit_quaternion_nonconst().coeffs().transpose());
  267. unit_quaternion_nonconst().coeffs() /= length;
  268. }
  269. /// Returns 3x3 matrix representation of the instance.
  270. ///
  271. /// For SO(3), the matrix representation is an orthogonal matrix ``R`` with
  272. /// ``det(R)=1``, thus the so-called "rotation matrix".
  273. ///
  274. SOPHUS_FUNC Transformation matrix() const {
  275. return unit_quaternion().toRotationMatrix();
  276. }
  277. /// Assignment operator.
  278. ///
  279. SOPHUS_FUNC SO3Base& operator=(SO3Base const& other) = default;
  280. /// Assignment-like operator from OtherDerived.
  281. ///
  282. template <class OtherDerived>
  283. SOPHUS_FUNC SO3Base<Derived>& operator=(SO3Base<OtherDerived> const& other) {
  284. unit_quaternion_nonconst() = other.unit_quaternion();
  285. return *this;
  286. }
  287. /// Group multiplication, which is rotation concatenation.
  288. ///
  289. template <typename OtherDerived>
  290. SOPHUS_FUNC SO3Product<OtherDerived> operator*(
  291. SO3Base<OtherDerived> const& other) const {
  292. using QuaternionProductType =
  293. typename SO3Product<OtherDerived>::QuaternionType;
  294. const QuaternionType& a = unit_quaternion();
  295. const typename OtherDerived::QuaternionType& b = other.unit_quaternion();
  296. /// NOTE: We cannot use Eigen's Quaternion multiplication because it always
  297. /// returns a Quaternion of the same Scalar as this object, so it is not
  298. /// able to multiple Jets and doubles correctly.
  299. return SO3Product<OtherDerived>(QuaternionProductType(
  300. a.w() * b.w() - a.x() * b.x() - a.y() * b.y() - a.z() * b.z(),
  301. a.w() * b.x() + a.x() * b.w() + a.y() * b.z() - a.z() * b.y(),
  302. a.w() * b.y() + a.y() * b.w() + a.z() * b.x() - a.x() * b.z(),
  303. a.w() * b.z() + a.z() * b.w() + a.x() * b.y() - a.y() * b.x()));
  304. }
  305. /// Group action on 3-points.
  306. ///
  307. /// This function rotates a 3 dimensional point ``p`` by the SO3 element
  308. /// ``bar_R_foo`` (= rotation matrix): ``p_bar = bar_R_foo * p_foo``.
  309. ///
  310. /// Since SO3 is internally represented by a unit quaternion ``q``, it is
  311. /// implemented as ``p_bar = q * p_foo * q^{*}``
  312. /// with ``q^{*}`` being the quaternion conjugate of ``q``.
  313. ///
  314. /// Geometrically, ``p`` is rotated by angle ``|omega|`` around the
  315. /// axis ``omega/|omega|`` with ``omega := vee(log(bar_R_foo))``.
  316. ///
  317. /// For ``vee``-operator, see below.
  318. ///
  319. template <typename PointDerived,
  320. typename = typename std::enable_if<
  321. IsFixedSizeVector<PointDerived, 3>::value>::type>
  322. SOPHUS_FUNC PointProduct<PointDerived> operator*(
  323. Eigen::MatrixBase<PointDerived> const& p) const {
  324. /// NOTE: We cannot use Eigen's Quaternion transformVector because it always
  325. /// returns a Vector3 of the same Scalar as this quaternion, so it is not
  326. /// able to be applied to Jets and doubles correctly.
  327. const QuaternionType& q = unit_quaternion();
  328. PointProduct<PointDerived> uv = q.vec().cross(p);
  329. uv += uv;
  330. return p + q.w() * uv + q.vec().cross(uv);
  331. }
  332. /// Group action on homogeneous 3-points. See above for more details.
  333. template <typename HPointDerived,
  334. typename = typename std::enable_if<
  335. IsFixedSizeVector<HPointDerived, 4>::value>::type>
  336. SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> operator*(
  337. Eigen::MatrixBase<HPointDerived> const& p) const {
  338. const auto rp = *this * p.template head<3>();
  339. return HomogeneousPointProduct<HPointDerived>(rp(0), rp(1), rp(2), p(3));
  340. }
  341. /// Group action on lines.
  342. ///
  343. /// This function rotates a parametrized line ``l(t) = o + t * d`` by the SO3
  344. /// element:
  345. ///
  346. /// Both direction ``d`` and origin ``o`` are rotated as a 3 dimensional point
  347. ///
  348. SOPHUS_FUNC Line operator*(Line const& l) const {
  349. return Line((*this) * l.origin(), (*this) * l.direction());
  350. }
  351. /// In-place group multiplication. This method is only valid if the return
  352. /// type of the multiplication is compatible with this SO3's Scalar type.
  353. ///
  354. template <typename OtherDerived,
  355. typename = typename std::enable_if<
  356. std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
  357. SOPHUS_FUNC SO3Base<Derived>& operator*=(SO3Base<OtherDerived> const& other) {
  358. *static_cast<Derived*>(this) = *this * other;
  359. return *this;
  360. }
  361. /// Takes in quaternion, and normalizes it.
  362. ///
  363. /// Precondition: The quaternion must not be close to zero.
  364. ///
  365. SOPHUS_FUNC void setQuaternion(Eigen::Quaternion<Scalar> const& quaternion) {
  366. unit_quaternion_nonconst() = quaternion;
  367. normalize();
  368. }
  369. /// Accessor of unit quaternion.
  370. ///
  371. SOPHUS_FUNC QuaternionType const& unit_quaternion() const {
  372. return static_cast<Derived const*>(this)->unit_quaternion();
  373. }
  374. private:
  375. /// Mutator of unit_quaternion is private to ensure class invariant. That is
  376. /// the quaternion must stay close to unit length.
  377. ///
  378. SOPHUS_FUNC QuaternionType& unit_quaternion_nonconst() {
  379. return static_cast<Derived*>(this)->unit_quaternion_nonconst();
  380. }
  381. };
  382. /// SO3 using default storage; derived from SO3Base.
  383. template <class Scalar_, int Options>
  384. class SO3 : public SO3Base<SO3<Scalar_, Options>> {
  385. public:
  386. using Base = SO3Base<SO3<Scalar_, Options>>;
  387. static int constexpr DoF = Base::DoF;
  388. static int constexpr num_parameters = Base::num_parameters;
  389. using Scalar = Scalar_;
  390. using Transformation = typename Base::Transformation;
  391. using Point = typename Base::Point;
  392. using HomogeneousPoint = typename Base::HomogeneousPoint;
  393. using Tangent = typename Base::Tangent;
  394. using Adjoint = typename Base::Adjoint;
  395. using QuaternionMember = Eigen::Quaternion<Scalar, Options>;
  396. /// ``Base`` is friend so unit_quaternion_nonconst can be accessed from
  397. /// ``Base``.
  398. friend class SO3Base<SO3<Scalar, Options>>;
  399. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  400. /// Default constructor initializes unit quaternion to identity rotation.
  401. ///
  402. SOPHUS_FUNC SO3()
  403. : unit_quaternion_(Scalar(1), Scalar(0), Scalar(0), Scalar(0)) {}
  404. /// Copy constructor
  405. ///
  406. SOPHUS_FUNC SO3(SO3 const& other) = default;
  407. /// Copy-like constructor from OtherDerived.
  408. ///
  409. template <class OtherDerived>
  410. SOPHUS_FUNC SO3(SO3Base<OtherDerived> const& other)
  411. : unit_quaternion_(other.unit_quaternion()) {}
  412. /// Constructor from rotation matrix
  413. ///
  414. /// Precondition: rotation matrix needs to be orthogonal with determinant
  415. /// of 1.
  416. ///
  417. SOPHUS_FUNC SO3(Transformation const& R) : unit_quaternion_(R) {
  418. SOPHUS_ENSURE(isOrthogonal(R), "R is not orthogonal:\n %",
  419. R * R.transpose());
  420. SOPHUS_ENSURE(R.determinant() > Scalar(0), "det(R) is not positive: %",
  421. R.determinant());
  422. }
  423. /// Constructor from quaternion
  424. ///
  425. /// Precondition: quaternion must not be close to zero.
  426. ///
  427. template <class D>
  428. SOPHUS_FUNC explicit SO3(Eigen::QuaternionBase<D> const& quat)
  429. : unit_quaternion_(quat) {
  430. static_assert(
  431. std::is_same<typename Eigen::QuaternionBase<D>::Scalar, Scalar>::value,
  432. "Input must be of same scalar type");
  433. Base::normalize();
  434. }
  435. /// Accessor of unit quaternion.
  436. ///
  437. SOPHUS_FUNC QuaternionMember const& unit_quaternion() const {
  438. return unit_quaternion_;
  439. }
  440. /// Returns derivative of exp(x) wrt. x.
  441. ///
  442. SOPHUS_FUNC static Sophus::Matrix<Scalar, num_parameters, DoF> Dx_exp_x(
  443. Tangent const& omega) {
  444. using std::cos;
  445. using std::exp;
  446. using std::sin;
  447. using std::sqrt;
  448. Scalar const c0 = omega[0] * omega[0];
  449. Scalar const c1 = omega[1] * omega[1];
  450. Scalar const c2 = omega[2] * omega[2];
  451. Scalar const c3 = c0 + c1 + c2;
  452. if (c3 < Constants<Scalar>::epsilon()) {
  453. return Dx_exp_x_at_0();
  454. }
  455. Scalar const c4 = sqrt(c3);
  456. Scalar const c5 = 1.0 / c4;
  457. Scalar const c6 = 0.5 * c4;
  458. Scalar const c7 = sin(c6);
  459. Scalar const c8 = c5 * c7;
  460. Scalar const c9 = pow(c3, -3.0L / 2.0L);
  461. Scalar const c10 = c7 * c9;
  462. Scalar const c11 = Scalar(1.0) / c3;
  463. Scalar const c12 = cos(c6);
  464. Scalar const c13 = Scalar(0.5) * c11 * c12;
  465. Scalar const c14 = c7 * c9 * omega[0];
  466. Scalar const c15 = Scalar(0.5) * c11 * c12 * omega[0];
  467. Scalar const c16 = -c14 * omega[1] + c15 * omega[1];
  468. Scalar const c17 = -c14 * omega[2] + c15 * omega[2];
  469. Scalar const c18 = omega[1] * omega[2];
  470. Scalar const c19 = -c10 * c18 + c13 * c18;
  471. Scalar const c20 = Scalar(0.5) * c5 * c7;
  472. Sophus::Matrix<Scalar, num_parameters, DoF> J;
  473. J(0, 0) = -c0 * c10 + c0 * c13 + c8;
  474. J(0, 1) = c16;
  475. J(0, 2) = c17;
  476. J(1, 0) = c16;
  477. J(1, 1) = -c1 * c10 + c1 * c13 + c8;
  478. J(1, 2) = c19;
  479. J(2, 0) = c17;
  480. J(2, 1) = c19;
  481. J(2, 2) = -c10 * c2 + c13 * c2 + c8;
  482. J(3, 0) = -c20 * omega[0];
  483. J(3, 1) = -c20 * omega[1];
  484. J(3, 2) = -c20 * omega[2];
  485. return J;
  486. }
  487. /// Returns derivative of exp(x) wrt. x_i at x=0.
  488. ///
  489. SOPHUS_FUNC static Sophus::Matrix<Scalar, num_parameters, DoF>
  490. Dx_exp_x_at_0() {
  491. Sophus::Matrix<Scalar, num_parameters, DoF> J;
  492. // clang-format off
  493. J << Scalar(0.5), Scalar(0), Scalar(0),
  494. Scalar(0), Scalar(0.5), Scalar(0),
  495. Scalar(0), Scalar(0), Scalar(0.5),
  496. Scalar(0), Scalar(0), Scalar(0);
  497. // clang-format on
  498. return J;
  499. }
  500. /// Returns derivative of exp(x).matrix() wrt. ``x_i at x=0``.
  501. ///
  502. SOPHUS_FUNC static Transformation Dxi_exp_x_matrix_at_0(int i) {
  503. return generator(i);
  504. }
  505. /// Group exponential
  506. ///
  507. /// This functions takes in an element of tangent space (= rotation vector
  508. /// ``omega``) and returns the corresponding element of the group SO(3).
  509. ///
  510. /// To be more specific, this function computes ``expmat(hat(omega))``
  511. /// with ``expmat(.)`` being the matrix exponential and ``hat(.)`` being the
  512. /// hat()-operator of SO(3).
  513. ///
  514. SOPHUS_FUNC static SO3<Scalar> exp(Tangent const& omega) {
  515. Scalar theta;
  516. return expAndTheta(omega, &theta);
  517. }
  518. /// As above, but also returns ``theta = |omega|`` as out-parameter.
  519. ///
  520. /// Precondition: ``theta`` must not be ``nullptr``.
  521. ///
  522. SOPHUS_FUNC static SO3<Scalar> expAndTheta(Tangent const& omega,
  523. Scalar* theta) {
  524. SOPHUS_ENSURE(theta != nullptr, "must not be nullptr.");
  525. using std::abs;
  526. using std::cos;
  527. using std::sin;
  528. using std::sqrt;
  529. Scalar theta_sq = omega.squaredNorm();
  530. Scalar imag_factor;
  531. Scalar real_factor;
  532. if (theta_sq <
  533. Constants<Scalar>::epsilon() * Constants<Scalar>::epsilon()) {
  534. *theta = Scalar(0);
  535. Scalar theta_po4 = theta_sq * theta_sq;
  536. imag_factor = Scalar(0.5) - Scalar(1.0 / 48.0) * theta_sq +
  537. Scalar(1.0 / 3840.0) * theta_po4;
  538. real_factor = Scalar(1) - Scalar(1.0 / 8.0) * theta_sq +
  539. Scalar(1.0 / 384.0) * theta_po4;
  540. } else {
  541. *theta = sqrt(theta_sq);
  542. Scalar half_theta = Scalar(0.5) * (*theta);
  543. Scalar sin_half_theta = sin(half_theta);
  544. imag_factor = sin_half_theta / (*theta);
  545. real_factor = cos(half_theta);
  546. }
  547. SO3 q;
  548. q.unit_quaternion_nonconst() =
  549. QuaternionMember(real_factor, imag_factor * omega.x(),
  550. imag_factor * omega.y(), imag_factor * omega.z());
  551. SOPHUS_ENSURE(abs(q.unit_quaternion().squaredNorm() - Scalar(1)) <
  552. Sophus::Constants<Scalar>::epsilon(),
  553. "SO3::exp failed! omega: %, real: %, img: %",
  554. omega.transpose(), real_factor, imag_factor);
  555. return q;
  556. }
  557. /// Returns closest SO3 given arbitrary 3x3 matrix.
  558. ///
  559. template <class S = Scalar>
  560. static SOPHUS_FUNC enable_if_t<std::is_floating_point<S>::value, SO3>
  561. fitToSO3(Transformation const& R) {
  562. return SO3(::Sophus::makeRotationMatrix(R));
  563. }
  564. /// Returns the ith infinitesimal generators of SO(3).
  565. ///
  566. /// The infinitesimal generators of SO(3) are:
  567. ///
  568. /// ```
  569. /// | 0 0 0 |
  570. /// G_0 = | 0 0 -1 |
  571. /// | 0 1 0 |
  572. ///
  573. /// | 0 0 1 |
  574. /// G_1 = | 0 0 0 |
  575. /// | -1 0 0 |
  576. ///
  577. /// | 0 -1 0 |
  578. /// G_2 = | 1 0 0 |
  579. /// | 0 0 0 |
  580. /// ```
  581. ///
  582. /// Precondition: ``i`` must be 0, 1 or 2.
  583. ///
  584. SOPHUS_FUNC static Transformation generator(int i) {
  585. SOPHUS_ENSURE(i >= 0 && i <= 2, "i should be in range [0,2].");
  586. Tangent e;
  587. e.setZero();
  588. e[i] = Scalar(1);
  589. return hat(e);
  590. }
  591. /// hat-operator
  592. ///
  593. /// It takes in the 3-vector representation ``omega`` (= rotation vector) and
  594. /// returns the corresponding matrix representation of Lie algebra element.
  595. ///
  596. /// Formally, the hat()-operator of SO(3) is defined as
  597. ///
  598. /// ``hat(.): R^3 -> R^{3x3}, hat(omega) = sum_i omega_i * G_i``
  599. /// (for i=0,1,2)
  600. ///
  601. /// with ``G_i`` being the ith infinitesimal generator of SO(3).
  602. ///
  603. /// The corresponding inverse is the vee()-operator, see below.
  604. ///
  605. SOPHUS_FUNC static Transformation hat(Tangent const& omega) {
  606. Transformation Omega;
  607. // clang-format off
  608. Omega <<
  609. Scalar(0), -omega(2), omega(1),
  610. omega(2), Scalar(0), -omega(0),
  611. -omega(1), omega(0), Scalar(0);
  612. // clang-format on
  613. return Omega;
  614. }
  615. /// Lie bracket
  616. ///
  617. /// It computes the Lie bracket of SO(3). To be more specific, it computes
  618. ///
  619. /// ``[omega_1, omega_2]_so3 := vee([hat(omega_1), hat(omega_2)])``
  620. ///
  621. /// with ``[A,B] := AB-BA`` being the matrix commutator, ``hat(.)`` the
  622. /// hat()-operator and ``vee(.)`` the vee()-operator of SO3.
  623. ///
  624. /// For the Lie algebra so3, the Lie bracket is simply the cross product:
  625. ///
  626. /// ``[omega_1, omega_2]_so3 = omega_1 x omega_2.``
  627. ///
  628. SOPHUS_FUNC static Tangent lieBracket(Tangent const& omega1,
  629. Tangent const& omega2) {
  630. return omega1.cross(omega2);
  631. }
  632. /// Construct x-axis rotation.
  633. ///
  634. static SOPHUS_FUNC SO3 rotX(Scalar const& x) {
  635. return SO3::exp(Sophus::Vector3<Scalar>(x, Scalar(0), Scalar(0)));
  636. }
  637. /// Construct y-axis rotation.
  638. ///
  639. static SOPHUS_FUNC SO3 rotY(Scalar const& y) {
  640. return SO3::exp(Sophus::Vector3<Scalar>(Scalar(0), y, Scalar(0)));
  641. }
  642. /// Construct z-axis rotation.
  643. ///
  644. static SOPHUS_FUNC SO3 rotZ(Scalar const& z) {
  645. return SO3::exp(Sophus::Vector3<Scalar>(Scalar(0), Scalar(0), z));
  646. }
  647. /// Draw uniform sample from SO(3) manifold.
  648. /// Based on: http://planning.cs.uiuc.edu/node198.html
  649. ///
  650. template <class UniformRandomBitGenerator>
  651. static SO3 sampleUniform(UniformRandomBitGenerator& generator) {
  652. static_assert(IsUniformRandomBitGenerator<UniformRandomBitGenerator>::value,
  653. "generator must meet the UniformRandomBitGenerator concept");
  654. std::uniform_real_distribution<Scalar> uniform(Scalar(0), Scalar(1));
  655. std::uniform_real_distribution<Scalar> uniform_twopi(
  656. Scalar(0), 2 * Constants<Scalar>::pi());
  657. const Scalar u1 = uniform(generator);
  658. const Scalar u2 = uniform_twopi(generator);
  659. const Scalar u3 = uniform_twopi(generator);
  660. const Scalar a = sqrt(1 - u1);
  661. const Scalar b = sqrt(u1);
  662. return SO3(
  663. QuaternionMember(a * sin(u2), a * cos(u2), b * sin(u3), b * cos(u3)));
  664. }
  665. /// vee-operator
  666. ///
  667. /// It takes the 3x3-matrix representation ``Omega`` and maps it to the
  668. /// corresponding vector representation of Lie algebra.
  669. ///
  670. /// This is the inverse of the hat()-operator, see above.
  671. ///
  672. /// Precondition: ``Omega`` must have the following structure:
  673. ///
  674. /// | 0 -c b |
  675. /// | c 0 -a |
  676. /// | -b a 0 |
  677. ///
  678. SOPHUS_FUNC static Tangent vee(Transformation const& Omega) {
  679. return Tangent(Omega(2, 1), Omega(0, 2), Omega(1, 0));
  680. }
  681. protected:
  682. /// Mutator of unit_quaternion is protected to ensure class invariant.
  683. ///
  684. SOPHUS_FUNC QuaternionMember& unit_quaternion_nonconst() {
  685. return unit_quaternion_;
  686. }
  687. QuaternionMember unit_quaternion_;
  688. };
  689. } // namespace Sophus
  690. namespace Eigen {
  691. /// Specialization of Eigen::Map for ``SO3``; derived from SO3Base.
  692. ///
  693. /// Allows us to wrap SO3 objects around POD array (e.g. external c style
  694. /// quaternion).
  695. template <class Scalar_, int Options>
  696. class Map<Sophus::SO3<Scalar_>, Options>
  697. : public Sophus::SO3Base<Map<Sophus::SO3<Scalar_>, Options>> {
  698. public:
  699. using Base = Sophus::SO3Base<Map<Sophus::SO3<Scalar_>, Options>>;
  700. using Scalar = Scalar_;
  701. using Transformation = typename Base::Transformation;
  702. using Point = typename Base::Point;
  703. using HomogeneousPoint = typename Base::HomogeneousPoint;
  704. using Tangent = typename Base::Tangent;
  705. using Adjoint = typename Base::Adjoint;
  706. /// ``Base`` is friend so unit_quaternion_nonconst can be accessed from
  707. /// ``Base``.
  708. friend class Sophus::SO3Base<Map<Sophus::SO3<Scalar_>, Options>>;
  709. // LCOV_EXCL_START
  710. EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Map);
  711. // LCOV_EXCL_STOP
  712. using Base::operator*=;
  713. using Base::operator*;
  714. SOPHUS_FUNC Map(Scalar* coeffs) : unit_quaternion_(coeffs) {}
  715. /// Accessor of unit quaternion.
  716. ///
  717. SOPHUS_FUNC Map<Eigen::Quaternion<Scalar>, Options> const& unit_quaternion()
  718. const {
  719. return unit_quaternion_;
  720. }
  721. protected:
  722. /// Mutator of unit_quaternion is protected to ensure class invariant.
  723. ///
  724. SOPHUS_FUNC Map<Eigen::Quaternion<Scalar>, Options>&
  725. unit_quaternion_nonconst() {
  726. return unit_quaternion_;
  727. }
  728. Map<Eigen::Quaternion<Scalar>, Options> unit_quaternion_;
  729. };
  730. /// Specialization of Eigen::Map for ``SO3 const``; derived from SO3Base.
  731. ///
  732. /// Allows us to wrap SO3 objects around POD array (e.g. external c style
  733. /// quaternion).
  734. template <class Scalar_, int Options>
  735. class Map<Sophus::SO3<Scalar_> const, Options>
  736. : public Sophus::SO3Base<Map<Sophus::SO3<Scalar_> const, Options>> {
  737. public:
  738. using Base = Sophus::SO3Base<Map<Sophus::SO3<Scalar_> const, Options>>;
  739. using Scalar = Scalar_;
  740. using Transformation = typename Base::Transformation;
  741. using Point = typename Base::Point;
  742. using HomogeneousPoint = typename Base::HomogeneousPoint;
  743. using Tangent = typename Base::Tangent;
  744. using Adjoint = typename Base::Adjoint;
  745. using Base::operator*=;
  746. using Base::operator*;
  747. SOPHUS_FUNC Map(Scalar const* coeffs) : unit_quaternion_(coeffs) {}
  748. /// Accessor of unit quaternion.
  749. ///
  750. SOPHUS_FUNC Map<Eigen::Quaternion<Scalar> const, Options> const&
  751. unit_quaternion() const {
  752. return unit_quaternion_;
  753. }
  754. protected:
  755. /// Mutator of unit_quaternion is protected to ensure class invariant.
  756. ///
  757. Map<Eigen::Quaternion<Scalar> const, Options> const unit_quaternion_;
  758. };
  759. } // namespace Eigen
  760. #endif