rxso3.hpp 25 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730
  1. /// @file
  2. /// Direct product R X SO(3) - rotation and scaling in 3d.
  3. #ifndef SOPHUS_RXSO3_HPP
  4. #define SOPHUS_RXSO3_HPP
  5. #include "so3.hpp"
  6. namespace Sophus {
  7. template <class Scalar_, int Options = 0>
  8. class RxSO3;
  9. using RxSO3d = RxSO3<double>;
  10. using RxSO3f = RxSO3<float>;
  11. } // namespace Sophus
  12. namespace Eigen {
  13. namespace internal {
  14. template <class Scalar_, int Options_>
  15. struct traits<Sophus::RxSO3<Scalar_, Options_>> {
  16. static constexpr int Options = Options_;
  17. using Scalar = Scalar_;
  18. using QuaternionType = Eigen::Quaternion<Scalar, Options>;
  19. };
  20. template <class Scalar_, int Options_>
  21. struct traits<Map<Sophus::RxSO3<Scalar_>, Options_>>
  22. : traits<Sophus::RxSO3<Scalar_, Options_>> {
  23. static constexpr int Options = Options_;
  24. using Scalar = Scalar_;
  25. using QuaternionType = Map<Eigen::Quaternion<Scalar>, Options>;
  26. };
  27. template <class Scalar_, int Options_>
  28. struct traits<Map<Sophus::RxSO3<Scalar_> const, Options_>>
  29. : traits<Sophus::RxSO3<Scalar_, Options_> const> {
  30. static constexpr int Options = Options_;
  31. using Scalar = Scalar_;
  32. using QuaternionType = Map<Eigen::Quaternion<Scalar> const, Options>;
  33. };
  34. } // namespace internal
  35. } // namespace Eigen
  36. namespace Sophus {
  37. /// RxSO3 base type - implements RxSO3 class but is storage agnostic
  38. ///
  39. /// This class implements the group ``R+ x SO(3)``, the direct product of the
  40. /// group of positive scalar 3x3 matrices (= isomorph to the positive
  41. /// real numbers) and the three-dimensional special orthogonal group SO(3).
  42. /// Geometrically, it is the group of rotation and scaling in three dimensions.
  43. /// As a matrix groups, RxSO3 consists of matrices of the form ``s * R``
  44. /// where ``R`` is an orthogonal matrix with ``det(R)=1`` and ``s > 0``
  45. /// being a positive real number.
  46. ///
  47. /// Internally, RxSO3 is represented by the group of non-zero quaternions.
  48. /// In particular, the scale equals the squared(!) norm of the quaternion ``q``,
  49. /// ``s = |q|^2``. This is a most compact representation since the degrees of
  50. /// freedom (DoF) of RxSO3 (=4) equals the number of internal parameters (=4).
  51. ///
  52. /// This class has the explicit class invariant that the scale ``s`` is not
  53. /// too close to zero. Strictly speaking, it must hold that:
  54. ///
  55. /// ``quaternion().squaredNorm() >= Constants::epsilon()``.
  56. ///
  57. /// In order to obey this condition, group multiplication is implemented with
  58. /// saturation such that a product always has a scale which is equal or greater
  59. /// this threshold.
  60. template <class Derived>
  61. class RxSO3Base {
  62. public:
  63. static constexpr int Options = Eigen::internal::traits<Derived>::Options;
  64. using Scalar = typename Eigen::internal::traits<Derived>::Scalar;
  65. using QuaternionType =
  66. typename Eigen::internal::traits<Derived>::QuaternionType;
  67. using QuaternionTemporaryType = Eigen::Quaternion<Scalar, Options>;
  68. /// Degrees of freedom of manifold, number of dimensions in tangent space
  69. /// (three for rotation and one for scaling).
  70. static int constexpr DoF = 4;
  71. /// Number of internal parameters used (quaternion is a 4-tuple).
  72. static int constexpr num_parameters = 4;
  73. /// Group transformations are 3x3 matrices.
  74. static int constexpr N = 3;
  75. using Transformation = Matrix<Scalar, N, N>;
  76. using Point = Vector3<Scalar>;
  77. using HomogeneousPoint = Vector4<Scalar>;
  78. using Line = ParametrizedLine3<Scalar>;
  79. using Tangent = Vector<Scalar, DoF>;
  80. using Adjoint = Matrix<Scalar, DoF, DoF>;
  81. struct TangentAndTheta {
  82. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  83. Tangent tangent;
  84. Scalar theta;
  85. };
  86. /// For binary operations the return type is determined with the
  87. /// ScalarBinaryOpTraits feature of Eigen. This allows mixing concrete and Map
  88. /// types, as well as other compatible scalar types such as Ceres::Jet and
  89. /// double scalars with RxSO3 operations.
  90. template <typename OtherDerived>
  91. using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<
  92. Scalar, typename OtherDerived::Scalar>::ReturnType;
  93. template <typename OtherDerived>
  94. using RxSO3Product = RxSO3<ReturnScalar<OtherDerived>>;
  95. template <typename PointDerived>
  96. using PointProduct = Vector3<ReturnScalar<PointDerived>>;
  97. template <typename HPointDerived>
  98. using HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived>>;
  99. /// Adjoint transformation
  100. ///
  101. /// This function return the adjoint transformation ``Ad`` of the group
  102. /// element ``A`` such that for all ``x`` it holds that
  103. /// ``hat(Ad_A * x) = A * hat(x) A^{-1}``. See hat-operator below.
  104. ///
  105. /// For RxSO(3), it simply returns the rotation matrix corresponding to ``A``.
  106. ///
  107. SOPHUS_FUNC Adjoint Adj() const {
  108. Adjoint res;
  109. res.setIdentity();
  110. res.template topLeftCorner<3, 3>() = rotationMatrix();
  111. return res;
  112. }
  113. /// Returns copy of instance casted to NewScalarType.
  114. ///
  115. template <class NewScalarType>
  116. SOPHUS_FUNC RxSO3<NewScalarType> cast() const {
  117. return RxSO3<NewScalarType>(quaternion().template cast<NewScalarType>());
  118. }
  119. /// This provides unsafe read/write access to internal data. RxSO(3) is
  120. /// represented by an Eigen::Quaternion (four parameters). When using direct
  121. /// write access, the user needs to take care of that the quaternion is not
  122. /// set close to zero.
  123. ///
  124. /// Note: The first three Scalars represent the imaginary parts, while the
  125. /// forth Scalar represent the real part.
  126. ///
  127. SOPHUS_FUNC Scalar* data() { return quaternion_nonconst().coeffs().data(); }
  128. /// Const version of data() above.
  129. ///
  130. SOPHUS_FUNC Scalar const* data() const {
  131. return quaternion().coeffs().data();
  132. }
  133. /// Returns group inverse.
  134. ///
  135. SOPHUS_FUNC RxSO3<Scalar> inverse() const {
  136. return RxSO3<Scalar>(quaternion().inverse());
  137. }
  138. /// Logarithmic map
  139. ///
  140. /// Computes the logarithm, the inverse of the group exponential which maps
  141. /// element of the group (scaled rotation matrices) to elements of the tangent
  142. /// space (rotation-vector plus logarithm of scale factor).
  143. ///
  144. /// To be specific, this function computes ``vee(logmat(.))`` with
  145. /// ``logmat(.)`` being the matrix logarithm and ``vee(.)`` the vee-operator
  146. /// of RxSO3.
  147. ///
  148. SOPHUS_FUNC Tangent log() const { return logAndTheta().tangent; }
  149. /// As above, but also returns ``theta = |omega|``.
  150. ///
  151. SOPHUS_FUNC TangentAndTheta logAndTheta() const {
  152. using std::log;
  153. Scalar scale = quaternion().squaredNorm();
  154. TangentAndTheta result;
  155. result.tangent[3] = log(scale);
  156. auto omega_and_theta = SO3<Scalar>(quaternion()).logAndTheta();
  157. result.tangent.template head<3>() = omega_and_theta.tangent;
  158. result.theta = omega_and_theta.theta;
  159. return result;
  160. }
  161. /// Returns 3x3 matrix representation of the instance.
  162. ///
  163. /// For RxSO3, the matrix representation is an scaled orthogonal matrix ``sR``
  164. /// with ``det(R)=s^3``, thus a scaled rotation matrix ``R`` with scale
  165. /// ``s``.
  166. ///
  167. SOPHUS_FUNC Transformation matrix() const {
  168. Transformation sR;
  169. Scalar const vx_sq = quaternion().vec().x() * quaternion().vec().x();
  170. Scalar const vy_sq = quaternion().vec().y() * quaternion().vec().y();
  171. Scalar const vz_sq = quaternion().vec().z() * quaternion().vec().z();
  172. Scalar const w_sq = quaternion().w() * quaternion().w();
  173. Scalar const two_vx = Scalar(2) * quaternion().vec().x();
  174. Scalar const two_vy = Scalar(2) * quaternion().vec().y();
  175. Scalar const two_vz = Scalar(2) * quaternion().vec().z();
  176. Scalar const two_vx_vy = two_vx * quaternion().vec().y();
  177. Scalar const two_vx_vz = two_vx * quaternion().vec().z();
  178. Scalar const two_vx_w = two_vx * quaternion().w();
  179. Scalar const two_vy_vz = two_vy * quaternion().vec().z();
  180. Scalar const two_vy_w = two_vy * quaternion().w();
  181. Scalar const two_vz_w = two_vz * quaternion().w();
  182. sR(0, 0) = vx_sq - vy_sq - vz_sq + w_sq;
  183. sR(1, 0) = two_vx_vy + two_vz_w;
  184. sR(2, 0) = two_vx_vz - two_vy_w;
  185. sR(0, 1) = two_vx_vy - two_vz_w;
  186. sR(1, 1) = -vx_sq + vy_sq - vz_sq + w_sq;
  187. sR(2, 1) = two_vx_w + two_vy_vz;
  188. sR(0, 2) = two_vx_vz + two_vy_w;
  189. sR(1, 2) = -two_vx_w + two_vy_vz;
  190. sR(2, 2) = -vx_sq - vy_sq + vz_sq + w_sq;
  191. return sR;
  192. }
  193. /// Assignment operator.
  194. ///
  195. SOPHUS_FUNC RxSO3Base& operator=(RxSO3Base const& other) = default;
  196. /// Assignment-like operator from OtherDerived.
  197. ///
  198. template <class OtherDerived>
  199. SOPHUS_FUNC RxSO3Base<Derived>& operator=(
  200. RxSO3Base<OtherDerived> const& other) {
  201. quaternion_nonconst() = other.quaternion();
  202. return *this;
  203. }
  204. /// Group multiplication, which is rotation concatenation and scale
  205. /// multiplication.
  206. ///
  207. /// Note: This function performs saturation for products close to zero in
  208. /// order to ensure the class invariant.
  209. ///
  210. template <typename OtherDerived>
  211. SOPHUS_FUNC RxSO3Product<OtherDerived> operator*(
  212. RxSO3Base<OtherDerived> const& other) const {
  213. using ResultT = ReturnScalar<OtherDerived>;
  214. typename RxSO3Product<OtherDerived>::QuaternionType result_quaternion(
  215. quaternion() * other.quaternion());
  216. ResultT scale = result_quaternion.squaredNorm();
  217. if (scale < Constants<ResultT>::epsilon()) {
  218. SOPHUS_ENSURE(scale > ResultT(0), "Scale must be greater zero.");
  219. /// Saturation to ensure class invariant.
  220. result_quaternion.normalize();
  221. result_quaternion.coeffs() *= sqrt(Constants<Scalar>::epsilon());
  222. }
  223. return RxSO3Product<OtherDerived>(result_quaternion);
  224. }
  225. /// Group action on 3-points.
  226. ///
  227. /// This function rotates a 3 dimensional point ``p`` by the SO3 element
  228. /// ``bar_R_foo`` (= rotation matrix) and scales it by the scale factor
  229. /// ``s``:
  230. ///
  231. /// ``p_bar = s * (bar_R_foo * p_foo)``.
  232. ///
  233. template <typename PointDerived,
  234. typename = typename std::enable_if<
  235. IsFixedSizeVector<PointDerived, 3>::value>::type>
  236. SOPHUS_FUNC PointProduct<PointDerived> operator*(
  237. Eigen::MatrixBase<PointDerived> const& p) const {
  238. // Follows http:///eigen.tuxfamily.org/bz/show_bug.cgi?id=459
  239. Scalar scale = quaternion().squaredNorm();
  240. PointProduct<PointDerived> two_vec_cross_p = quaternion().vec().cross(p);
  241. two_vec_cross_p += two_vec_cross_p;
  242. return scale * p + (quaternion().w() * two_vec_cross_p +
  243. quaternion().vec().cross(two_vec_cross_p));
  244. }
  245. /// Group action on homogeneous 3-points. See above for more details.
  246. ///
  247. template <typename HPointDerived,
  248. typename = typename std::enable_if<
  249. IsFixedSizeVector<HPointDerived, 4>::value>::type>
  250. SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> operator*(
  251. Eigen::MatrixBase<HPointDerived> const& p) const {
  252. const auto rsp = *this * p.template head<3>();
  253. return HomogeneousPointProduct<HPointDerived>(rsp(0), rsp(1), rsp(2), p(3));
  254. }
  255. /// Group action on lines.
  256. ///
  257. /// This function rotates a parametrized line ``l(t) = o + t * d`` by the SO3
  258. /// element ans scales it by the scale factor:
  259. ///
  260. /// Origin ``o`` is rotated and scaled
  261. /// Direction ``d`` is rotated (preserving it's norm)
  262. ///
  263. SOPHUS_FUNC Line operator*(Line const& l) const {
  264. return Line((*this) * l.origin(),
  265. (*this) * l.direction() / quaternion().squaredNorm());
  266. }
  267. /// In-place group multiplication. This method is only valid if the return
  268. /// type of the multiplication is compatible with this SO3's Scalar type.
  269. ///
  270. /// Note: This function performs saturation for products close to zero in
  271. /// order to ensure the class invariant.
  272. ///
  273. template <typename OtherDerived,
  274. typename = typename std::enable_if<
  275. std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
  276. SOPHUS_FUNC RxSO3Base<Derived>& operator*=(
  277. RxSO3Base<OtherDerived> const& other) {
  278. *static_cast<Derived*>(this) = *this * other;
  279. return *this;
  280. }
  281. /// Returns internal parameters of RxSO(3).
  282. ///
  283. /// It returns (q.imag[0], q.imag[1], q.imag[2], q.real), with q being the
  284. /// quaternion.
  285. ///
  286. SOPHUS_FUNC Sophus::Vector<Scalar, num_parameters> params() const {
  287. return quaternion().coeffs();
  288. }
  289. /// Sets non-zero quaternion
  290. ///
  291. /// Precondition: ``quat`` must not be close to zero.
  292. SOPHUS_FUNC void setQuaternion(Eigen::Quaternion<Scalar> const& quat) {
  293. SOPHUS_ENSURE(quat.squaredNorm() > Constants<Scalar>::epsilon() *
  294. Constants<Scalar>::epsilon(),
  295. "Scale factor must be greater-equal epsilon.");
  296. static_cast<Derived*>(this)->quaternion_nonconst() = quat;
  297. }
  298. /// Accessor of quaternion.
  299. ///
  300. SOPHUS_FUNC QuaternionType const& quaternion() const {
  301. return static_cast<Derived const*>(this)->quaternion();
  302. }
  303. /// Returns rotation matrix.
  304. ///
  305. SOPHUS_FUNC Transformation rotationMatrix() const {
  306. QuaternionTemporaryType norm_quad = quaternion();
  307. norm_quad.normalize();
  308. return norm_quad.toRotationMatrix();
  309. }
  310. /// Returns scale.
  311. ///
  312. SOPHUS_FUNC
  313. Scalar scale() const { return quaternion().squaredNorm(); }
  314. /// Setter of quaternion using rotation matrix ``R``, leaves scale as is.
  315. ///
  316. SOPHUS_FUNC void setRotationMatrix(Transformation const& R) {
  317. using std::sqrt;
  318. Scalar saved_scale = scale();
  319. quaternion_nonconst() = R;
  320. quaternion_nonconst().coeffs() *= sqrt(saved_scale);
  321. }
  322. /// Sets scale and leaves rotation as is.
  323. ///
  324. /// Note: This function as a significant computational cost, since it has to
  325. /// call the square root twice.
  326. ///
  327. SOPHUS_FUNC
  328. void setScale(Scalar const& scale) {
  329. using std::sqrt;
  330. quaternion_nonconst().normalize();
  331. quaternion_nonconst().coeffs() *= sqrt(scale);
  332. }
  333. /// Setter of quaternion using scaled rotation matrix ``sR``.
  334. ///
  335. /// Precondition: The 3x3 matrix must be "scaled orthogonal"
  336. /// and have a positive determinant.
  337. ///
  338. SOPHUS_FUNC void setScaledRotationMatrix(Transformation const& sR) {
  339. Transformation squared_sR = sR * sR.transpose();
  340. Scalar squared_scale =
  341. Scalar(1. / 3.) *
  342. (squared_sR(0, 0) + squared_sR(1, 1) + squared_sR(2, 2));
  343. SOPHUS_ENSURE(squared_scale >= Constants<Scalar>::epsilon() *
  344. Constants<Scalar>::epsilon(),
  345. "Scale factor must be greater-equal epsilon.");
  346. Scalar scale = sqrt(squared_scale);
  347. quaternion_nonconst() = sR / scale;
  348. quaternion_nonconst().coeffs() *= sqrt(scale);
  349. }
  350. /// Setter of SO(3) rotations, leaves scale as is.
  351. ///
  352. SOPHUS_FUNC void setSO3(SO3<Scalar> const& so3) {
  353. using std::sqrt;
  354. Scalar saved_scale = scale();
  355. quaternion_nonconst() = so3.unit_quaternion();
  356. quaternion_nonconst().coeffs() *= sqrt(saved_scale);
  357. }
  358. SOPHUS_FUNC SO3<Scalar> so3() const { return SO3<Scalar>(quaternion()); }
  359. protected:
  360. /// Mutator of quaternion is private to ensure class invariant.
  361. ///
  362. SOPHUS_FUNC QuaternionType& quaternion_nonconst() {
  363. return static_cast<Derived*>(this)->quaternion_nonconst();
  364. }
  365. };
  366. /// RxSO3 using storage; derived from RxSO3Base.
  367. template <class Scalar_, int Options>
  368. class RxSO3 : public RxSO3Base<RxSO3<Scalar_, Options>> {
  369. public:
  370. using Base = RxSO3Base<RxSO3<Scalar_, Options>>;
  371. using Scalar = Scalar_;
  372. using Transformation = typename Base::Transformation;
  373. using Point = typename Base::Point;
  374. using HomogeneousPoint = typename Base::HomogeneousPoint;
  375. using Tangent = typename Base::Tangent;
  376. using Adjoint = typename Base::Adjoint;
  377. using QuaternionMember = Eigen::Quaternion<Scalar, Options>;
  378. /// ``Base`` is friend so quaternion_nonconst can be accessed from ``Base``.
  379. friend class RxSO3Base<RxSO3<Scalar_, Options>>;
  380. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  381. /// Default constructor initializes quaternion to identity rotation and scale
  382. /// to 1.
  383. ///
  384. SOPHUS_FUNC RxSO3()
  385. : quaternion_(Scalar(1), Scalar(0), Scalar(0), Scalar(0)) {}
  386. /// Copy constructor
  387. ///
  388. SOPHUS_FUNC RxSO3(RxSO3 const& other) = default;
  389. /// Copy-like constructor from OtherDerived
  390. ///
  391. template <class OtherDerived>
  392. SOPHUS_FUNC RxSO3(RxSO3Base<OtherDerived> const& other)
  393. : quaternion_(other.quaternion()) {}
  394. /// Constructor from scaled rotation matrix
  395. ///
  396. /// Precondition: rotation matrix need to be scaled orthogonal with
  397. /// determinant of ``s^3``.
  398. ///
  399. SOPHUS_FUNC explicit RxSO3(Transformation const& sR) {
  400. this->setScaledRotationMatrix(sR);
  401. }
  402. /// Constructor from scale factor and rotation matrix ``R``.
  403. ///
  404. /// Precondition: Rotation matrix ``R`` must to be orthogonal with determinant
  405. /// of 1 and ``scale`` must not be close to zero.
  406. ///
  407. SOPHUS_FUNC RxSO3(Scalar const& scale, Transformation const& R)
  408. : quaternion_(R) {
  409. SOPHUS_ENSURE(scale >= Constants<Scalar>::epsilon(),
  410. "Scale factor must be greater-equal epsilon.");
  411. using std::sqrt;
  412. quaternion_.coeffs() *= sqrt(scale);
  413. }
  414. /// Constructor from scale factor and SO3
  415. ///
  416. /// Precondition: ``scale`` must not to be close to zero.
  417. ///
  418. SOPHUS_FUNC RxSO3(Scalar const& scale, SO3<Scalar> const& so3)
  419. : quaternion_(so3.unit_quaternion()) {
  420. SOPHUS_ENSURE(scale >= Constants<Scalar>::epsilon(),
  421. "Scale factor must be greater-equal epsilon.");
  422. using std::sqrt;
  423. quaternion_.coeffs() *= sqrt(scale);
  424. }
  425. /// Constructor from quaternion
  426. ///
  427. /// Precondition: quaternion must not be close to zero.
  428. ///
  429. template <class D>
  430. SOPHUS_FUNC explicit RxSO3(Eigen::QuaternionBase<D> const& quat)
  431. : quaternion_(quat) {
  432. static_assert(std::is_same<typename D::Scalar, Scalar>::value,
  433. "must be same Scalar type.");
  434. SOPHUS_ENSURE(quaternion_.squaredNorm() >= Constants<Scalar>::epsilon(),
  435. "Scale factor must be greater-equal epsilon.");
  436. }
  437. /// Accessor of quaternion.
  438. ///
  439. SOPHUS_FUNC QuaternionMember const& quaternion() const { return quaternion_; }
  440. /// Returns derivative of exp(x).matrix() wrt. ``x_i at x=0``.
  441. ///
  442. SOPHUS_FUNC static Transformation Dxi_exp_x_matrix_at_0(int i) {
  443. return generator(i);
  444. }
  445. /// Group exponential
  446. ///
  447. /// This functions takes in an element of tangent space (= rotation 3-vector
  448. /// plus logarithm of scale) and returns the corresponding element of the
  449. /// group RxSO3.
  450. ///
  451. /// To be more specific, thixs function computes ``expmat(hat(omega))``
  452. /// with ``expmat(.)`` being the matrix exponential and ``hat(.)`` being the
  453. /// hat()-operator of RSO3.
  454. ///
  455. SOPHUS_FUNC static RxSO3<Scalar> exp(Tangent const& a) {
  456. Scalar theta;
  457. return expAndTheta(a, &theta);
  458. }
  459. /// As above, but also returns ``theta = |omega|`` as out-parameter.
  460. ///
  461. /// Precondition: ``theta`` must not be ``nullptr``.
  462. ///
  463. SOPHUS_FUNC static RxSO3<Scalar> expAndTheta(Tangent const& a,
  464. Scalar* theta) {
  465. SOPHUS_ENSURE(theta != nullptr, "must not be nullptr.");
  466. using std::exp;
  467. using std::sqrt;
  468. Vector3<Scalar> const omega = a.template head<3>();
  469. Scalar sigma = a[3];
  470. Scalar sqrt_scale = sqrt(exp(sigma));
  471. Eigen::Quaternion<Scalar> quat =
  472. SO3<Scalar>::expAndTheta(omega, theta).unit_quaternion();
  473. quat.coeffs() *= sqrt_scale;
  474. return RxSO3<Scalar>(quat);
  475. }
  476. /// Returns the ith infinitesimal generators of ``R+ x SO(3)``.
  477. ///
  478. /// The infinitesimal generators of RxSO3 are:
  479. ///
  480. /// ```
  481. /// | 0 0 0 |
  482. /// G_0 = | 0 0 -1 |
  483. /// | 0 1 0 |
  484. ///
  485. /// | 0 0 1 |
  486. /// G_1 = | 0 0 0 |
  487. /// | -1 0 0 |
  488. ///
  489. /// | 0 -1 0 |
  490. /// G_2 = | 1 0 0 |
  491. /// | 0 0 0 |
  492. ///
  493. /// | 1 0 0 |
  494. /// G_2 = | 0 1 0 |
  495. /// | 0 0 1 |
  496. /// ```
  497. ///
  498. /// Precondition: ``i`` must be 0, 1, 2 or 3.
  499. ///
  500. SOPHUS_FUNC static Transformation generator(int i) {
  501. SOPHUS_ENSURE(i >= 0 && i <= 3, "i should be in range [0,3].");
  502. Tangent e;
  503. e.setZero();
  504. e[i] = Scalar(1);
  505. return hat(e);
  506. }
  507. /// hat-operator
  508. ///
  509. /// It takes in the 4-vector representation ``a`` (= rotation vector plus
  510. /// logarithm of scale) and returns the corresponding matrix representation
  511. /// of Lie algebra element.
  512. ///
  513. /// Formally, the hat()-operator of RxSO3 is defined as
  514. ///
  515. /// ``hat(.): R^4 -> R^{3x3}, hat(a) = sum_i a_i * G_i`` (for i=0,1,2,3)
  516. ///
  517. /// with ``G_i`` being the ith infinitesimal generator of RxSO3.
  518. ///
  519. /// The corresponding inverse is the vee()-operator, see below.
  520. ///
  521. SOPHUS_FUNC static Transformation hat(Tangent const& a) {
  522. Transformation A;
  523. // clang-format off
  524. A << a(3), -a(2), a(1),
  525. a(2), a(3), -a(0),
  526. -a(1), a(0), a(3);
  527. // clang-format on
  528. return A;
  529. }
  530. /// Lie bracket
  531. ///
  532. /// It computes the Lie bracket of RxSO(3). To be more specific, it computes
  533. ///
  534. /// ``[omega_1, omega_2]_rxso3 := vee([hat(omega_1), hat(omega_2)])``
  535. ///
  536. /// with ``[A,B] := AB-BA`` being the matrix commutator, ``hat(.)`` the
  537. /// hat()-operator and ``vee(.)`` the vee()-operator of RxSO3.
  538. ///
  539. SOPHUS_FUNC static Tangent lieBracket(Tangent const& a, Tangent const& b) {
  540. Vector3<Scalar> const omega1 = a.template head<3>();
  541. Vector3<Scalar> const omega2 = b.template head<3>();
  542. Vector4<Scalar> res;
  543. res.template head<3>() = omega1.cross(omega2);
  544. res[3] = Scalar(0);
  545. return res;
  546. }
  547. /// Draw uniform sample from RxSO(3) manifold.
  548. ///
  549. /// The scale factor is drawn uniformly in log2-space from [-1, 1],
  550. /// hence the scale is in [0.5, 2].
  551. ///
  552. template <class UniformRandomBitGenerator>
  553. static RxSO3 sampleUniform(UniformRandomBitGenerator& generator) {
  554. std::uniform_real_distribution<Scalar> uniform(Scalar(-1), Scalar(1));
  555. using std::exp2;
  556. return RxSO3(exp2(uniform(generator)),
  557. SO3<Scalar>::sampleUniform(generator));
  558. }
  559. /// vee-operator
  560. ///
  561. /// It takes the 3x3-matrix representation ``Omega`` and maps it to the
  562. /// corresponding vector representation of Lie algebra.
  563. ///
  564. /// This is the inverse of the hat()-operator, see above.
  565. ///
  566. /// Precondition: ``Omega`` must have the following structure:
  567. ///
  568. /// | d -c b |
  569. /// | c d -a |
  570. /// | -b a d |
  571. ///
  572. SOPHUS_FUNC static Tangent vee(Transformation const& Omega) {
  573. using std::abs;
  574. return Tangent(Omega(2, 1), Omega(0, 2), Omega(1, 0), Omega(0, 0));
  575. }
  576. protected:
  577. SOPHUS_FUNC QuaternionMember& quaternion_nonconst() { return quaternion_; }
  578. QuaternionMember quaternion_;
  579. };
  580. } // namespace Sophus
  581. namespace Eigen {
  582. /// Specialization of Eigen::Map for ``RxSO3``; derived from RxSO3Base
  583. ///
  584. /// Allows us to wrap RxSO3 objects around POD array (e.g. external c style
  585. /// quaternion).
  586. template <class Scalar_, int Options>
  587. class Map<Sophus::RxSO3<Scalar_>, Options>
  588. : public Sophus::RxSO3Base<Map<Sophus::RxSO3<Scalar_>, Options>> {
  589. public:
  590. using Base = Sophus::RxSO3Base<Map<Sophus::RxSO3<Scalar_>, Options>>;
  591. using Scalar = Scalar_;
  592. using Transformation = typename Base::Transformation;
  593. using Point = typename Base::Point;
  594. using HomogeneousPoint = typename Base::HomogeneousPoint;
  595. using Tangent = typename Base::Tangent;
  596. using Adjoint = typename Base::Adjoint;
  597. /// ``Base`` is friend so quaternion_nonconst can be accessed from ``Base``.
  598. friend class Sophus::RxSO3Base<Map<Sophus::RxSO3<Scalar_>, Options>>;
  599. // LCOV_EXCL_START
  600. SOPHUS_INHERIT_ASSIGNMENT_OPERATORS(Map);
  601. // LCOV_EXCL_STOP
  602. using Base::operator*=;
  603. using Base::operator*;
  604. SOPHUS_FUNC Map(Scalar* coeffs) : quaternion_(coeffs) {}
  605. /// Accessor of quaternion.
  606. ///
  607. SOPHUS_FUNC
  608. Map<Eigen::Quaternion<Scalar>, Options> const& quaternion() const {
  609. return quaternion_;
  610. }
  611. protected:
  612. SOPHUS_FUNC Map<Eigen::Quaternion<Scalar>, Options>& quaternion_nonconst() {
  613. return quaternion_;
  614. }
  615. Map<Eigen::Quaternion<Scalar>, Options> quaternion_;
  616. };
  617. /// Specialization of Eigen::Map for ``RxSO3 const``; derived from RxSO3Base.
  618. ///
  619. /// Allows us to wrap RxSO3 objects around POD array (e.g. external c style
  620. /// quaternion).
  621. template <class Scalar_, int Options>
  622. class Map<Sophus::RxSO3<Scalar_> const, Options>
  623. : public Sophus::RxSO3Base<Map<Sophus::RxSO3<Scalar_> const, Options>> {
  624. public:
  625. using Base = Sophus::RxSO3Base<Map<Sophus::RxSO3<Scalar_> const, Options>>;
  626. using Scalar = Scalar_;
  627. using Transformation = typename Base::Transformation;
  628. using Point = typename Base::Point;
  629. using HomogeneousPoint = typename Base::HomogeneousPoint;
  630. using Tangent = typename Base::Tangent;
  631. using Adjoint = typename Base::Adjoint;
  632. using Base::operator*=;
  633. using Base::operator*;
  634. SOPHUS_FUNC
  635. Map(Scalar const* coeffs) : quaternion_(coeffs) {}
  636. /// Accessor of quaternion.
  637. ///
  638. SOPHUS_FUNC
  639. Map<Eigen::Quaternion<Scalar> const, Options> const& quaternion() const {
  640. return quaternion_;
  641. }
  642. protected:
  643. Map<Eigen::Quaternion<Scalar> const, Options> const quaternion_;
  644. };
  645. } // namespace Eigen
  646. #endif /// SOPHUS_RXSO3_HPP