so3.hpp 28 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850
  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 <eigen3/Eigen/src/Geometry/OrthoMethods.h>
  11. #include <eigen3/Eigen/src/Geometry/Quaternion.h>
  12. #include <eigen3/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-like operator from OtherDerived.
  278. ///
  279. template <class OtherDerived>
  280. SOPHUS_FUNC SO3Base<Derived>& operator=(SO3Base<OtherDerived> const& other) {
  281. unit_quaternion_nonconst() = other.unit_quaternion();
  282. return *this;
  283. }
  284. /// Group multiplication, which is rotation concatenation.
  285. ///
  286. template <typename OtherDerived>
  287. SOPHUS_FUNC SO3Product<OtherDerived> operator*(
  288. SO3Base<OtherDerived> const& other) const {
  289. using QuaternionProductType =
  290. typename SO3Product<OtherDerived>::QuaternionType;
  291. const QuaternionType& a = unit_quaternion();
  292. const typename OtherDerived::QuaternionType& b = other.unit_quaternion();
  293. /// NOTE: We cannot use Eigen's Quaternion multiplication because it always
  294. /// returns a Quaternion of the same Scalar as this object, so it is not
  295. /// able to multiple Jets and doubles correctly.
  296. return SO3Product<OtherDerived>(QuaternionProductType(
  297. a.w() * b.w() - a.x() * b.x() - a.y() * b.y() - a.z() * b.z(),
  298. a.w() * b.x() + a.x() * b.w() + a.y() * b.z() - a.z() * b.y(),
  299. a.w() * b.y() + a.y() * b.w() + a.z() * b.x() - a.x() * b.z(),
  300. a.w() * b.z() + a.z() * b.w() + a.x() * b.y() - a.y() * b.x()));
  301. }
  302. /// Group action on 3-points.
  303. ///
  304. /// This function rotates a 3 dimensional point ``p`` by the SO3 element
  305. /// ``bar_R_foo`` (= rotation matrix): ``p_bar = bar_R_foo * p_foo``.
  306. ///
  307. /// Since SO3 is internally represented by a unit quaternion ``q``, it is
  308. /// implemented as ``p_bar = q * p_foo * q^{*}``
  309. /// with ``q^{*}`` being the quaternion conjugate of ``q``.
  310. ///
  311. /// Geometrically, ``p`` is rotated by angle ``|omega|`` around the
  312. /// axis ``omega/|omega|`` with ``omega := vee(log(bar_R_foo))``.
  313. ///
  314. /// For ``vee``-operator, see below.
  315. ///
  316. template <typename PointDerived,
  317. typename = typename std::enable_if<
  318. IsFixedSizeVector<PointDerived, 3>::value>::type>
  319. SOPHUS_FUNC PointProduct<PointDerived> operator*(
  320. Eigen::MatrixBase<PointDerived> const& p) const {
  321. /// NOTE: We cannot use Eigen's Quaternion transformVector because it always
  322. /// returns a Vector3 of the same Scalar as this quaternion, so it is not
  323. /// able to be applied to Jets and doubles correctly.
  324. const QuaternionType& q = unit_quaternion();
  325. PointProduct<PointDerived> uv = q.vec().cross(p);
  326. uv += uv;
  327. return p + q.w() * uv + q.vec().cross(uv);
  328. }
  329. /// Group action on homogeneous 3-points. See above for more details.
  330. template <typename HPointDerived,
  331. typename = typename std::enable_if<
  332. IsFixedSizeVector<HPointDerived, 4>::value>::type>
  333. SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> operator*(
  334. Eigen::MatrixBase<HPointDerived> const& p) const {
  335. const auto rp = *this * p.template head<3>();
  336. return HomogeneousPointProduct<HPointDerived>(rp(0), rp(1), rp(2), p(3));
  337. }
  338. /// Group action on lines.
  339. ///
  340. /// This function rotates a parametrized line ``l(t) = o + t * d`` by the SO3
  341. /// element:
  342. ///
  343. /// Both direction ``d`` and origin ``o`` are rotated as a 3 dimensional point
  344. ///
  345. SOPHUS_FUNC Line operator*(Line const& l) const {
  346. return Line((*this) * l.origin(), (*this) * l.direction());
  347. }
  348. /// In-place group multiplication. This method is only valid if the return
  349. /// type of the multiplication is compatible with this SO3's Scalar type.
  350. ///
  351. template <typename OtherDerived,
  352. typename = typename std::enable_if<
  353. std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
  354. SOPHUS_FUNC SO3Base<Derived>& operator*=(SO3Base<OtherDerived> const& other) {
  355. *static_cast<Derived*>(this) = *this * other;
  356. return *this;
  357. }
  358. /// Takes in quaternion, and normalizes it.
  359. ///
  360. /// Precondition: The quaternion must not be close to zero.
  361. ///
  362. SOPHUS_FUNC void setQuaternion(Eigen::Quaternion<Scalar> const& quaternion) {
  363. unit_quaternion_nonconst() = quaternion;
  364. normalize();
  365. }
  366. /// Accessor of unit quaternion.
  367. ///
  368. SOPHUS_FUNC QuaternionType const& unit_quaternion() const {
  369. return static_cast<Derived const*>(this)->unit_quaternion();
  370. }
  371. private:
  372. /// Mutator of unit_quaternion is private to ensure class invariant. That is
  373. /// the quaternion must stay close to unit length.
  374. ///
  375. SOPHUS_FUNC QuaternionType& unit_quaternion_nonconst() {
  376. return static_cast<Derived*>(this)->unit_quaternion_nonconst();
  377. }
  378. };
  379. /// SO3 using default storage; derived from SO3Base.
  380. template <class Scalar_, int Options>
  381. class SO3 : public SO3Base<SO3<Scalar_, Options>> {
  382. public:
  383. using Base = SO3Base<SO3<Scalar_, Options>>;
  384. static int constexpr DoF = Base::DoF;
  385. static int constexpr num_parameters = Base::num_parameters;
  386. using Scalar = Scalar_;
  387. using Transformation = typename Base::Transformation;
  388. using Point = typename Base::Point;
  389. using HomogeneousPoint = typename Base::HomogeneousPoint;
  390. using Tangent = typename Base::Tangent;
  391. using Adjoint = typename Base::Adjoint;
  392. using QuaternionMember = Eigen::Quaternion<Scalar, Options>;
  393. /// ``Base`` is friend so unit_quaternion_nonconst can be accessed from
  394. /// ``Base``.
  395. friend class SO3Base<SO3<Scalar, Options>>;
  396. using Base::operator=;
  397. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  398. /// Default constructor initializes unit quaternion to identity rotation.
  399. ///
  400. SOPHUS_FUNC SO3()
  401. : unit_quaternion_(Scalar(1), Scalar(0), Scalar(0), Scalar(0)) {}
  402. /// Copy constructor
  403. ///
  404. SOPHUS_FUNC SO3(SO3 const& other) = default;
  405. /// Copy-like constructor from OtherDerived.
  406. ///
  407. template <class OtherDerived>
  408. SOPHUS_FUNC SO3(SO3Base<OtherDerived> const& other)
  409. : unit_quaternion_(other.unit_quaternion()) {}
  410. /// Constructor from rotation matrix
  411. ///
  412. /// Precondition: rotation matrix needs to be orthogonal with determinant
  413. /// of 1.
  414. ///
  415. SOPHUS_FUNC SO3(Transformation const& R) : unit_quaternion_(R) {
  416. SOPHUS_ENSURE(isOrthogonal(R), "R is not orthogonal:\n %",
  417. R * R.transpose());
  418. SOPHUS_ENSURE(R.determinant() > Scalar(0), "det(R) is not positive: %",
  419. R.determinant());
  420. }
  421. /// Constructor from quaternion
  422. ///
  423. /// Precondition: quaternion must not be close to zero.
  424. ///
  425. template <class D>
  426. SOPHUS_FUNC explicit SO3(Eigen::QuaternionBase<D> const& quat)
  427. : unit_quaternion_(quat) {
  428. static_assert(
  429. std::is_same<typename Eigen::QuaternionBase<D>::Scalar, Scalar>::value,
  430. "Input must be of same scalar type");
  431. Base::normalize();
  432. }
  433. /// Accessor of unit quaternion.
  434. ///
  435. SOPHUS_FUNC QuaternionMember const& unit_quaternion() const {
  436. return unit_quaternion_;
  437. }
  438. /// Returns derivative of exp(x) wrt. x.
  439. ///
  440. SOPHUS_FUNC static Sophus::Matrix<Scalar, num_parameters, DoF> Dx_exp_x(
  441. Tangent const& omega) {
  442. using std::cos;
  443. using std::exp;
  444. using std::sin;
  445. using std::sqrt;
  446. Scalar const c0 = omega[0] * omega[0];
  447. Scalar const c1 = omega[1] * omega[1];
  448. Scalar const c2 = omega[2] * omega[2];
  449. Scalar const c3 = c0 + c1 + c2;
  450. if (c3 < Constants<Scalar>::epsilon()) {
  451. return Dx_exp_x_at_0();
  452. }
  453. Scalar const c4 = sqrt(c3);
  454. Scalar const c5 = 1.0 / c4;
  455. Scalar const c6 = 0.5 * c4;
  456. Scalar const c7 = sin(c6);
  457. Scalar const c8 = c5 * c7;
  458. Scalar const c9 = pow(c3, -3.0L / 2.0L);
  459. Scalar const c10 = c7 * c9;
  460. Scalar const c11 = Scalar(1.0) / c3;
  461. Scalar const c12 = cos(c6);
  462. Scalar const c13 = Scalar(0.5) * c11 * c12;
  463. Scalar const c14 = c7 * c9 * omega[0];
  464. Scalar const c15 = Scalar(0.5) * c11 * c12 * omega[0];
  465. Scalar const c16 = -c14 * omega[1] + c15 * omega[1];
  466. Scalar const c17 = -c14 * omega[2] + c15 * omega[2];
  467. Scalar const c18 = omega[1] * omega[2];
  468. Scalar const c19 = -c10 * c18 + c13 * c18;
  469. Scalar const c20 = Scalar(0.5) * c5 * c7;
  470. Sophus::Matrix<Scalar, num_parameters, DoF> J;
  471. J(0, 0) = -c0 * c10 + c0 * c13 + c8;
  472. J(0, 1) = c16;
  473. J(0, 2) = c17;
  474. J(1, 0) = c16;
  475. J(1, 1) = -c1 * c10 + c1 * c13 + c8;
  476. J(1, 2) = c19;
  477. J(2, 0) = c17;
  478. J(2, 1) = c19;
  479. J(2, 2) = -c10 * c2 + c13 * c2 + c8;
  480. J(3, 0) = -c20 * omega[0];
  481. J(3, 1) = -c20 * omega[1];
  482. J(3, 2) = -c20 * omega[2];
  483. return J;
  484. }
  485. /// Returns derivative of exp(x) wrt. x_i at x=0.
  486. ///
  487. SOPHUS_FUNC static Sophus::Matrix<Scalar, num_parameters, DoF>
  488. Dx_exp_x_at_0() {
  489. Sophus::Matrix<Scalar, num_parameters, DoF> J;
  490. // clang-format off
  491. J << Scalar(0.5), Scalar(0), Scalar(0),
  492. Scalar(0), Scalar(0.5), Scalar(0),
  493. Scalar(0), Scalar(0), Scalar(0.5),
  494. Scalar(0), Scalar(0), Scalar(0);
  495. // clang-format on
  496. return J;
  497. }
  498. /// Returns derivative of exp(x).matrix() wrt. ``x_i at x=0``.
  499. ///
  500. SOPHUS_FUNC static Transformation Dxi_exp_x_matrix_at_0(int i) {
  501. return generator(i);
  502. }
  503. /// Group exponential
  504. ///
  505. /// This functions takes in an element of tangent space (= rotation vector
  506. /// ``omega``) and returns the corresponding element of the group SO(3).
  507. ///
  508. /// To be more specific, this function computes ``expmat(hat(omega))``
  509. /// with ``expmat(.)`` being the matrix exponential and ``hat(.)`` being the
  510. /// hat()-operator of SO(3).
  511. ///
  512. SOPHUS_FUNC static SO3<Scalar> exp(Tangent const& omega) {
  513. Scalar theta;
  514. return expAndTheta(omega, &theta);
  515. }
  516. /// As above, but also returns ``theta = |omega|`` as out-parameter.
  517. ///
  518. /// Precondition: ``theta`` must not be ``nullptr``.
  519. ///
  520. SOPHUS_FUNC static SO3<Scalar> expAndTheta(Tangent const& omega,
  521. Scalar* theta) {
  522. SOPHUS_ENSURE(theta != nullptr, "must not be nullptr.");
  523. using std::abs;
  524. using std::cos;
  525. using std::sin;
  526. using std::sqrt;
  527. Scalar theta_sq = omega.squaredNorm();
  528. Scalar imag_factor;
  529. Scalar real_factor;
  530. if (theta_sq <
  531. Constants<Scalar>::epsilon() * Constants<Scalar>::epsilon()) {
  532. *theta = Scalar(0);
  533. Scalar theta_po4 = theta_sq * theta_sq;
  534. imag_factor = Scalar(0.5) - Scalar(1.0 / 48.0) * theta_sq +
  535. Scalar(1.0 / 3840.0) * theta_po4;
  536. real_factor = Scalar(1) - Scalar(1.0 / 8.0) * theta_sq +
  537. Scalar(1.0 / 384.0) * theta_po4;
  538. } else {
  539. *theta = sqrt(theta_sq);
  540. Scalar half_theta = Scalar(0.5) * (*theta);
  541. Scalar sin_half_theta = sin(half_theta);
  542. imag_factor = sin_half_theta / (*theta);
  543. real_factor = cos(half_theta);
  544. }
  545. SO3 q;
  546. q.unit_quaternion_nonconst() =
  547. QuaternionMember(real_factor, imag_factor * omega.x(),
  548. imag_factor * omega.y(), imag_factor * omega.z());
  549. SOPHUS_ENSURE(abs(q.unit_quaternion().squaredNorm() - Scalar(1)) <
  550. Sophus::Constants<Scalar>::epsilon(),
  551. "SO3::exp failed! omega: %, real: %, img: %",
  552. omega.transpose(), real_factor, imag_factor);
  553. return q;
  554. }
  555. /// Returns closest SO3 given arbitrary 3x3 matrix.
  556. ///
  557. template <class S = Scalar>
  558. static SOPHUS_FUNC enable_if_t<std::is_floating_point<S>::value, SO3>
  559. fitToSO3(Transformation const& R) {
  560. return SO3(::Sophus::makeRotationMatrix(R));
  561. }
  562. /// Returns the ith infinitesimal generators of SO(3).
  563. ///
  564. /// The infinitesimal generators of SO(3) are:
  565. ///
  566. /// ```
  567. /// | 0 0 0 |
  568. /// G_0 = | 0 0 -1 |
  569. /// | 0 1 0 |
  570. ///
  571. /// | 0 0 1 |
  572. /// G_1 = | 0 0 0 |
  573. /// | -1 0 0 |
  574. ///
  575. /// | 0 -1 0 |
  576. /// G_2 = | 1 0 0 |
  577. /// | 0 0 0 |
  578. /// ```
  579. ///
  580. /// Precondition: ``i`` must be 0, 1 or 2.
  581. ///
  582. SOPHUS_FUNC static Transformation generator(int i) {
  583. SOPHUS_ENSURE(i >= 0 && i <= 2, "i should be in range [0,2].");
  584. Tangent e;
  585. e.setZero();
  586. e[i] = Scalar(1);
  587. return hat(e);
  588. }
  589. /// hat-operator
  590. ///
  591. /// It takes in the 3-vector representation ``omega`` (= rotation vector) and
  592. /// returns the corresponding matrix representation of Lie algebra element.
  593. ///
  594. /// Formally, the hat()-operator of SO(3) is defined as
  595. ///
  596. /// ``hat(.): R^3 -> R^{3x3}, hat(omega) = sum_i omega_i * G_i``
  597. /// (for i=0,1,2)
  598. ///
  599. /// with ``G_i`` being the ith infinitesimal generator of SO(3).
  600. ///
  601. /// The corresponding inverse is the vee()-operator, see below.
  602. ///
  603. SOPHUS_FUNC static Transformation hat(Tangent const& omega) {
  604. Transformation Omega;
  605. // clang-format off
  606. Omega <<
  607. Scalar(0), -omega(2), omega(1),
  608. omega(2), Scalar(0), -omega(0),
  609. -omega(1), omega(0), Scalar(0);
  610. // clang-format on
  611. return Omega;
  612. }
  613. /// Lie bracket
  614. ///
  615. /// It computes the Lie bracket of SO(3). To be more specific, it computes
  616. ///
  617. /// ``[omega_1, omega_2]_so3 := vee([hat(omega_1), hat(omega_2)])``
  618. ///
  619. /// with ``[A,B] := AB-BA`` being the matrix commutator, ``hat(.)`` the
  620. /// hat()-operator and ``vee(.)`` the vee()-operator of SO3.
  621. ///
  622. /// For the Lie algebra so3, the Lie bracket is simply the cross product:
  623. ///
  624. /// ``[omega_1, omega_2]_so3 = omega_1 x omega_2.``
  625. ///
  626. SOPHUS_FUNC static Tangent lieBracket(Tangent const& omega1,
  627. Tangent const& omega2) {
  628. return omega1.cross(omega2);
  629. }
  630. /// Construct x-axis rotation.
  631. ///
  632. static SOPHUS_FUNC SO3 rotX(Scalar const& x) {
  633. return SO3::exp(Sophus::Vector3<Scalar>(x, Scalar(0), Scalar(0)));
  634. }
  635. /// Construct y-axis rotation.
  636. ///
  637. static SOPHUS_FUNC SO3 rotY(Scalar const& y) {
  638. return SO3::exp(Sophus::Vector3<Scalar>(Scalar(0), y, Scalar(0)));
  639. }
  640. /// Construct z-axis rotation.
  641. ///
  642. static SOPHUS_FUNC SO3 rotZ(Scalar const& z) {
  643. return SO3::exp(Sophus::Vector3<Scalar>(Scalar(0), Scalar(0), z));
  644. }
  645. /// Draw uniform sample from SO(3) manifold.
  646. /// Based on: http://planning.cs.uiuc.edu/node198.html
  647. ///
  648. template <class UniformRandomBitGenerator>
  649. static SO3 sampleUniform(UniformRandomBitGenerator& generator) {
  650. static_assert(IsUniformRandomBitGenerator<UniformRandomBitGenerator>::value,
  651. "generator must meet the UniformRandomBitGenerator concept");
  652. std::uniform_real_distribution<Scalar> uniform(Scalar(0), Scalar(1));
  653. std::uniform_real_distribution<Scalar> uniform_twopi(
  654. Scalar(0), 2 * Constants<Scalar>::pi());
  655. const Scalar u1 = uniform(generator);
  656. const Scalar u2 = uniform_twopi(generator);
  657. const Scalar u3 = uniform_twopi(generator);
  658. const Scalar a = sqrt(1 - u1);
  659. const Scalar b = sqrt(u1);
  660. return SO3(
  661. QuaternionMember(a * sin(u2), a * cos(u2), b * sin(u3), b * cos(u3)));
  662. }
  663. /// vee-operator
  664. ///
  665. /// It takes the 3x3-matrix representation ``Omega`` and maps it to the
  666. /// corresponding vector representation of Lie algebra.
  667. ///
  668. /// This is the inverse of the hat()-operator, see above.
  669. ///
  670. /// Precondition: ``Omega`` must have the following structure:
  671. ///
  672. /// | 0 -c b |
  673. /// | c 0 -a |
  674. /// | -b a 0 |
  675. ///
  676. SOPHUS_FUNC static Tangent vee(Transformation const& Omega) {
  677. return Tangent(Omega(2, 1), Omega(0, 2), Omega(1, 0));
  678. }
  679. protected:
  680. /// Mutator of unit_quaternion is protected to ensure class invariant.
  681. ///
  682. SOPHUS_FUNC QuaternionMember& unit_quaternion_nonconst() {
  683. return unit_quaternion_;
  684. }
  685. QuaternionMember unit_quaternion_;
  686. };
  687. } // namespace Sophus
  688. namespace Eigen {
  689. /// Specialization of Eigen::Map for ``SO3``; derived from SO3Base.
  690. ///
  691. /// Allows us to wrap SO3 objects around POD array (e.g. external c style
  692. /// quaternion).
  693. template <class Scalar_, int Options>
  694. class Map<Sophus::SO3<Scalar_>, Options>
  695. : public Sophus::SO3Base<Map<Sophus::SO3<Scalar_>, Options>> {
  696. public:
  697. using Base = Sophus::SO3Base<Map<Sophus::SO3<Scalar_>, Options>>;
  698. using Scalar = Scalar_;
  699. using Transformation = typename Base::Transformation;
  700. using Point = typename Base::Point;
  701. using HomogeneousPoint = typename Base::HomogeneousPoint;
  702. using Tangent = typename Base::Tangent;
  703. using Adjoint = typename Base::Adjoint;
  704. /// ``Base`` is friend so unit_quaternion_nonconst can be accessed from
  705. /// ``Base``.
  706. friend class Sophus::SO3Base<Map<Sophus::SO3<Scalar_>, Options>>;
  707. using Base::operator=;
  708. using Base::operator*=;
  709. using Base::operator*;
  710. SOPHUS_FUNC Map(Scalar* coeffs) : unit_quaternion_(coeffs) {}
  711. /// Accessor of unit quaternion.
  712. ///
  713. SOPHUS_FUNC Map<Eigen::Quaternion<Scalar>, Options> const& unit_quaternion()
  714. const {
  715. return unit_quaternion_;
  716. }
  717. protected:
  718. /// Mutator of unit_quaternion is protected to ensure class invariant.
  719. ///
  720. SOPHUS_FUNC Map<Eigen::Quaternion<Scalar>, Options>&
  721. unit_quaternion_nonconst() {
  722. return unit_quaternion_;
  723. }
  724. Map<Eigen::Quaternion<Scalar>, Options> unit_quaternion_;
  725. };
  726. /// Specialization of Eigen::Map for ``SO3 const``; derived from SO3Base.
  727. ///
  728. /// Allows us to wrap SO3 objects around POD array (e.g. external c style
  729. /// quaternion).
  730. template <class Scalar_, int Options>
  731. class Map<Sophus::SO3<Scalar_> const, Options>
  732. : public Sophus::SO3Base<Map<Sophus::SO3<Scalar_> const, Options>> {
  733. public:
  734. using Base = Sophus::SO3Base<Map<Sophus::SO3<Scalar_> const, Options>>;
  735. using Scalar = Scalar_;
  736. using Transformation = typename Base::Transformation;
  737. using Point = typename Base::Point;
  738. using HomogeneousPoint = typename Base::HomogeneousPoint;
  739. using Tangent = typename Base::Tangent;
  740. using Adjoint = typename Base::Adjoint;
  741. using Base::operator*=;
  742. using Base::operator*;
  743. SOPHUS_FUNC Map(Scalar const* coeffs) : unit_quaternion_(coeffs) {}
  744. /// Accessor of unit quaternion.
  745. ///
  746. SOPHUS_FUNC Map<Eigen::Quaternion<Scalar> const, Options> const&
  747. unit_quaternion() const {
  748. return unit_quaternion_;
  749. }
  750. protected:
  751. /// Mutator of unit_quaternion is protected to ensure class invariant.
  752. ///
  753. Map<Eigen::Quaternion<Scalar> const, Options> const unit_quaternion_;
  754. };
  755. } // namespace Eigen
  756. #endif