sim3.hpp 24 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740
  1. /// @file
  2. /// Similarity group Sim(3) - scaling, rotation and translation in 3d.
  3. #ifndef SOPHUS_SIM3_HPP
  4. #define SOPHUS_SIM3_HPP
  5. #include "rxso3.hpp"
  6. #include "sim_details.hpp"
  7. namespace Sophus {
  8. template <class Scalar_, int Options = 0>
  9. class Sim3;
  10. using Sim3d = Sim3<double>;
  11. using Sim3f = Sim3<float>;
  12. } // namespace Sophus
  13. namespace Eigen {
  14. namespace internal {
  15. template <class Scalar_, int Options>
  16. struct traits<Sophus::Sim3<Scalar_, Options>> {
  17. using Scalar = Scalar_;
  18. using TranslationType = Sophus::Vector3<Scalar, Options>;
  19. using RxSO3Type = Sophus::RxSO3<Scalar, Options>;
  20. };
  21. template <class Scalar_, int Options>
  22. struct traits<Map<Sophus::Sim3<Scalar_>, Options>>
  23. : traits<Sophus::Sim3<Scalar_, Options>> {
  24. using Scalar = Scalar_;
  25. using TranslationType = Map<Sophus::Vector3<Scalar>, Options>;
  26. using RxSO3Type = Map<Sophus::RxSO3<Scalar>, Options>;
  27. };
  28. template <class Scalar_, int Options>
  29. struct traits<Map<Sophus::Sim3<Scalar_> const, Options>>
  30. : traits<Sophus::Sim3<Scalar_, Options> const> {
  31. using Scalar = Scalar_;
  32. using TranslationType = Map<Sophus::Vector3<Scalar> const, Options>;
  33. using RxSO3Type = Map<Sophus::RxSO3<Scalar> const, Options>;
  34. };
  35. } // namespace internal
  36. } // namespace Eigen
  37. namespace Sophus {
  38. /// Sim3 base type - implements Sim3 class but is storage agnostic.
  39. ///
  40. /// Sim(3) is the group of rotations and translation and scaling in 3d. It is
  41. /// the semi-direct product of R+xSO(3) and the 3d Euclidean vector space. The
  42. /// class is represented using a composition of RxSO3 for scaling plus
  43. /// rotation and a 3-vector for translation.
  44. ///
  45. /// Sim(3) is neither compact, nor a commutative group.
  46. ///
  47. /// See RxSO3 for more details of the scaling + rotation representation in 3d.
  48. ///
  49. template <class Derived>
  50. class Sim3Base {
  51. public:
  52. using Scalar = typename Eigen::internal::traits<Derived>::Scalar;
  53. using TranslationType =
  54. typename Eigen::internal::traits<Derived>::TranslationType;
  55. using RxSO3Type = typename Eigen::internal::traits<Derived>::RxSO3Type;
  56. using QuaternionType = typename RxSO3Type::QuaternionType;
  57. /// Degrees of freedom of manifold, number of dimensions in tangent space
  58. /// (three for translation, three for rotation and one for scaling).
  59. static int constexpr DoF = 7;
  60. /// Number of internal parameters used (4-tuple for quaternion, three for
  61. /// translation).
  62. static int constexpr num_parameters = 7;
  63. /// Group transformations are 4x4 matrices.
  64. static int constexpr N = 4;
  65. using Transformation = Matrix<Scalar, N, N>;
  66. using Point = Vector3<Scalar>;
  67. using HomogeneousPoint = Vector4<Scalar>;
  68. using Line = ParametrizedLine3<Scalar>;
  69. using Tangent = Vector<Scalar, DoF>;
  70. using Adjoint = Matrix<Scalar, DoF, DoF>;
  71. /// For binary operations the return type is determined with the
  72. /// ScalarBinaryOpTraits feature of Eigen. This allows mixing concrete and Map
  73. /// types, as well as other compatible scalar types such as Ceres::Jet and
  74. /// double scalars with Sim3 operations.
  75. template <typename OtherDerived>
  76. using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<
  77. Scalar, typename OtherDerived::Scalar>::ReturnType;
  78. template <typename OtherDerived>
  79. using Sim3Product = Sim3<ReturnScalar<OtherDerived>>;
  80. template <typename PointDerived>
  81. using PointProduct = Vector3<ReturnScalar<PointDerived>>;
  82. template <typename HPointDerived>
  83. using HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived>>;
  84. /// Adjoint transformation
  85. ///
  86. /// This function return the adjoint transformation ``Ad`` of the group
  87. /// element ``A`` such that for all ``x`` it holds that
  88. /// ``hat(Ad_A * x) = A * hat(x) A^{-1}``. See hat-operator below.
  89. ///
  90. SOPHUS_FUNC Adjoint Adj() const {
  91. Matrix3<Scalar> const R = rxso3().rotationMatrix();
  92. Adjoint res;
  93. res.setZero();
  94. res.template block<3, 3>(0, 0) = rxso3().matrix();
  95. res.template block<3, 3>(0, 3) = SO3<Scalar>::hat(translation()) * R;
  96. res.template block<3, 1>(0, 6) = -translation();
  97. res.template block<3, 3>(3, 3) = R;
  98. res(6, 6) = Scalar(1);
  99. return res;
  100. }
  101. /// Returns copy of instance casted to NewScalarType.
  102. ///
  103. template <class NewScalarType>
  104. SOPHUS_FUNC Sim3<NewScalarType> cast() const {
  105. return Sim3<NewScalarType>(rxso3().template cast<NewScalarType>(),
  106. translation().template cast<NewScalarType>());
  107. }
  108. /// Returns group inverse.
  109. ///
  110. SOPHUS_FUNC Sim3<Scalar> inverse() const {
  111. RxSO3<Scalar> invR = rxso3().inverse();
  112. return Sim3<Scalar>(invR, invR * (translation() * Scalar(-1)));
  113. }
  114. /// Logarithmic map
  115. ///
  116. /// Computes the logarithm, the inverse of the group exponential which maps
  117. /// element of the group (rigid body transformations) to elements of the
  118. /// tangent space (twist).
  119. ///
  120. /// To be specific, this function computes ``vee(logmat(.))`` with
  121. /// ``logmat(.)`` being the matrix logarithm and ``vee(.)`` the vee-operator
  122. /// of Sim(3).
  123. ///
  124. SOPHUS_FUNC Tangent log() const {
  125. // The derivation of the closed-form Sim(3) logarithm for is done
  126. // analogously to the closed-form solution of the SE(3) logarithm, see
  127. // J. Gallier, D. Xu, "Computing exponentials of skew symmetric matrices
  128. // and logarithms of orthogonal matrices", IJRA 2002.
  129. // https:///pdfs.semanticscholar.org/cfe3/e4b39de63c8cabd89bf3feff7f5449fc981d.pdf
  130. // (Sec. 6., pp. 8)
  131. Tangent res;
  132. auto omega_sigma_and_theta = rxso3().logAndTheta();
  133. Vector3<Scalar> const omega =
  134. omega_sigma_and_theta.tangent.template head<3>();
  135. Scalar sigma = omega_sigma_and_theta.tangent[3];
  136. Matrix3<Scalar> const Omega = SO3<Scalar>::hat(omega);
  137. Matrix3<Scalar> const W_inv = details::calcWInv<Scalar, 3>(
  138. Omega, omega_sigma_and_theta.theta, sigma, scale());
  139. res.segment(0, 3) = W_inv * translation();
  140. res.segment(3, 3) = omega;
  141. res[6] = sigma;
  142. return res;
  143. }
  144. /// Returns 4x4 matrix representation of the instance.
  145. ///
  146. /// It has the following form:
  147. ///
  148. /// | s*R t |
  149. /// | o 1 |
  150. ///
  151. /// where ``R`` is a 3x3 rotation matrix, ``s`` a scale factor, ``t`` a
  152. /// translation 3-vector and ``o`` a 3-column vector of zeros.
  153. ///
  154. SOPHUS_FUNC Transformation matrix() const {
  155. Transformation homogenious_matrix;
  156. homogenious_matrix.template topLeftCorner<3, 4>() = matrix3x4();
  157. homogenious_matrix.row(3) =
  158. Matrix<Scalar, 4, 1>(Scalar(0), Scalar(0), Scalar(0), Scalar(1));
  159. return homogenious_matrix;
  160. }
  161. /// Returns the significant first three rows of the matrix above.
  162. ///
  163. SOPHUS_FUNC Matrix<Scalar, 3, 4> matrix3x4() const {
  164. Matrix<Scalar, 3, 4> matrix;
  165. matrix.template topLeftCorner<3, 3>() = rxso3().matrix();
  166. matrix.col(3) = translation();
  167. return matrix;
  168. }
  169. /// Assignment-like operator from OtherDerived.
  170. ///
  171. template <class OtherDerived>
  172. SOPHUS_FUNC Sim3Base<Derived>& operator=(
  173. Sim3Base<OtherDerived> const& other) {
  174. rxso3() = other.rxso3();
  175. translation() = other.translation();
  176. return *this;
  177. }
  178. /// Group multiplication, which is rotation plus scaling concatenation.
  179. ///
  180. /// Note: That scaling is calculated with saturation. See RxSO3 for
  181. /// details.
  182. ///
  183. template <typename OtherDerived>
  184. SOPHUS_FUNC Sim3Product<OtherDerived> operator*(
  185. Sim3Base<OtherDerived> const& other) const {
  186. return Sim3Product<OtherDerived>(
  187. rxso3() * other.rxso3(), translation() + rxso3() * other.translation());
  188. }
  189. /// Group action on 3-points.
  190. ///
  191. /// This function rotates, scales and translates a three dimensional point
  192. /// ``p`` by the Sim(3) element ``(bar_sR_foo, t_bar)`` (= similarity
  193. /// transformation):
  194. ///
  195. /// ``p_bar = bar_sR_foo * p_foo + t_bar``.
  196. ///
  197. template <typename PointDerived,
  198. typename = typename std::enable_if<
  199. IsFixedSizeVector<PointDerived, 3>::value>::type>
  200. SOPHUS_FUNC PointProduct<PointDerived> operator*(
  201. Eigen::MatrixBase<PointDerived> const& p) const {
  202. return rxso3() * p + translation();
  203. }
  204. /// Group action on homogeneous 3-points. See above for more details.
  205. ///
  206. template <typename HPointDerived,
  207. typename = typename std::enable_if<
  208. IsFixedSizeVector<HPointDerived, 4>::value>::type>
  209. SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> operator*(
  210. Eigen::MatrixBase<HPointDerived> const& p) const {
  211. const PointProduct<HPointDerived> tp =
  212. rxso3() * p.template head<3>() + p(3) * translation();
  213. return HomogeneousPointProduct<HPointDerived>(tp(0), tp(1), tp(2), p(3));
  214. }
  215. /// Group action on lines.
  216. ///
  217. /// This function rotates, scales and translates a parametrized line
  218. /// ``l(t) = o + t * d`` by the Sim(3) element:
  219. ///
  220. /// Origin ``o`` is rotated, scaled and translated
  221. /// Direction ``d`` is rotated
  222. ///
  223. SOPHUS_FUNC Line operator*(Line const& l) const {
  224. Line rotatedLine = rxso3() * l;
  225. return Line(rotatedLine.origin() + translation(), rotatedLine.direction());
  226. }
  227. /// In-place group multiplication. This method is only valid if the return
  228. /// type of the multiplication is compatible with this SO3's Scalar type.
  229. ///
  230. template <typename OtherDerived,
  231. typename = typename std::enable_if<
  232. std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
  233. SOPHUS_FUNC Sim3Base<Derived>& operator*=(
  234. Sim3Base<OtherDerived> const& other) {
  235. *static_cast<Derived*>(this) = *this * other;
  236. return *this;
  237. }
  238. /// Returns internal parameters of Sim(3).
  239. ///
  240. /// It returns (q.imag[0], q.imag[1], q.imag[2], q.real, t[0], t[1], t[2]),
  241. /// with q being the quaternion, t the translation 3-vector.
  242. ///
  243. SOPHUS_FUNC Sophus::Vector<Scalar, num_parameters> params() const {
  244. Sophus::Vector<Scalar, num_parameters> p;
  245. p << rxso3().params(), translation();
  246. return p;
  247. }
  248. /// Setter of non-zero quaternion.
  249. ///
  250. /// Precondition: ``quat`` must not be close to zero.
  251. ///
  252. SOPHUS_FUNC void setQuaternion(Eigen::Quaternion<Scalar> const& quat) {
  253. rxso3().setQuaternion(quat);
  254. }
  255. /// Accessor of quaternion.
  256. ///
  257. SOPHUS_FUNC QuaternionType const& quaternion() const {
  258. return rxso3().quaternion();
  259. }
  260. /// Returns Rotation matrix
  261. ///
  262. SOPHUS_FUNC Matrix3<Scalar> rotationMatrix() const {
  263. return rxso3().rotationMatrix();
  264. }
  265. /// Mutator of SO3 group.
  266. ///
  267. SOPHUS_FUNC RxSO3Type& rxso3() {
  268. return static_cast<Derived*>(this)->rxso3();
  269. }
  270. /// Accessor of SO3 group.
  271. ///
  272. SOPHUS_FUNC RxSO3Type const& rxso3() const {
  273. return static_cast<Derived const*>(this)->rxso3();
  274. }
  275. /// Returns scale.
  276. ///
  277. SOPHUS_FUNC Scalar scale() const { return rxso3().scale(); }
  278. /// Setter of quaternion using rotation matrix ``R``, leaves scale as is.
  279. ///
  280. SOPHUS_FUNC void setRotationMatrix(Matrix3<Scalar>& R) {
  281. rxso3().setRotationMatrix(R);
  282. }
  283. /// Sets scale and leaves rotation as is.
  284. ///
  285. /// Note: This function as a significant computational cost, since it has to
  286. /// call the square root twice.
  287. ///
  288. SOPHUS_FUNC void setScale(Scalar const& scale) { rxso3().setScale(scale); }
  289. /// Setter of quaternion using scaled rotation matrix ``sR``.
  290. ///
  291. /// Precondition: The 3x3 matrix must be "scaled orthogonal"
  292. /// and have a positive determinant.
  293. ///
  294. SOPHUS_FUNC void setScaledRotationMatrix(Matrix3<Scalar> const& sR) {
  295. rxso3().setScaledRotationMatrix(sR);
  296. }
  297. /// Mutator of translation vector
  298. ///
  299. SOPHUS_FUNC TranslationType& translation() {
  300. return static_cast<Derived*>(this)->translation();
  301. }
  302. /// Accessor of translation vector
  303. ///
  304. SOPHUS_FUNC TranslationType const& translation() const {
  305. return static_cast<Derived const*>(this)->translation();
  306. }
  307. };
  308. /// Sim3 using default storage; derived from Sim3Base.
  309. template <class Scalar_, int Options>
  310. class Sim3 : public Sim3Base<Sim3<Scalar_, Options>> {
  311. public:
  312. using Base = Sim3Base<Sim3<Scalar_, Options>>;
  313. using Scalar = Scalar_;
  314. using Transformation = typename Base::Transformation;
  315. using Point = typename Base::Point;
  316. using HomogeneousPoint = typename Base::HomogeneousPoint;
  317. using Tangent = typename Base::Tangent;
  318. using Adjoint = typename Base::Adjoint;
  319. using RxSo3Member = RxSO3<Scalar, Options>;
  320. using TranslationMember = Vector3<Scalar, Options>;
  321. using Base::operator=;
  322. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  323. /// Default constructor initializes similarity transform to the identity.
  324. ///
  325. SOPHUS_FUNC Sim3();
  326. /// Copy constructor
  327. ///
  328. SOPHUS_FUNC Sim3(Sim3 const& other) = default;
  329. /// Copy-like constructor from OtherDerived.
  330. ///
  331. template <class OtherDerived>
  332. SOPHUS_FUNC Sim3(Sim3Base<OtherDerived> const& other)
  333. : rxso3_(other.rxso3()), translation_(other.translation()) {
  334. static_assert(std::is_same<typename OtherDerived::Scalar, Scalar>::value,
  335. "must be same Scalar type");
  336. }
  337. /// Constructor from RxSO3 and translation vector
  338. ///
  339. template <class OtherDerived, class D>
  340. SOPHUS_FUNC Sim3(RxSO3Base<OtherDerived> const& rxso3,
  341. Eigen::MatrixBase<D> const& translation)
  342. : rxso3_(rxso3), translation_(translation) {
  343. static_assert(std::is_same<typename OtherDerived::Scalar, Scalar>::value,
  344. "must be same Scalar type");
  345. static_assert(std::is_same<typename D::Scalar, Scalar>::value,
  346. "must be same Scalar type");
  347. }
  348. /// Constructor from quaternion and translation vector.
  349. ///
  350. /// Precondition: quaternion must not be close to zero.
  351. ///
  352. template <class D1, class D2>
  353. SOPHUS_FUNC Sim3(Eigen::QuaternionBase<D1> const& quaternion,
  354. Eigen::MatrixBase<D2> const& translation)
  355. : rxso3_(quaternion), translation_(translation) {
  356. static_assert(std::is_same<typename D1::Scalar, Scalar>::value,
  357. "must be same Scalar type");
  358. static_assert(std::is_same<typename D2::Scalar, Scalar>::value,
  359. "must be same Scalar type");
  360. }
  361. /// Constructor from 4x4 matrix
  362. ///
  363. /// Precondition: Top-left 3x3 matrix needs to be "scaled-orthogonal" with
  364. /// positive determinant. The last row must be ``(0, 0, 0, 1)``.
  365. ///
  366. SOPHUS_FUNC explicit Sim3(Matrix<Scalar, 4, 4> const& T)
  367. : rxso3_(T.template topLeftCorner<3, 3>()),
  368. translation_(T.template block<3, 1>(0, 3)) {}
  369. /// This provides unsafe read/write access to internal data. Sim(3) is
  370. /// represented by an Eigen::Quaternion (four parameters) and a 3-vector. When
  371. /// using direct write access, the user needs to take care of that the
  372. /// quaternion is not set close to zero.
  373. ///
  374. SOPHUS_FUNC Scalar* data() {
  375. // rxso3_ and translation_ are laid out sequentially with no padding
  376. return rxso3_.data();
  377. }
  378. /// Const version of data() above.
  379. ///
  380. SOPHUS_FUNC Scalar const* data() const {
  381. // rxso3_ and translation_ are laid out sequentially with no padding
  382. return rxso3_.data();
  383. }
  384. /// Accessor of RxSO3
  385. ///
  386. SOPHUS_FUNC RxSo3Member& rxso3() { return rxso3_; }
  387. /// Mutator of RxSO3
  388. ///
  389. SOPHUS_FUNC RxSo3Member const& rxso3() const { return rxso3_; }
  390. /// Mutator of translation vector
  391. ///
  392. SOPHUS_FUNC TranslationMember& translation() { return translation_; }
  393. /// Accessor of translation vector
  394. ///
  395. SOPHUS_FUNC TranslationMember const& translation() const {
  396. return translation_;
  397. }
  398. /// Returns derivative of exp(x).matrix() wrt. ``x_i at x=0``.
  399. ///
  400. SOPHUS_FUNC static Transformation Dxi_exp_x_matrix_at_0(int i) {
  401. return generator(i);
  402. }
  403. /// Group exponential
  404. ///
  405. /// This functions takes in an element of tangent space and returns the
  406. /// corresponding element of the group Sim(3).
  407. ///
  408. /// The first three components of ``a`` represent the translational part
  409. /// ``upsilon`` in the tangent space of Sim(3), the following three components
  410. /// of ``a`` represents the rotation vector ``omega`` and the final component
  411. /// represents the logarithm of the scaling factor ``sigma``.
  412. /// To be more specific, this function computes ``expmat(hat(a))`` with
  413. /// ``expmat(.)`` being the matrix exponential and ``hat(.)`` the hat-operator
  414. /// of Sim(3), see below.
  415. ///
  416. SOPHUS_FUNC static Sim3<Scalar> exp(Tangent const& a) {
  417. // For the derivation of the exponential map of Sim(3) see
  418. // H. Strasdat, "Local Accuracy and Global Consistency for Efficient Visual
  419. // SLAM", PhD thesis, 2012.
  420. // http:///hauke.strasdat.net/files/strasdat_thesis_2012.pdf (A.5, pp. 186)
  421. Vector3<Scalar> const upsilon = a.segment(0, 3);
  422. Vector3<Scalar> const omega = a.segment(3, 3);
  423. Scalar const sigma = a[6];
  424. Scalar theta;
  425. RxSO3<Scalar> rxso3 =
  426. RxSO3<Scalar>::expAndTheta(a.template tail<4>(), &theta);
  427. Matrix3<Scalar> const Omega = SO3<Scalar>::hat(omega);
  428. Matrix3<Scalar> const W = details::calcW<Scalar, 3>(Omega, theta, sigma);
  429. return Sim3<Scalar>(rxso3, W * upsilon);
  430. }
  431. /// Returns the ith infinitesimal generators of Sim(3).
  432. ///
  433. /// The infinitesimal generators of Sim(3) are:
  434. ///
  435. /// ```
  436. /// | 0 0 0 1 |
  437. /// G_0 = | 0 0 0 0 |
  438. /// | 0 0 0 0 |
  439. /// | 0 0 0 0 |
  440. ///
  441. /// | 0 0 0 0 |
  442. /// G_1 = | 0 0 0 1 |
  443. /// | 0 0 0 0 |
  444. /// | 0 0 0 0 |
  445. ///
  446. /// | 0 0 0 0 |
  447. /// G_2 = | 0 0 0 0 |
  448. /// | 0 0 0 1 |
  449. /// | 0 0 0 0 |
  450. ///
  451. /// | 0 0 0 0 |
  452. /// G_3 = | 0 0 -1 0 |
  453. /// | 0 1 0 0 |
  454. /// | 0 0 0 0 |
  455. ///
  456. /// | 0 0 1 0 |
  457. /// G_4 = | 0 0 0 0 |
  458. /// | -1 0 0 0 |
  459. /// | 0 0 0 0 |
  460. ///
  461. /// | 0 -1 0 0 |
  462. /// G_5 = | 1 0 0 0 |
  463. /// | 0 0 0 0 |
  464. /// | 0 0 0 0 |
  465. ///
  466. /// | 1 0 0 0 |
  467. /// G_6 = | 0 1 0 0 |
  468. /// | 0 0 1 0 |
  469. /// | 0 0 0 0 |
  470. /// ```
  471. ///
  472. /// Precondition: ``i`` must be in [0, 6].
  473. ///
  474. SOPHUS_FUNC static Transformation generator(int i) {
  475. SOPHUS_ENSURE(i >= 0 || i <= 6, "i should be in range [0,6].");
  476. Tangent e;
  477. e.setZero();
  478. e[i] = Scalar(1);
  479. return hat(e);
  480. }
  481. /// hat-operator
  482. ///
  483. /// It takes in the 7-vector representation and returns the corresponding
  484. /// matrix representation of Lie algebra element.
  485. ///
  486. /// Formally, the hat()-operator of Sim(3) is defined as
  487. ///
  488. /// ``hat(.): R^7 -> R^{4x4}, hat(a) = sum_i a_i * G_i`` (for i=0,...,6)
  489. ///
  490. /// with ``G_i`` being the ith infinitesimal generator of Sim(3).
  491. ///
  492. /// The corresponding inverse is the vee()-operator, see below.
  493. ///
  494. SOPHUS_FUNC static Transformation hat(Tangent const& a) {
  495. Transformation Omega;
  496. Omega.template topLeftCorner<3, 3>() =
  497. RxSO3<Scalar>::hat(a.template tail<4>());
  498. Omega.col(3).template head<3>() = a.template head<3>();
  499. Omega.row(3).setZero();
  500. return Omega;
  501. }
  502. /// Lie bracket
  503. ///
  504. /// It computes the Lie bracket of Sim(3). To be more specific, it computes
  505. ///
  506. /// ``[omega_1, omega_2]_sim3 := vee([hat(omega_1), hat(omega_2)])``
  507. ///
  508. /// with ``[A,B] := AB-BA`` being the matrix commutator, ``hat(.)`` the
  509. /// hat()-operator and ``vee(.)`` the vee()-operator of Sim(3).
  510. ///
  511. SOPHUS_FUNC static Tangent lieBracket(Tangent const& a, Tangent const& b) {
  512. Vector3<Scalar> const upsilon1 = a.template head<3>();
  513. Vector3<Scalar> const upsilon2 = b.template head<3>();
  514. Vector3<Scalar> const omega1 = a.template segment<3>(3);
  515. Vector3<Scalar> const omega2 = b.template segment<3>(3);
  516. Scalar sigma1 = a[6];
  517. Scalar sigma2 = b[6];
  518. Tangent res;
  519. res.template head<3>() = SO3<Scalar>::hat(omega1) * upsilon2 +
  520. SO3<Scalar>::hat(upsilon1) * omega2 +
  521. sigma1 * upsilon2 - sigma2 * upsilon1;
  522. res.template segment<3>(3) = omega1.cross(omega2);
  523. res[6] = Scalar(0);
  524. return res;
  525. }
  526. /// Draw uniform sample from Sim(3) manifold.
  527. ///
  528. /// Translations are drawn component-wise from the range [-1, 1].
  529. /// The scale factor is drawn uniformly in log2-space from [-1, 1],
  530. /// hence the scale is in [0.5, 2].
  531. ///
  532. template <class UniformRandomBitGenerator>
  533. static Sim3 sampleUniform(UniformRandomBitGenerator& generator) {
  534. std::uniform_real_distribution<Scalar> uniform(Scalar(-1), Scalar(1));
  535. return Sim3(RxSO3<Scalar>::sampleUniform(generator),
  536. Vector3<Scalar>(uniform(generator), uniform(generator),
  537. uniform(generator)));
  538. }
  539. /// vee-operator
  540. ///
  541. /// It takes the 4x4-matrix representation ``Omega`` and maps it to the
  542. /// corresponding 7-vector representation of Lie algebra.
  543. ///
  544. /// This is the inverse of the hat()-operator, see above.
  545. ///
  546. /// Precondition: ``Omega`` must have the following structure:
  547. ///
  548. /// | g -f e a |
  549. /// | f g -d b |
  550. /// | -e d g c |
  551. /// | 0 0 0 0 |
  552. ///
  553. SOPHUS_FUNC static Tangent vee(Transformation const& Omega) {
  554. Tangent upsilon_omega_sigma;
  555. upsilon_omega_sigma.template head<3>() = Omega.col(3).template head<3>();
  556. upsilon_omega_sigma.template tail<4>() =
  557. RxSO3<Scalar>::vee(Omega.template topLeftCorner<3, 3>());
  558. return upsilon_omega_sigma;
  559. }
  560. protected:
  561. RxSo3Member rxso3_;
  562. TranslationMember translation_;
  563. };
  564. template <class Scalar, int Options>
  565. Sim3<Scalar, Options>::Sim3() : translation_(TranslationMember::Zero()) {
  566. static_assert(std::is_standard_layout<Sim3>::value,
  567. "Assume standard layout for the use of offsetof check below.");
  568. static_assert(
  569. offsetof(Sim3, rxso3_) + sizeof(Scalar) * RxSO3<Scalar>::num_parameters ==
  570. offsetof(Sim3, translation_),
  571. "This class assumes packed storage and hence will only work "
  572. "correctly depending on the compiler (options) - in "
  573. "particular when using [this->data(), this-data() + "
  574. "num_parameters] to access the raw data in a contiguous fashion.");
  575. }
  576. } // namespace Sophus
  577. namespace Eigen {
  578. /// Specialization of Eigen::Map for ``Sim3``; derived from Sim3Base.
  579. ///
  580. /// Allows us to wrap Sim3 objects around POD array.
  581. template <class Scalar_, int Options>
  582. class Map<Sophus::Sim3<Scalar_>, Options>
  583. : public Sophus::Sim3Base<Map<Sophus::Sim3<Scalar_>, Options>> {
  584. public:
  585. using Base = Sophus::Sim3Base<Map<Sophus::Sim3<Scalar_>, Options>>;
  586. using Scalar = Scalar_;
  587. using Transformation = typename Base::Transformation;
  588. using Point = typename Base::Point;
  589. using HomogeneousPoint = typename Base::HomogeneousPoint;
  590. using Tangent = typename Base::Tangent;
  591. using Adjoint = typename Base::Adjoint;
  592. using Base::operator=;
  593. using Base::operator*=;
  594. using Base::operator*;
  595. SOPHUS_FUNC Map(Scalar* coeffs)
  596. : rxso3_(coeffs),
  597. translation_(coeffs + Sophus::RxSO3<Scalar>::num_parameters) {}
  598. /// Mutator of RxSO3
  599. ///
  600. SOPHUS_FUNC Map<Sophus::RxSO3<Scalar>, Options>& rxso3() { return rxso3_; }
  601. /// Accessor of RxSO3
  602. ///
  603. SOPHUS_FUNC Map<Sophus::RxSO3<Scalar>, Options> const& rxso3() const {
  604. return rxso3_;
  605. }
  606. /// Mutator of translation vector
  607. ///
  608. SOPHUS_FUNC Map<Sophus::Vector3<Scalar>, Options>& translation() {
  609. return translation_;
  610. }
  611. /// Accessor of translation vector
  612. SOPHUS_FUNC Map<Sophus::Vector3<Scalar>, Options> const& translation() const {
  613. return translation_;
  614. }
  615. protected:
  616. Map<Sophus::RxSO3<Scalar>, Options> rxso3_;
  617. Map<Sophus::Vector3<Scalar>, Options> translation_;
  618. };
  619. /// Specialization of Eigen::Map for ``Sim3 const``; derived from Sim3Base.
  620. ///
  621. /// Allows us to wrap RxSO3 objects around POD array.
  622. template <class Scalar_, int Options>
  623. class Map<Sophus::Sim3<Scalar_> const, Options>
  624. : public Sophus::Sim3Base<Map<Sophus::Sim3<Scalar_> const, Options>> {
  625. using Base = Sophus::Sim3Base<Map<Sophus::Sim3<Scalar_> const, Options>>;
  626. public:
  627. using Scalar = Scalar_;
  628. using Transformation = typename Base::Transformation;
  629. using Point = typename Base::Point;
  630. using HomogeneousPoint = typename Base::HomogeneousPoint;
  631. using Tangent = typename Base::Tangent;
  632. using Adjoint = typename Base::Adjoint;
  633. using Base::operator*=;
  634. using Base::operator*;
  635. SOPHUS_FUNC Map(Scalar const* coeffs)
  636. : rxso3_(coeffs),
  637. translation_(coeffs + Sophus::RxSO3<Scalar>::num_parameters) {}
  638. /// Accessor of RxSO3
  639. ///
  640. SOPHUS_FUNC Map<Sophus::RxSO3<Scalar> const, Options> const& rxso3() const {
  641. return rxso3_;
  642. }
  643. /// Accessor of translation vector
  644. ///
  645. SOPHUS_FUNC Map<Sophus::Vector3<Scalar> const, Options> const& translation()
  646. const {
  647. return translation_;
  648. }
  649. protected:
  650. Map<Sophus::RxSO3<Scalar> const, Options> const rxso3_;
  651. Map<Sophus::Vector3<Scalar> const, Options> const translation_;
  652. };
  653. } // namespace Eigen
  654. #endif