sim2.hpp 24 KB

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