rxso3.hpp 24 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725
  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-like operator from OtherDerived.
  194. ///
  195. template <class OtherDerived>
  196. SOPHUS_FUNC RxSO3Base<Derived>& operator=(
  197. RxSO3Base<OtherDerived> const& other) {
  198. quaternion_nonconst() = other.quaternion();
  199. return *this;
  200. }
  201. /// Group multiplication, which is rotation concatenation and scale
  202. /// multiplication.
  203. ///
  204. /// Note: This function performs saturation for products close to zero in
  205. /// order to ensure the class invariant.
  206. ///
  207. template <typename OtherDerived>
  208. SOPHUS_FUNC RxSO3Product<OtherDerived> operator*(
  209. RxSO3Base<OtherDerived> const& other) const {
  210. using ResultT = ReturnScalar<OtherDerived>;
  211. typename RxSO3Product<OtherDerived>::QuaternionType result_quaternion(
  212. quaternion() * other.quaternion());
  213. ResultT scale = result_quaternion.squaredNorm();
  214. if (scale < Constants<ResultT>::epsilon()) {
  215. SOPHUS_ENSURE(scale > ResultT(0), "Scale must be greater zero.");
  216. /// Saturation to ensure class invariant.
  217. result_quaternion.normalize();
  218. result_quaternion.coeffs() *= sqrt(Constants<Scalar>::epsilon());
  219. }
  220. return RxSO3Product<OtherDerived>(result_quaternion);
  221. }
  222. /// Group action on 3-points.
  223. ///
  224. /// This function rotates a 3 dimensional point ``p`` by the SO3 element
  225. /// ``bar_R_foo`` (= rotation matrix) and scales it by the scale factor
  226. /// ``s``:
  227. ///
  228. /// ``p_bar = s * (bar_R_foo * p_foo)``.
  229. ///
  230. template <typename PointDerived,
  231. typename = typename std::enable_if<
  232. IsFixedSizeVector<PointDerived, 3>::value>::type>
  233. SOPHUS_FUNC PointProduct<PointDerived> operator*(
  234. Eigen::MatrixBase<PointDerived> const& p) const {
  235. // Follows http:///eigen.tuxfamily.org/bz/show_bug.cgi?id=459
  236. Scalar scale = quaternion().squaredNorm();
  237. PointProduct<PointDerived> two_vec_cross_p = quaternion().vec().cross(p);
  238. two_vec_cross_p += two_vec_cross_p;
  239. return scale * p + (quaternion().w() * two_vec_cross_p +
  240. quaternion().vec().cross(two_vec_cross_p));
  241. }
  242. /// Group action on homogeneous 3-points. See above for more details.
  243. ///
  244. template <typename HPointDerived,
  245. typename = typename std::enable_if<
  246. IsFixedSizeVector<HPointDerived, 4>::value>::type>
  247. SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> operator*(
  248. Eigen::MatrixBase<HPointDerived> const& p) const {
  249. const auto rsp = *this * p.template head<3>();
  250. return HomogeneousPointProduct<HPointDerived>(rsp(0), rsp(1), rsp(2), p(3));
  251. }
  252. /// Group action on lines.
  253. ///
  254. /// This function rotates a parametrized line ``l(t) = o + t * d`` by the SO3
  255. /// element ans scales it by the scale factor:
  256. ///
  257. /// Origin ``o`` is rotated and scaled
  258. /// Direction ``d`` is rotated (preserving it's norm)
  259. ///
  260. SOPHUS_FUNC Line operator*(Line const& l) const {
  261. return Line((*this) * l.origin(),
  262. (*this) * l.direction() / quaternion().squaredNorm());
  263. }
  264. /// In-place group multiplication. This method is only valid if the return
  265. /// type of the multiplication is compatible with this SO3's Scalar type.
  266. ///
  267. /// Note: This function performs saturation for products close to zero in
  268. /// order to ensure the class invariant.
  269. ///
  270. template <typename OtherDerived,
  271. typename = typename std::enable_if<
  272. std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
  273. SOPHUS_FUNC RxSO3Base<Derived>& operator*=(
  274. RxSO3Base<OtherDerived> const& other) {
  275. *static_cast<Derived*>(this) = *this * other;
  276. return *this;
  277. }
  278. /// Returns internal parameters of RxSO(3).
  279. ///
  280. /// It returns (q.imag[0], q.imag[1], q.imag[2], q.real), with q being the
  281. /// quaternion.
  282. ///
  283. SOPHUS_FUNC Sophus::Vector<Scalar, num_parameters> params() const {
  284. return quaternion().coeffs();
  285. }
  286. /// Sets non-zero quaternion
  287. ///
  288. /// Precondition: ``quat`` must not be close to zero.
  289. SOPHUS_FUNC void setQuaternion(Eigen::Quaternion<Scalar> const& quat) {
  290. SOPHUS_ENSURE(quat.squaredNorm() > Constants<Scalar>::epsilon() *
  291. Constants<Scalar>::epsilon(),
  292. "Scale factor must be greater-equal epsilon.");
  293. static_cast<Derived*>(this)->quaternion_nonconst() = quat;
  294. }
  295. /// Accessor of quaternion.
  296. ///
  297. SOPHUS_FUNC QuaternionType const& quaternion() const {
  298. return static_cast<Derived const*>(this)->quaternion();
  299. }
  300. /// Returns rotation matrix.
  301. ///
  302. SOPHUS_FUNC Transformation rotationMatrix() const {
  303. QuaternionTemporaryType norm_quad = quaternion();
  304. norm_quad.normalize();
  305. return norm_quad.toRotationMatrix();
  306. }
  307. /// Returns scale.
  308. ///
  309. SOPHUS_FUNC
  310. Scalar scale() const { return quaternion().squaredNorm(); }
  311. /// Setter of quaternion using rotation matrix ``R``, leaves scale as is.
  312. ///
  313. SOPHUS_FUNC void setRotationMatrix(Transformation const& R) {
  314. using std::sqrt;
  315. Scalar saved_scale = scale();
  316. quaternion_nonconst() = R;
  317. quaternion_nonconst().coeffs() *= sqrt(saved_scale);
  318. }
  319. /// Sets scale and leaves rotation as is.
  320. ///
  321. /// Note: This function as a significant computational cost, since it has to
  322. /// call the square root twice.
  323. ///
  324. SOPHUS_FUNC
  325. void setScale(Scalar const& scale) {
  326. using std::sqrt;
  327. quaternion_nonconst().normalize();
  328. quaternion_nonconst().coeffs() *= sqrt(scale);
  329. }
  330. /// Setter of quaternion using scaled rotation matrix ``sR``.
  331. ///
  332. /// Precondition: The 3x3 matrix must be "scaled orthogonal"
  333. /// and have a positive determinant.
  334. ///
  335. SOPHUS_FUNC void setScaledRotationMatrix(Transformation const& sR) {
  336. Transformation squared_sR = sR * sR.transpose();
  337. Scalar squared_scale =
  338. Scalar(1. / 3.) *
  339. (squared_sR(0, 0) + squared_sR(1, 1) + squared_sR(2, 2));
  340. SOPHUS_ENSURE(squared_scale >= Constants<Scalar>::epsilon() *
  341. Constants<Scalar>::epsilon(),
  342. "Scale factor must be greater-equal epsilon.");
  343. Scalar scale = sqrt(squared_scale);
  344. quaternion_nonconst() = sR / scale;
  345. quaternion_nonconst().coeffs() *= sqrt(scale);
  346. }
  347. /// Setter of SO(3) rotations, leaves scale as is.
  348. ///
  349. SOPHUS_FUNC void setSO3(SO3<Scalar> const& so3) {
  350. using std::sqrt;
  351. Scalar saved_scale = scale();
  352. quaternion_nonconst() = so3.unit_quaternion();
  353. quaternion_nonconst().coeffs() *= sqrt(saved_scale);
  354. }
  355. SOPHUS_FUNC SO3<Scalar> so3() const { return SO3<Scalar>(quaternion()); }
  356. private:
  357. /// Mutator of quaternion is private to ensure class invariant.
  358. ///
  359. SOPHUS_FUNC QuaternionType& quaternion_nonconst() {
  360. return static_cast<Derived*>(this)->quaternion_nonconst();
  361. }
  362. };
  363. /// RxSO3 using storage; derived from RxSO3Base.
  364. template <class Scalar_, int Options>
  365. class RxSO3 : public RxSO3Base<RxSO3<Scalar_, Options>> {
  366. public:
  367. using Base = RxSO3Base<RxSO3<Scalar_, Options>>;
  368. using Scalar = Scalar_;
  369. using Transformation = typename Base::Transformation;
  370. using Point = typename Base::Point;
  371. using HomogeneousPoint = typename Base::HomogeneousPoint;
  372. using Tangent = typename Base::Tangent;
  373. using Adjoint = typename Base::Adjoint;
  374. using QuaternionMember = Eigen::Quaternion<Scalar, Options>;
  375. /// ``Base`` is friend so quaternion_nonconst can be accessed from ``Base``.
  376. friend class RxSO3Base<RxSO3<Scalar_, Options>>;
  377. using Base::operator=;
  378. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  379. /// Default constructor initializes quaternion to identity rotation and scale
  380. /// to 1.
  381. ///
  382. SOPHUS_FUNC RxSO3()
  383. : quaternion_(Scalar(1), Scalar(0), Scalar(0), Scalar(0)) {}
  384. /// Copy constructor
  385. ///
  386. SOPHUS_FUNC RxSO3(RxSO3 const& other) = default;
  387. /// Copy-like constructor from OtherDerived
  388. ///
  389. template <class OtherDerived>
  390. SOPHUS_FUNC RxSO3(RxSO3Base<OtherDerived> const& other)
  391. : quaternion_(other.quaternion()) {}
  392. /// Constructor from scaled rotation matrix
  393. ///
  394. /// Precondition: rotation matrix need to be scaled orthogonal with
  395. /// determinant of ``s^3``.
  396. ///
  397. SOPHUS_FUNC explicit RxSO3(Transformation const& sR) {
  398. this->setScaledRotationMatrix(sR);
  399. }
  400. /// Constructor from scale factor and rotation matrix ``R``.
  401. ///
  402. /// Precondition: Rotation matrix ``R`` must to be orthogonal with determinant
  403. /// of 1 and ``scale`` must not be close to zero.
  404. ///
  405. SOPHUS_FUNC RxSO3(Scalar const& scale, Transformation const& R)
  406. : quaternion_(R) {
  407. SOPHUS_ENSURE(scale >= Constants<Scalar>::epsilon(),
  408. "Scale factor must be greater-equal epsilon.");
  409. using std::sqrt;
  410. quaternion_.coeffs() *= sqrt(scale);
  411. }
  412. /// Constructor from scale factor and SO3
  413. ///
  414. /// Precondition: ``scale`` must not to be close to zero.
  415. ///
  416. SOPHUS_FUNC RxSO3(Scalar const& scale, SO3<Scalar> const& so3)
  417. : quaternion_(so3.unit_quaternion()) {
  418. SOPHUS_ENSURE(scale >= Constants<Scalar>::epsilon(),
  419. "Scale factor must be greater-equal epsilon.");
  420. using std::sqrt;
  421. quaternion_.coeffs() *= sqrt(scale);
  422. }
  423. /// Constructor from quaternion
  424. ///
  425. /// Precondition: quaternion must not be close to zero.
  426. ///
  427. template <class D>
  428. SOPHUS_FUNC explicit RxSO3(Eigen::QuaternionBase<D> const& quat)
  429. : quaternion_(quat) {
  430. static_assert(std::is_same<typename D::Scalar, Scalar>::value,
  431. "must be same Scalar type.");
  432. SOPHUS_ENSURE(quaternion_.squaredNorm() >= Constants<Scalar>::epsilon(),
  433. "Scale factor must be greater-equal epsilon.");
  434. }
  435. /// Accessor of quaternion.
  436. ///
  437. SOPHUS_FUNC QuaternionMember const& quaternion() const { return quaternion_; }
  438. /// Returns derivative of exp(x).matrix() wrt. ``x_i at x=0``.
  439. ///
  440. SOPHUS_FUNC static Transformation Dxi_exp_x_matrix_at_0(int i) {
  441. return generator(i);
  442. }
  443. /// Group exponential
  444. ///
  445. /// This functions takes in an element of tangent space (= rotation 3-vector
  446. /// plus logarithm of scale) and returns the corresponding element of the
  447. /// group RxSO3.
  448. ///
  449. /// To be more specific, thixs function computes ``expmat(hat(omega))``
  450. /// with ``expmat(.)`` being the matrix exponential and ``hat(.)`` being the
  451. /// hat()-operator of RSO3.
  452. ///
  453. SOPHUS_FUNC static RxSO3<Scalar> exp(Tangent const& a) {
  454. Scalar theta;
  455. return expAndTheta(a, &theta);
  456. }
  457. /// As above, but also returns ``theta = |omega|`` as out-parameter.
  458. ///
  459. /// Precondition: ``theta`` must not be ``nullptr``.
  460. ///
  461. SOPHUS_FUNC static RxSO3<Scalar> expAndTheta(Tangent const& a,
  462. Scalar* theta) {
  463. SOPHUS_ENSURE(theta != nullptr, "must not be nullptr.");
  464. using std::exp;
  465. using std::sqrt;
  466. Vector3<Scalar> const omega = a.template head<3>();
  467. Scalar sigma = a[3];
  468. Scalar sqrt_scale = sqrt(exp(sigma));
  469. Eigen::Quaternion<Scalar> quat =
  470. SO3<Scalar>::expAndTheta(omega, theta).unit_quaternion();
  471. quat.coeffs() *= sqrt_scale;
  472. return RxSO3<Scalar>(quat);
  473. }
  474. /// Returns the ith infinitesimal generators of ``R+ x SO(3)``.
  475. ///
  476. /// The infinitesimal generators of RxSO3 are:
  477. ///
  478. /// ```
  479. /// | 0 0 0 |
  480. /// G_0 = | 0 0 -1 |
  481. /// | 0 1 0 |
  482. ///
  483. /// | 0 0 1 |
  484. /// G_1 = | 0 0 0 |
  485. /// | -1 0 0 |
  486. ///
  487. /// | 0 -1 0 |
  488. /// G_2 = | 1 0 0 |
  489. /// | 0 0 0 |
  490. ///
  491. /// | 1 0 0 |
  492. /// G_2 = | 0 1 0 |
  493. /// | 0 0 1 |
  494. /// ```
  495. ///
  496. /// Precondition: ``i`` must be 0, 1, 2 or 3.
  497. ///
  498. SOPHUS_FUNC static Transformation generator(int i) {
  499. SOPHUS_ENSURE(i >= 0 && i <= 3, "i should be in range [0,3].");
  500. Tangent e;
  501. e.setZero();
  502. e[i] = Scalar(1);
  503. return hat(e);
  504. }
  505. /// hat-operator
  506. ///
  507. /// It takes in the 4-vector representation ``a`` (= rotation vector plus
  508. /// logarithm of scale) and returns the corresponding matrix representation
  509. /// of Lie algebra element.
  510. ///
  511. /// Formally, the hat()-operator of RxSO3 is defined as
  512. ///
  513. /// ``hat(.): R^4 -> R^{3x3}, hat(a) = sum_i a_i * G_i`` (for i=0,1,2,3)
  514. ///
  515. /// with ``G_i`` being the ith infinitesimal generator of RxSO3.
  516. ///
  517. /// The corresponding inverse is the vee()-operator, see below.
  518. ///
  519. SOPHUS_FUNC static Transformation hat(Tangent const& a) {
  520. Transformation A;
  521. // clang-format off
  522. A << a(3), -a(2), a(1),
  523. a(2), a(3), -a(0),
  524. -a(1), a(0), a(3);
  525. // clang-format on
  526. return A;
  527. }
  528. /// Lie bracket
  529. ///
  530. /// It computes the Lie bracket of RxSO(3). To be more specific, it computes
  531. ///
  532. /// ``[omega_1, omega_2]_rxso3 := vee([hat(omega_1), hat(omega_2)])``
  533. ///
  534. /// with ``[A,B] := AB-BA`` being the matrix commutator, ``hat(.)`` the
  535. /// hat()-operator and ``vee(.)`` the vee()-operator of RxSO3.
  536. ///
  537. SOPHUS_FUNC static Tangent lieBracket(Tangent const& a, Tangent const& b) {
  538. Vector3<Scalar> const omega1 = a.template head<3>();
  539. Vector3<Scalar> const omega2 = b.template head<3>();
  540. Vector4<Scalar> res;
  541. res.template head<3>() = omega1.cross(omega2);
  542. res[3] = Scalar(0);
  543. return res;
  544. }
  545. /// Draw uniform sample from RxSO(3) manifold.
  546. ///
  547. /// The scale factor is drawn uniformly in log2-space from [-1, 1],
  548. /// hence the scale is in [0.5, 2].
  549. ///
  550. template <class UniformRandomBitGenerator>
  551. static RxSO3 sampleUniform(UniformRandomBitGenerator& generator) {
  552. std::uniform_real_distribution<Scalar> uniform(Scalar(-1), Scalar(1));
  553. using std::exp2;
  554. return RxSO3(exp2(uniform(generator)),
  555. SO3<Scalar>::sampleUniform(generator));
  556. }
  557. /// vee-operator
  558. ///
  559. /// It takes the 3x3-matrix representation ``Omega`` and maps it to the
  560. /// corresponding vector representation of Lie algebra.
  561. ///
  562. /// This is the inverse of the hat()-operator, see above.
  563. ///
  564. /// Precondition: ``Omega`` must have the following structure:
  565. ///
  566. /// | d -c b |
  567. /// | c d -a |
  568. /// | -b a d |
  569. ///
  570. SOPHUS_FUNC static Tangent vee(Transformation const& Omega) {
  571. using std::abs;
  572. return Tangent(Omega(2, 1), Omega(0, 2), Omega(1, 0), Omega(0, 0));
  573. }
  574. protected:
  575. SOPHUS_FUNC QuaternionMember& quaternion_nonconst() { return quaternion_; }
  576. QuaternionMember quaternion_;
  577. };
  578. } // namespace Sophus
  579. namespace Eigen {
  580. /// Specialization of Eigen::Map for ``RxSO3``; derived from RxSO3Base
  581. ///
  582. /// Allows us to wrap RxSO3 objects around POD array (e.g. external c style
  583. /// quaternion).
  584. template <class Scalar_, int Options>
  585. class Map<Sophus::RxSO3<Scalar_>, Options>
  586. : public Sophus::RxSO3Base<Map<Sophus::RxSO3<Scalar_>, Options>> {
  587. public:
  588. using Base = Sophus::RxSO3Base<Map<Sophus::RxSO3<Scalar_>, Options>>;
  589. using Scalar = Scalar_;
  590. using Transformation = typename Base::Transformation;
  591. using Point = typename Base::Point;
  592. using HomogeneousPoint = typename Base::HomogeneousPoint;
  593. using Tangent = typename Base::Tangent;
  594. using Adjoint = typename Base::Adjoint;
  595. /// ``Base`` is friend so quaternion_nonconst can be accessed from ``Base``.
  596. friend class Sophus::RxSO3Base<Map<Sophus::RxSO3<Scalar_>, Options>>;
  597. using Base::operator=;
  598. using Base::operator*=;
  599. using Base::operator*;
  600. SOPHUS_FUNC Map(Scalar* coeffs) : quaternion_(coeffs) {}
  601. /// Accessor of quaternion.
  602. ///
  603. SOPHUS_FUNC
  604. Map<Eigen::Quaternion<Scalar>, Options> const& quaternion() const {
  605. return quaternion_;
  606. }
  607. protected:
  608. SOPHUS_FUNC Map<Eigen::Quaternion<Scalar>, Options>& quaternion_nonconst() {
  609. return quaternion_;
  610. }
  611. Map<Eigen::Quaternion<Scalar>, Options> quaternion_;
  612. };
  613. /// Specialization of Eigen::Map for ``RxSO3 const``; derived from RxSO3Base.
  614. ///
  615. /// Allows us to wrap RxSO3 objects around POD array (e.g. external c style
  616. /// quaternion).
  617. template <class Scalar_, int Options>
  618. class Map<Sophus::RxSO3<Scalar_> const, Options>
  619. : public Sophus::RxSO3Base<Map<Sophus::RxSO3<Scalar_> const, Options>> {
  620. public:
  621. using Base = Sophus::RxSO3Base<Map<Sophus::RxSO3<Scalar_> const, Options>>;
  622. using Scalar = Scalar_;
  623. using Transformation = typename Base::Transformation;
  624. using Point = typename Base::Point;
  625. using HomogeneousPoint = typename Base::HomogeneousPoint;
  626. using Tangent = typename Base::Tangent;
  627. using Adjoint = typename Base::Adjoint;
  628. using Base::operator*=;
  629. using Base::operator*;
  630. SOPHUS_FUNC
  631. Map(Scalar const* coeffs) : quaternion_(coeffs) {}
  632. /// Accessor of quaternion.
  633. ///
  634. SOPHUS_FUNC
  635. Map<Eigen::Quaternion<Scalar> const, Options> const& quaternion() const {
  636. return quaternion_;
  637. }
  638. protected:
  639. Map<Eigen::Quaternion<Scalar> const, Options> const quaternion_;
  640. };
  641. } // namespace Eigen
  642. #endif /// SOPHUS_RXSO3_HPP