sim3.hpp 25 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745
  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 operator.
  170. ///
  171. SOPHUS_FUNC Sim3Base& operator=(Sim3Base const& other) = default;
  172. /// Assignment-like operator from OtherDerived.
  173. ///
  174. template <class OtherDerived>
  175. SOPHUS_FUNC Sim3Base<Derived>& operator=(
  176. Sim3Base<OtherDerived> const& other) {
  177. rxso3() = other.rxso3();
  178. translation() = other.translation();
  179. return *this;
  180. }
  181. /// Group multiplication, which is rotation plus scaling concatenation.
  182. ///
  183. /// Note: That scaling is calculated with saturation. See RxSO3 for
  184. /// details.
  185. ///
  186. template <typename OtherDerived>
  187. SOPHUS_FUNC Sim3Product<OtherDerived> operator*(
  188. Sim3Base<OtherDerived> const& other) const {
  189. return Sim3Product<OtherDerived>(
  190. rxso3() * other.rxso3(), translation() + rxso3() * other.translation());
  191. }
  192. /// Group action on 3-points.
  193. ///
  194. /// This function rotates, scales and translates a three dimensional point
  195. /// ``p`` by the Sim(3) element ``(bar_sR_foo, t_bar)`` (= similarity
  196. /// transformation):
  197. ///
  198. /// ``p_bar = bar_sR_foo * p_foo + t_bar``.
  199. ///
  200. template <typename PointDerived,
  201. typename = typename std::enable_if<
  202. IsFixedSizeVector<PointDerived, 3>::value>::type>
  203. SOPHUS_FUNC PointProduct<PointDerived> operator*(
  204. Eigen::MatrixBase<PointDerived> const& p) const {
  205. return rxso3() * p + translation();
  206. }
  207. /// Group action on homogeneous 3-points. See above for more details.
  208. ///
  209. template <typename HPointDerived,
  210. typename = typename std::enable_if<
  211. IsFixedSizeVector<HPointDerived, 4>::value>::type>
  212. SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> operator*(
  213. Eigen::MatrixBase<HPointDerived> const& p) const {
  214. const PointProduct<HPointDerived> tp =
  215. rxso3() * p.template head<3>() + p(3) * translation();
  216. return HomogeneousPointProduct<HPointDerived>(tp(0), tp(1), tp(2), p(3));
  217. }
  218. /// Group action on lines.
  219. ///
  220. /// This function rotates, scales and translates a parametrized line
  221. /// ``l(t) = o + t * d`` by the Sim(3) element:
  222. ///
  223. /// Origin ``o`` is rotated, scaled and translated
  224. /// Direction ``d`` is rotated
  225. ///
  226. SOPHUS_FUNC Line operator*(Line const& l) const {
  227. Line rotatedLine = rxso3() * l;
  228. return Line(rotatedLine.origin() + translation(), rotatedLine.direction());
  229. }
  230. /// In-place group multiplication. This method is only valid if the return
  231. /// type of the multiplication is compatible with this SO3's Scalar type.
  232. ///
  233. template <typename OtherDerived,
  234. typename = typename std::enable_if<
  235. std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
  236. SOPHUS_FUNC Sim3Base<Derived>& operator*=(
  237. Sim3Base<OtherDerived> const& other) {
  238. *static_cast<Derived*>(this) = *this * other;
  239. return *this;
  240. }
  241. /// Returns internal parameters of Sim(3).
  242. ///
  243. /// It returns (q.imag[0], q.imag[1], q.imag[2], q.real, t[0], t[1], t[2]),
  244. /// with q being the quaternion, t the translation 3-vector.
  245. ///
  246. SOPHUS_FUNC Sophus::Vector<Scalar, num_parameters> params() const {
  247. Sophus::Vector<Scalar, num_parameters> p;
  248. p << rxso3().params(), translation();
  249. return p;
  250. }
  251. /// Setter of non-zero quaternion.
  252. ///
  253. /// Precondition: ``quat`` must not be close to zero.
  254. ///
  255. SOPHUS_FUNC void setQuaternion(Eigen::Quaternion<Scalar> const& quat) {
  256. rxso3().setQuaternion(quat);
  257. }
  258. /// Accessor of quaternion.
  259. ///
  260. SOPHUS_FUNC QuaternionType const& quaternion() const {
  261. return rxso3().quaternion();
  262. }
  263. /// Returns Rotation matrix
  264. ///
  265. SOPHUS_FUNC Matrix3<Scalar> rotationMatrix() const {
  266. return rxso3().rotationMatrix();
  267. }
  268. /// Mutator of SO3 group.
  269. ///
  270. SOPHUS_FUNC RxSO3Type& rxso3() {
  271. return static_cast<Derived*>(this)->rxso3();
  272. }
  273. /// Accessor of SO3 group.
  274. ///
  275. SOPHUS_FUNC RxSO3Type const& rxso3() const {
  276. return static_cast<Derived const*>(this)->rxso3();
  277. }
  278. /// Returns scale.
  279. ///
  280. SOPHUS_FUNC Scalar scale() const { return rxso3().scale(); }
  281. /// Setter of quaternion using rotation matrix ``R``, leaves scale as is.
  282. ///
  283. SOPHUS_FUNC void setRotationMatrix(Matrix3<Scalar>& R) {
  284. rxso3().setRotationMatrix(R);
  285. }
  286. /// Sets scale and leaves rotation as is.
  287. ///
  288. /// Note: This function as a significant computational cost, since it has to
  289. /// call the square root twice.
  290. ///
  291. SOPHUS_FUNC void setScale(Scalar const& scale) { rxso3().setScale(scale); }
  292. /// Setter of quaternion using scaled rotation matrix ``sR``.
  293. ///
  294. /// Precondition: The 3x3 matrix must be "scaled orthogonal"
  295. /// and have a positive determinant.
  296. ///
  297. SOPHUS_FUNC void setScaledRotationMatrix(Matrix3<Scalar> const& sR) {
  298. rxso3().setScaledRotationMatrix(sR);
  299. }
  300. /// Mutator of translation vector
  301. ///
  302. SOPHUS_FUNC TranslationType& translation() {
  303. return static_cast<Derived*>(this)->translation();
  304. }
  305. /// Accessor of translation vector
  306. ///
  307. SOPHUS_FUNC TranslationType const& translation() const {
  308. return static_cast<Derived const*>(this)->translation();
  309. }
  310. };
  311. /// Sim3 using default storage; derived from Sim3Base.
  312. template <class Scalar_, int Options>
  313. class Sim3 : public Sim3Base<Sim3<Scalar_, Options>> {
  314. public:
  315. using Base = Sim3Base<Sim3<Scalar_, Options>>;
  316. using Scalar = Scalar_;
  317. using Transformation = typename Base::Transformation;
  318. using Point = typename Base::Point;
  319. using HomogeneousPoint = typename Base::HomogeneousPoint;
  320. using Tangent = typename Base::Tangent;
  321. using Adjoint = typename Base::Adjoint;
  322. using RxSo3Member = RxSO3<Scalar, Options>;
  323. using TranslationMember = Vector3<Scalar, Options>;
  324. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  325. /// Default constructor initializes similarity transform to the identity.
  326. ///
  327. SOPHUS_FUNC Sim3();
  328. /// Copy constructor
  329. ///
  330. SOPHUS_FUNC Sim3(Sim3 const& other) = default;
  331. /// Copy-like constructor from OtherDerived.
  332. ///
  333. template <class OtherDerived>
  334. SOPHUS_FUNC Sim3(Sim3Base<OtherDerived> const& other)
  335. : rxso3_(other.rxso3()), translation_(other.translation()) {
  336. static_assert(std::is_same<typename OtherDerived::Scalar, Scalar>::value,
  337. "must be same Scalar type");
  338. }
  339. /// Constructor from RxSO3 and translation vector
  340. ///
  341. template <class OtherDerived, class D>
  342. SOPHUS_FUNC Sim3(RxSO3Base<OtherDerived> const& rxso3,
  343. Eigen::MatrixBase<D> const& translation)
  344. : rxso3_(rxso3), translation_(translation) {
  345. static_assert(std::is_same<typename OtherDerived::Scalar, Scalar>::value,
  346. "must be same Scalar type");
  347. static_assert(std::is_same<typename D::Scalar, Scalar>::value,
  348. "must be same Scalar type");
  349. }
  350. /// Constructor from quaternion and translation vector.
  351. ///
  352. /// Precondition: quaternion must not be close to zero.
  353. ///
  354. template <class D1, class D2>
  355. SOPHUS_FUNC Sim3(Eigen::QuaternionBase<D1> const& quaternion,
  356. Eigen::MatrixBase<D2> const& translation)
  357. : rxso3_(quaternion), translation_(translation) {
  358. static_assert(std::is_same<typename D1::Scalar, Scalar>::value,
  359. "must be same Scalar type");
  360. static_assert(std::is_same<typename D2::Scalar, Scalar>::value,
  361. "must be same Scalar type");
  362. }
  363. /// Constructor from 4x4 matrix
  364. ///
  365. /// Precondition: Top-left 3x3 matrix needs to be "scaled-orthogonal" with
  366. /// positive determinant. The last row must be ``(0, 0, 0, 1)``.
  367. ///
  368. SOPHUS_FUNC explicit Sim3(Matrix<Scalar, 4, 4> const& T)
  369. : rxso3_(T.template topLeftCorner<3, 3>()),
  370. translation_(T.template block<3, 1>(0, 3)) {}
  371. /// This provides unsafe read/write access to internal data. Sim(3) is
  372. /// represented by an Eigen::Quaternion (four parameters) and a 3-vector. When
  373. /// using direct write access, the user needs to take care of that the
  374. /// quaternion is not set close to zero.
  375. ///
  376. SOPHUS_FUNC Scalar* data() {
  377. // rxso3_ and translation_ are laid out sequentially with no padding
  378. return rxso3_.data();
  379. }
  380. /// Const version of data() above.
  381. ///
  382. SOPHUS_FUNC Scalar const* data() const {
  383. // rxso3_ and translation_ are laid out sequentially with no padding
  384. return rxso3_.data();
  385. }
  386. /// Accessor of RxSO3
  387. ///
  388. SOPHUS_FUNC RxSo3Member& rxso3() { return rxso3_; }
  389. /// Mutator of RxSO3
  390. ///
  391. SOPHUS_FUNC RxSo3Member const& rxso3() const { return rxso3_; }
  392. /// Mutator of translation vector
  393. ///
  394. SOPHUS_FUNC TranslationMember& translation() { return translation_; }
  395. /// Accessor of translation vector
  396. ///
  397. SOPHUS_FUNC TranslationMember const& translation() const {
  398. return translation_;
  399. }
  400. /// Returns derivative of exp(x).matrix() wrt. ``x_i at x=0``.
  401. ///
  402. SOPHUS_FUNC static Transformation Dxi_exp_x_matrix_at_0(int i) {
  403. return generator(i);
  404. }
  405. /// Group exponential
  406. ///
  407. /// This functions takes in an element of tangent space and returns the
  408. /// corresponding element of the group Sim(3).
  409. ///
  410. /// The first three components of ``a`` represent the translational part
  411. /// ``upsilon`` in the tangent space of Sim(3), the following three components
  412. /// of ``a`` represents the rotation vector ``omega`` and the final component
  413. /// represents the logarithm of the scaling factor ``sigma``.
  414. /// To be more specific, this function computes ``expmat(hat(a))`` with
  415. /// ``expmat(.)`` being the matrix exponential and ``hat(.)`` the hat-operator
  416. /// of Sim(3), see below.
  417. ///
  418. SOPHUS_FUNC static Sim3<Scalar> exp(Tangent const& a) {
  419. // For the derivation of the exponential map of Sim(3) see
  420. // H. Strasdat, "Local Accuracy and Global Consistency for Efficient Visual
  421. // SLAM", PhD thesis, 2012.
  422. // http:///hauke.strasdat.net/files/strasdat_thesis_2012.pdf (A.5, pp. 186)
  423. Vector3<Scalar> const upsilon = a.segment(0, 3);
  424. Vector3<Scalar> const omega = a.segment(3, 3);
  425. Scalar const sigma = a[6];
  426. Scalar theta;
  427. RxSO3<Scalar> rxso3 =
  428. RxSO3<Scalar>::expAndTheta(a.template tail<4>(), &theta);
  429. Matrix3<Scalar> const Omega = SO3<Scalar>::hat(omega);
  430. Matrix3<Scalar> const W = details::calcW<Scalar, 3>(Omega, theta, sigma);
  431. return Sim3<Scalar>(rxso3, W * upsilon);
  432. }
  433. /// Returns the ith infinitesimal generators of Sim(3).
  434. ///
  435. /// The infinitesimal generators of Sim(3) are:
  436. ///
  437. /// ```
  438. /// | 0 0 0 1 |
  439. /// G_0 = | 0 0 0 0 |
  440. /// | 0 0 0 0 |
  441. /// | 0 0 0 0 |
  442. ///
  443. /// | 0 0 0 0 |
  444. /// G_1 = | 0 0 0 1 |
  445. /// | 0 0 0 0 |
  446. /// | 0 0 0 0 |
  447. ///
  448. /// | 0 0 0 0 |
  449. /// G_2 = | 0 0 0 0 |
  450. /// | 0 0 0 1 |
  451. /// | 0 0 0 0 |
  452. ///
  453. /// | 0 0 0 0 |
  454. /// G_3 = | 0 0 -1 0 |
  455. /// | 0 1 0 0 |
  456. /// | 0 0 0 0 |
  457. ///
  458. /// | 0 0 1 0 |
  459. /// G_4 = | 0 0 0 0 |
  460. /// | -1 0 0 0 |
  461. /// | 0 0 0 0 |
  462. ///
  463. /// | 0 -1 0 0 |
  464. /// G_5 = | 1 0 0 0 |
  465. /// | 0 0 0 0 |
  466. /// | 0 0 0 0 |
  467. ///
  468. /// | 1 0 0 0 |
  469. /// G_6 = | 0 1 0 0 |
  470. /// | 0 0 1 0 |
  471. /// | 0 0 0 0 |
  472. /// ```
  473. ///
  474. /// Precondition: ``i`` must be in [0, 6].
  475. ///
  476. SOPHUS_FUNC static Transformation generator(int i) {
  477. SOPHUS_ENSURE(i >= 0 || i <= 6, "i should be in range [0,6].");
  478. Tangent e;
  479. e.setZero();
  480. e[i] = Scalar(1);
  481. return hat(e);
  482. }
  483. /// hat-operator
  484. ///
  485. /// It takes in the 7-vector representation and returns the corresponding
  486. /// matrix representation of Lie algebra element.
  487. ///
  488. /// Formally, the hat()-operator of Sim(3) is defined as
  489. ///
  490. /// ``hat(.): R^7 -> R^{4x4}, hat(a) = sum_i a_i * G_i`` (for i=0,...,6)
  491. ///
  492. /// with ``G_i`` being the ith infinitesimal generator of Sim(3).
  493. ///
  494. /// The corresponding inverse is the vee()-operator, see below.
  495. ///
  496. SOPHUS_FUNC static Transformation hat(Tangent const& a) {
  497. Transformation Omega;
  498. Omega.template topLeftCorner<3, 3>() =
  499. RxSO3<Scalar>::hat(a.template tail<4>());
  500. Omega.col(3).template head<3>() = a.template head<3>();
  501. Omega.row(3).setZero();
  502. return Omega;
  503. }
  504. /// Lie bracket
  505. ///
  506. /// It computes the Lie bracket of Sim(3). To be more specific, it computes
  507. ///
  508. /// ``[omega_1, omega_2]_sim3 := vee([hat(omega_1), hat(omega_2)])``
  509. ///
  510. /// with ``[A,B] := AB-BA`` being the matrix commutator, ``hat(.)`` the
  511. /// hat()-operator and ``vee(.)`` the vee()-operator of Sim(3).
  512. ///
  513. SOPHUS_FUNC static Tangent lieBracket(Tangent const& a, Tangent const& b) {
  514. Vector3<Scalar> const upsilon1 = a.template head<3>();
  515. Vector3<Scalar> const upsilon2 = b.template head<3>();
  516. Vector3<Scalar> const omega1 = a.template segment<3>(3);
  517. Vector3<Scalar> const omega2 = b.template segment<3>(3);
  518. Scalar sigma1 = a[6];
  519. Scalar sigma2 = b[6];
  520. Tangent res;
  521. res.template head<3>() = SO3<Scalar>::hat(omega1) * upsilon2 +
  522. SO3<Scalar>::hat(upsilon1) * omega2 +
  523. sigma1 * upsilon2 - sigma2 * upsilon1;
  524. res.template segment<3>(3) = omega1.cross(omega2);
  525. res[6] = Scalar(0);
  526. return res;
  527. }
  528. /// Draw uniform sample from Sim(3) manifold.
  529. ///
  530. /// Translations are drawn component-wise from the range [-1, 1].
  531. /// The scale factor is drawn uniformly in log2-space from [-1, 1],
  532. /// hence the scale is in [0.5, 2].
  533. ///
  534. template <class UniformRandomBitGenerator>
  535. static Sim3 sampleUniform(UniformRandomBitGenerator& generator) {
  536. std::uniform_real_distribution<Scalar> uniform(Scalar(-1), Scalar(1));
  537. return Sim3(RxSO3<Scalar>::sampleUniform(generator),
  538. Vector3<Scalar>(uniform(generator), uniform(generator),
  539. uniform(generator)));
  540. }
  541. /// vee-operator
  542. ///
  543. /// It takes the 4x4-matrix representation ``Omega`` and maps it to the
  544. /// corresponding 7-vector representation of Lie algebra.
  545. ///
  546. /// This is the inverse of the hat()-operator, see above.
  547. ///
  548. /// Precondition: ``Omega`` must have the following structure:
  549. ///
  550. /// | g -f e a |
  551. /// | f g -d b |
  552. /// | -e d g c |
  553. /// | 0 0 0 0 |
  554. ///
  555. SOPHUS_FUNC static Tangent vee(Transformation const& Omega) {
  556. Tangent upsilon_omega_sigma;
  557. upsilon_omega_sigma.template head<3>() = Omega.col(3).template head<3>();
  558. upsilon_omega_sigma.template tail<4>() =
  559. RxSO3<Scalar>::vee(Omega.template topLeftCorner<3, 3>());
  560. return upsilon_omega_sigma;
  561. }
  562. protected:
  563. RxSo3Member rxso3_;
  564. TranslationMember translation_;
  565. };
  566. template <class Scalar, int Options>
  567. Sim3<Scalar, Options>::Sim3() : translation_(TranslationMember::Zero()) {
  568. static_assert(std::is_standard_layout<Sim3>::value,
  569. "Assume standard layout for the use of offsetof check below.");
  570. static_assert(
  571. offsetof(Sim3, rxso3_) + sizeof(Scalar) * RxSO3<Scalar>::num_parameters ==
  572. offsetof(Sim3, translation_),
  573. "This class assumes packed storage and hence will only work "
  574. "correctly depending on the compiler (options) - in "
  575. "particular when using [this->data(), this-data() + "
  576. "num_parameters] to access the raw data in a contiguous fashion.");
  577. }
  578. } // namespace Sophus
  579. namespace Eigen {
  580. /// Specialization of Eigen::Map for ``Sim3``; derived from Sim3Base.
  581. ///
  582. /// Allows us to wrap Sim3 objects around POD array.
  583. template <class Scalar_, int Options>
  584. class Map<Sophus::Sim3<Scalar_>, Options>
  585. : public Sophus::Sim3Base<Map<Sophus::Sim3<Scalar_>, Options>> {
  586. public:
  587. using Base = Sophus::Sim3Base<Map<Sophus::Sim3<Scalar_>, Options>>;
  588. using Scalar = Scalar_;
  589. using Transformation = typename Base::Transformation;
  590. using Point = typename Base::Point;
  591. using HomogeneousPoint = typename Base::HomogeneousPoint;
  592. using Tangent = typename Base::Tangent;
  593. using Adjoint = typename Base::Adjoint;
  594. // LCOV_EXCL_START
  595. SOPHUS_INHERIT_ASSIGNMENT_OPERATORS(Map);
  596. // LCOV_EXCL_STOP
  597. using Base::operator*=;
  598. using Base::operator*;
  599. SOPHUS_FUNC Map(Scalar* coeffs)
  600. : rxso3_(coeffs),
  601. translation_(coeffs + Sophus::RxSO3<Scalar>::num_parameters) {}
  602. /// Mutator of RxSO3
  603. ///
  604. SOPHUS_FUNC Map<Sophus::RxSO3<Scalar>, Options>& rxso3() { return rxso3_; }
  605. /// Accessor of RxSO3
  606. ///
  607. SOPHUS_FUNC Map<Sophus::RxSO3<Scalar>, Options> const& rxso3() const {
  608. return rxso3_;
  609. }
  610. /// Mutator of translation vector
  611. ///
  612. SOPHUS_FUNC Map<Sophus::Vector3<Scalar>, Options>& translation() {
  613. return translation_;
  614. }
  615. /// Accessor of translation vector
  616. SOPHUS_FUNC Map<Sophus::Vector3<Scalar>, Options> const& translation() const {
  617. return translation_;
  618. }
  619. protected:
  620. Map<Sophus::RxSO3<Scalar>, Options> rxso3_;
  621. Map<Sophus::Vector3<Scalar>, Options> translation_;
  622. };
  623. /// Specialization of Eigen::Map for ``Sim3 const``; derived from Sim3Base.
  624. ///
  625. /// Allows us to wrap RxSO3 objects around POD array.
  626. template <class Scalar_, int Options>
  627. class Map<Sophus::Sim3<Scalar_> const, Options>
  628. : public Sophus::Sim3Base<Map<Sophus::Sim3<Scalar_> const, Options>> {
  629. using Base = Sophus::Sim3Base<Map<Sophus::Sim3<Scalar_> const, Options>>;
  630. public:
  631. using Scalar = Scalar_;
  632. using Transformation = typename Base::Transformation;
  633. using Point = typename Base::Point;
  634. using HomogeneousPoint = typename Base::HomogeneousPoint;
  635. using Tangent = typename Base::Tangent;
  636. using Adjoint = typename Base::Adjoint;
  637. using Base::operator*=;
  638. using Base::operator*;
  639. SOPHUS_FUNC Map(Scalar const* coeffs)
  640. : rxso3_(coeffs),
  641. translation_(coeffs + Sophus::RxSO3<Scalar>::num_parameters) {}
  642. /// Accessor of RxSO3
  643. ///
  644. SOPHUS_FUNC Map<Sophus::RxSO3<Scalar> const, Options> const& rxso3() const {
  645. return rxso3_;
  646. }
  647. /// Accessor of translation vector
  648. ///
  649. SOPHUS_FUNC Map<Sophus::Vector3<Scalar> const, Options> const& translation()
  650. const {
  651. return translation_;
  652. }
  653. protected:
  654. Map<Sophus::RxSO3<Scalar> const, Options> const rxso3_;
  655. Map<Sophus::Vector3<Scalar> const, Options> const translation_;
  656. };
  657. } // namespace Eigen
  658. #endif