se2.hpp 26 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840
  1. /// @file
  2. /// Special Euclidean group SE(2) - rotation and translation in 2d.
  3. #ifndef SOPHUS_SE2_HPP
  4. #define SOPHUS_SE2_HPP
  5. #include "so2.hpp"
  6. namespace Sophus {
  7. template <class Scalar_, int Options = 0>
  8. class SE2;
  9. using SE2d = SE2<double>;
  10. using SE2f = SE2<float>;
  11. } // namespace Sophus
  12. namespace Eigen {
  13. namespace internal {
  14. template <class Scalar_, int Options>
  15. struct traits<Sophus::SE2<Scalar_, Options>> {
  16. using Scalar = Scalar_;
  17. using TranslationType = Sophus::Vector2<Scalar, Options>;
  18. using SO2Type = Sophus::SO2<Scalar, Options>;
  19. };
  20. template <class Scalar_, int Options>
  21. struct traits<Map<Sophus::SE2<Scalar_>, Options>>
  22. : traits<Sophus::SE2<Scalar_, Options>> {
  23. using Scalar = Scalar_;
  24. using TranslationType = Map<Sophus::Vector2<Scalar>, Options>;
  25. using SO2Type = Map<Sophus::SO2<Scalar>, Options>;
  26. };
  27. template <class Scalar_, int Options>
  28. struct traits<Map<Sophus::SE2<Scalar_> const, Options>>
  29. : traits<Sophus::SE2<Scalar_, Options> const> {
  30. using Scalar = Scalar_;
  31. using TranslationType = Map<Sophus::Vector2<Scalar> const, Options>;
  32. using SO2Type = Map<Sophus::SO2<Scalar> const, Options>;
  33. };
  34. } // namespace internal
  35. } // namespace Eigen
  36. namespace Sophus {
  37. /// SE2 base type - implements SE2 class but is storage agnostic.
  38. ///
  39. /// SE(2) is the group of rotations and translation in 2d. It is the
  40. /// semi-direct product of SO(2) and the 2d Euclidean vector space. The class
  41. /// is represented using a composition of SO2Group for rotation and a 2-vector
  42. /// for translation.
  43. ///
  44. /// SE(2) is neither compact, nor a commutative group.
  45. ///
  46. /// See SO2Group for more details of the rotation representation in 2d.
  47. ///
  48. template <class Derived>
  49. class SE2Base {
  50. public:
  51. using Scalar = typename Eigen::internal::traits<Derived>::Scalar;
  52. using TranslationType =
  53. typename Eigen::internal::traits<Derived>::TranslationType;
  54. using SO2Type = typename Eigen::internal::traits<Derived>::SO2Type;
  55. /// Degrees of freedom of manifold, number of dimensions in tangent space
  56. /// (two for translation, three for rotation).
  57. static int constexpr DoF = 3;
  58. /// Number of internal parameters used (tuple for complex, two for
  59. /// translation).
  60. static int constexpr num_parameters = 4;
  61. /// Group transformations are 3x3 matrices.
  62. static int constexpr N = 3;
  63. using Transformation = Matrix<Scalar, N, N>;
  64. using Point = Vector2<Scalar>;
  65. using HomogeneousPoint = Vector3<Scalar>;
  66. using Line = ParametrizedLine2<Scalar>;
  67. using Tangent = Vector<Scalar, DoF>;
  68. using Adjoint = Matrix<Scalar, DoF, DoF>;
  69. /// For binary operations the return type is determined with the
  70. /// ScalarBinaryOpTraits feature of Eigen. This allows mixing concrete and Map
  71. /// types, as well as other compatible scalar types such as Ceres::Jet and
  72. /// double scalars with SE2 operations.
  73. template <typename OtherDerived>
  74. using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<
  75. Scalar, typename OtherDerived::Scalar>::ReturnType;
  76. template <typename OtherDerived>
  77. using SE2Product = SE2<ReturnScalar<OtherDerived>>;
  78. template <typename PointDerived>
  79. using PointProduct = Vector2<ReturnScalar<PointDerived>>;
  80. template <typename HPointDerived>
  81. using HomogeneousPointProduct = Vector3<ReturnScalar<HPointDerived>>;
  82. /// Adjoint transformation
  83. ///
  84. /// This function return the adjoint transformation ``Ad`` of the group
  85. /// element ``A`` such that for all ``x`` it holds that
  86. /// ``hat(Ad_A * x) = A * hat(x) A^{-1}``. See hat-operator below.
  87. ///
  88. SOPHUS_FUNC Adjoint Adj() const {
  89. Matrix<Scalar, 2, 2> const& R = so2().matrix();
  90. Transformation res;
  91. res.setIdentity();
  92. res.template topLeftCorner<2, 2>() = R;
  93. res(0, 2) = translation()[1];
  94. res(1, 2) = -translation()[0];
  95. return res;
  96. }
  97. /// Returns copy of instance casted to NewScalarType.
  98. ///
  99. template <class NewScalarType>
  100. SOPHUS_FUNC SE2<NewScalarType> cast() const {
  101. return SE2<NewScalarType>(so2().template cast<NewScalarType>(),
  102. translation().template cast<NewScalarType>());
  103. }
  104. /// Returns derivative of this * exp(x) wrt x at x=0.
  105. ///
  106. SOPHUS_FUNC Matrix<Scalar, num_parameters, DoF> Dx_this_mul_exp_x_at_0()
  107. const {
  108. Matrix<Scalar, num_parameters, DoF> J;
  109. Sophus::Vector2<Scalar> const c = unit_complex();
  110. Scalar o(0);
  111. J(0, 0) = o;
  112. J(0, 1) = o;
  113. J(0, 2) = -c[1];
  114. J(1, 0) = o;
  115. J(1, 1) = o;
  116. J(1, 2) = c[0];
  117. J(2, 0) = c[0];
  118. J(2, 1) = -c[1];
  119. J(2, 2) = o;
  120. J(3, 0) = c[1];
  121. J(3, 1) = c[0];
  122. J(3, 2) = o;
  123. return J;
  124. }
  125. /// Returns group inverse.
  126. ///
  127. SOPHUS_FUNC SE2<Scalar> inverse() const {
  128. SO2<Scalar> const invR = so2().inverse();
  129. return SE2<Scalar>(invR, invR * (translation() * Scalar(-1)));
  130. }
  131. /// Logarithmic map
  132. ///
  133. /// Computes the logarithm, the inverse of the group exponential which maps
  134. /// element of the group (rigid body transformations) to elements of the
  135. /// tangent space (twist).
  136. ///
  137. /// To be specific, this function computes ``vee(logmat(.))`` with
  138. /// ``logmat(.)`` being the matrix logarithm and ``vee(.)`` the vee-operator
  139. /// of SE(2).
  140. ///
  141. SOPHUS_FUNC Tangent log() const {
  142. using std::abs;
  143. Tangent upsilon_theta;
  144. Scalar theta = so2().log();
  145. upsilon_theta[2] = theta;
  146. Scalar halftheta = Scalar(0.5) * theta;
  147. Scalar halftheta_by_tan_of_halftheta;
  148. Vector2<Scalar> z = so2().unit_complex();
  149. Scalar real_minus_one = z.x() - Scalar(1.);
  150. if (abs(real_minus_one) < Constants<Scalar>::epsilon()) {
  151. halftheta_by_tan_of_halftheta =
  152. Scalar(1.) - Scalar(1. / 12) * theta * theta;
  153. } else {
  154. halftheta_by_tan_of_halftheta = -(halftheta * z.y()) / (real_minus_one);
  155. }
  156. Matrix<Scalar, 2, 2> V_inv;
  157. V_inv << halftheta_by_tan_of_halftheta, halftheta, -halftheta,
  158. halftheta_by_tan_of_halftheta;
  159. upsilon_theta.template head<2>() = V_inv * translation();
  160. return upsilon_theta;
  161. }
  162. /// Normalize SO2 element
  163. ///
  164. /// It re-normalizes the SO2 element.
  165. ///
  166. SOPHUS_FUNC void normalize() { so2().normalize(); }
  167. /// Returns 3x3 matrix representation of the instance.
  168. ///
  169. /// It has the following form:
  170. ///
  171. /// | R t |
  172. /// | o 1 |
  173. ///
  174. /// where ``R`` is a 2x2 rotation matrix, ``t`` a translation 2-vector and
  175. /// ``o`` a 2-column vector of zeros.
  176. ///
  177. SOPHUS_FUNC Transformation matrix() const {
  178. Transformation homogenious_matrix;
  179. homogenious_matrix.template topLeftCorner<2, 3>() = matrix2x3();
  180. homogenious_matrix.row(2) =
  181. Matrix<Scalar, 1, 3>(Scalar(0), Scalar(0), Scalar(1));
  182. return homogenious_matrix;
  183. }
  184. /// Returns the significant first two rows of the matrix above.
  185. ///
  186. SOPHUS_FUNC Matrix<Scalar, 2, 3> matrix2x3() const {
  187. Matrix<Scalar, 2, 3> matrix;
  188. matrix.template topLeftCorner<2, 2>() = rotationMatrix();
  189. matrix.col(2) = translation();
  190. return matrix;
  191. }
  192. /// Assignment operator.
  193. ///
  194. SOPHUS_FUNC SE2Base& operator=(SE2Base const& other) = default;
  195. /// Assignment-like operator from OtherDerived.
  196. ///
  197. template <class OtherDerived>
  198. SOPHUS_FUNC SE2Base<Derived>& operator=(SE2Base<OtherDerived> const& other) {
  199. so2() = other.so2();
  200. translation() = other.translation();
  201. return *this;
  202. }
  203. /// Group multiplication, which is rotation concatenation.
  204. ///
  205. template <typename OtherDerived>
  206. SOPHUS_FUNC SE2Product<OtherDerived> operator*(
  207. SE2Base<OtherDerived> const& other) const {
  208. return SE2Product<OtherDerived>(
  209. so2() * other.so2(), translation() + so2() * other.translation());
  210. }
  211. /// Group action on 2-points.
  212. ///
  213. /// This function rotates and translates a two dimensional point ``p`` by the
  214. /// SE(2) element ``bar_T_foo = (bar_R_foo, t_bar)`` (= rigid body
  215. /// transformation):
  216. ///
  217. /// ``p_bar = bar_R_foo * p_foo + t_bar``.
  218. ///
  219. template <typename PointDerived,
  220. typename = typename std::enable_if<
  221. IsFixedSizeVector<PointDerived, 2>::value>::type>
  222. SOPHUS_FUNC PointProduct<PointDerived> operator*(
  223. Eigen::MatrixBase<PointDerived> const& p) const {
  224. return so2() * p + translation();
  225. }
  226. /// Group action on homogeneous 2-points. See above for more details.
  227. ///
  228. template <typename HPointDerived,
  229. typename = typename std::enable_if<
  230. IsFixedSizeVector<HPointDerived, 3>::value>::type>
  231. SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> operator*(
  232. Eigen::MatrixBase<HPointDerived> const& p) const {
  233. const PointProduct<HPointDerived> tp =
  234. so2() * p.template head<2>() + p(2) * translation();
  235. return HomogeneousPointProduct<HPointDerived>(tp(0), tp(1), p(2));
  236. }
  237. /// Group action on lines.
  238. ///
  239. /// This function rotates and translates a parametrized line
  240. /// ``l(t) = o + t * d`` by the SE(2) element:
  241. ///
  242. /// Origin ``o`` is rotated and translated using SE(2) action
  243. /// Direction ``d`` is rotated using SO(2) action
  244. ///
  245. SOPHUS_FUNC Line operator*(Line const& l) const {
  246. return Line((*this) * l.origin(), so2() * l.direction());
  247. }
  248. /// In-place group multiplication. This method is only valid if the return
  249. /// type of the multiplication is compatible with this SO2's Scalar type.
  250. ///
  251. template <typename OtherDerived,
  252. typename = typename std::enable_if<
  253. std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
  254. SOPHUS_FUNC SE2Base<Derived>& operator*=(SE2Base<OtherDerived> const& other) {
  255. *static_cast<Derived*>(this) = *this * other;
  256. return *this;
  257. }
  258. /// Returns internal parameters of SE(2).
  259. ///
  260. /// It returns (c[0], c[1], t[0], t[1]),
  261. /// with c being the unit complex number, t the translation 3-vector.
  262. ///
  263. SOPHUS_FUNC Sophus::Vector<Scalar, num_parameters> params() const {
  264. Sophus::Vector<Scalar, num_parameters> p;
  265. p << so2().params(), translation();
  266. return p;
  267. }
  268. /// Returns rotation matrix.
  269. ///
  270. SOPHUS_FUNC Matrix<Scalar, 2, 2> rotationMatrix() const {
  271. return so2().matrix();
  272. }
  273. /// Takes in complex number, and normalizes it.
  274. ///
  275. /// Precondition: The complex number must not be close to zero.
  276. ///
  277. SOPHUS_FUNC void setComplex(Sophus::Vector2<Scalar> const& complex) {
  278. return so2().setComplex(complex);
  279. }
  280. /// Sets ``so3`` using ``rotation_matrix``.
  281. ///
  282. /// Precondition: ``R`` must be orthogonal and ``det(R)=1``.
  283. ///
  284. SOPHUS_FUNC void setRotationMatrix(Matrix<Scalar, 2, 2> const& R) {
  285. SOPHUS_ENSURE(isOrthogonal(R), "R is not orthogonal:\n %", R);
  286. SOPHUS_ENSURE(R.determinant() > Scalar(0), "det(R) is not positive: %",
  287. R.determinant());
  288. typename SO2Type::ComplexTemporaryType const complex(
  289. Scalar(0.5) * (R(0, 0) + R(1, 1)), Scalar(0.5) * (R(1, 0) - R(0, 1)));
  290. so2().setComplex(complex);
  291. }
  292. /// Mutator of SO3 group.
  293. ///
  294. SOPHUS_FUNC
  295. SO2Type& so2() { return static_cast<Derived*>(this)->so2(); }
  296. /// Accessor of SO3 group.
  297. ///
  298. SOPHUS_FUNC
  299. SO2Type const& so2() const {
  300. return static_cast<Derived const*>(this)->so2();
  301. }
  302. /// Mutator of translation vector.
  303. ///
  304. SOPHUS_FUNC
  305. TranslationType& translation() {
  306. return static_cast<Derived*>(this)->translation();
  307. }
  308. /// Accessor of translation vector
  309. ///
  310. SOPHUS_FUNC
  311. TranslationType const& translation() const {
  312. return static_cast<Derived const*>(this)->translation();
  313. }
  314. /// Accessor of unit complex number.
  315. ///
  316. SOPHUS_FUNC
  317. typename Eigen::internal::traits<Derived>::SO2Type::ComplexT const&
  318. unit_complex() const {
  319. return so2().unit_complex();
  320. }
  321. };
  322. /// SE2 using default storage; derived from SE2Base.
  323. template <class Scalar_, int Options>
  324. class SE2 : public SE2Base<SE2<Scalar_, Options>> {
  325. public:
  326. using Base = SE2Base<SE2<Scalar_, Options>>;
  327. static int constexpr DoF = Base::DoF;
  328. static int constexpr num_parameters = Base::num_parameters;
  329. using Scalar = Scalar_;
  330. using Transformation = typename Base::Transformation;
  331. using Point = typename Base::Point;
  332. using HomogeneousPoint = typename Base::HomogeneousPoint;
  333. using Tangent = typename Base::Tangent;
  334. using Adjoint = typename Base::Adjoint;
  335. using SO2Member = SO2<Scalar, Options>;
  336. using TranslationMember = Vector2<Scalar, Options>;
  337. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  338. /// Default constructor initializes rigid body motion to the identity.
  339. ///
  340. SOPHUS_FUNC SE2();
  341. /// Copy constructor
  342. ///
  343. SOPHUS_FUNC SE2(SE2 const& other) = default;
  344. /// Copy-like constructor from OtherDerived
  345. ///
  346. template <class OtherDerived>
  347. SOPHUS_FUNC SE2(SE2Base<OtherDerived> const& other)
  348. : so2_(other.so2()), translation_(other.translation()) {
  349. static_assert(std::is_same<typename OtherDerived::Scalar, Scalar>::value,
  350. "must be same Scalar type");
  351. }
  352. /// Constructor from SO3 and translation vector
  353. ///
  354. template <class OtherDerived, class D>
  355. SOPHUS_FUNC SE2(SO2Base<OtherDerived> const& so2,
  356. Eigen::MatrixBase<D> const& translation)
  357. : so2_(so2), translation_(translation) {
  358. static_assert(std::is_same<typename OtherDerived::Scalar, Scalar>::value,
  359. "must be same Scalar type");
  360. static_assert(std::is_same<typename D::Scalar, Scalar>::value,
  361. "must be same Scalar type");
  362. }
  363. /// Constructor from rotation matrix and translation vector
  364. ///
  365. /// Precondition: Rotation matrix needs to be orthogonal with determinant
  366. /// of 1.
  367. ///
  368. SOPHUS_FUNC
  369. SE2(typename SO2<Scalar>::Transformation const& rotation_matrix,
  370. Point const& translation)
  371. : so2_(rotation_matrix), translation_(translation) {}
  372. /// Constructor from rotation angle and translation vector.
  373. ///
  374. SOPHUS_FUNC SE2(Scalar const& theta, Point const& translation)
  375. : so2_(theta), translation_(translation) {}
  376. /// Constructor from complex number and translation vector
  377. ///
  378. /// Precondition: ``complex`` must not be close to zero.
  379. SOPHUS_FUNC SE2(Vector2<Scalar> const& complex, Point const& translation)
  380. : so2_(complex), translation_(translation) {}
  381. /// Constructor from 3x3 matrix
  382. ///
  383. /// Precondition: Rotation matrix needs to be orthogonal with determinant
  384. /// of 1. The last row must be ``(0, 0, 1)``.
  385. ///
  386. SOPHUS_FUNC explicit SE2(Transformation const& T)
  387. : so2_(T.template topLeftCorner<2, 2>().eval()),
  388. translation_(T.template block<2, 1>(0, 2)) {}
  389. /// This provides unsafe read/write access to internal data. SO(2) is
  390. /// represented by a complex number (two parameters). When using direct write
  391. /// access, the user needs to take care of that the complex number stays
  392. /// normalized.
  393. ///
  394. SOPHUS_FUNC Scalar* data() {
  395. // so2_ and translation_ are layed out sequentially with no padding
  396. return so2_.data();
  397. }
  398. /// Const version of data() above.
  399. ///
  400. SOPHUS_FUNC Scalar const* data() const {
  401. /// so2_ and translation_ are layed out sequentially with no padding
  402. return so2_.data();
  403. }
  404. /// Accessor of SO3
  405. ///
  406. SOPHUS_FUNC SO2Member& so2() { return so2_; }
  407. /// Mutator of SO3
  408. ///
  409. SOPHUS_FUNC SO2Member const& so2() const { return so2_; }
  410. /// Mutator of translation vector
  411. ///
  412. SOPHUS_FUNC TranslationMember& translation() { return translation_; }
  413. /// Accessor of translation vector
  414. ///
  415. SOPHUS_FUNC TranslationMember const& translation() const {
  416. return translation_;
  417. }
  418. /// Returns derivative of exp(x) wrt. x.
  419. ///
  420. SOPHUS_FUNC static Sophus::Matrix<Scalar, num_parameters, DoF> Dx_exp_x(
  421. Tangent const& upsilon_theta) {
  422. using std::abs;
  423. using std::cos;
  424. using std::pow;
  425. using std::sin;
  426. Sophus::Matrix<Scalar, num_parameters, DoF> J;
  427. Sophus::Vector<Scalar, 2> upsilon = upsilon_theta.template head<2>();
  428. Scalar theta = upsilon_theta[2];
  429. if (abs(theta) < Constants<Scalar>::epsilon()) {
  430. Scalar const o(0);
  431. Scalar const i(1);
  432. // clang-format off
  433. J << o, o, o, o, o, i, i, o, -Scalar(0.5) * upsilon[1], o, i,
  434. Scalar(0.5) * upsilon[0];
  435. // clang-format on
  436. return J;
  437. }
  438. Scalar const c0 = sin(theta);
  439. Scalar const c1 = cos(theta);
  440. Scalar const c2 = 1.0 / theta;
  441. Scalar const c3 = c0 * c2;
  442. Scalar const c4 = -c1 + Scalar(1);
  443. Scalar const c5 = c2 * c4;
  444. Scalar const c6 = c1 * c2;
  445. Scalar const c7 = pow(theta, -2);
  446. Scalar const c8 = c0 * c7;
  447. Scalar const c9 = c4 * c7;
  448. Scalar const o = Scalar(0);
  449. J(0, 0) = o;
  450. J(0, 1) = o;
  451. J(0, 2) = -c0;
  452. J(1, 0) = o;
  453. J(1, 1) = o;
  454. J(1, 2) = c1;
  455. J(2, 0) = c3;
  456. J(2, 1) = -c5;
  457. J(2, 2) =
  458. -c3 * upsilon[1] + c6 * upsilon[0] - c8 * upsilon[0] + c9 * upsilon[1];
  459. J(3, 0) = c5;
  460. J(3, 1) = c3;
  461. J(3, 2) =
  462. c3 * upsilon[0] + c6 * upsilon[1] - c8 * upsilon[1] - c9 * upsilon[0];
  463. return J;
  464. }
  465. /// Returns derivative of exp(x) wrt. x_i at x=0.
  466. ///
  467. SOPHUS_FUNC static Sophus::Matrix<Scalar, num_parameters, DoF>
  468. Dx_exp_x_at_0() {
  469. Sophus::Matrix<Scalar, num_parameters, DoF> J;
  470. Scalar const o(0);
  471. Scalar const i(1);
  472. // clang-format off
  473. J << o, o, o, o, o, i, i, o, o, o, i, o;
  474. // clang-format on
  475. return J;
  476. }
  477. /// Returns derivative of exp(x).matrix() wrt. ``x_i at x=0``.
  478. ///
  479. SOPHUS_FUNC static Transformation Dxi_exp_x_matrix_at_0(int i) {
  480. return generator(i);
  481. }
  482. /// Group exponential
  483. ///
  484. /// This functions takes in an element of tangent space (= twist ``a``) and
  485. /// returns the corresponding element of the group SE(2).
  486. ///
  487. /// The first two components of ``a`` represent the translational part
  488. /// ``upsilon`` in the tangent space of SE(2), while the last three components
  489. /// of ``a`` represents the rotation vector ``omega``.
  490. /// To be more specific, this function computes ``expmat(hat(a))`` with
  491. /// ``expmat(.)`` being the matrix exponential and ``hat(.)`` the hat-operator
  492. /// of SE(2), see below.
  493. ///
  494. SOPHUS_FUNC static SE2<Scalar> exp(Tangent const& a) {
  495. Scalar theta = a[2];
  496. SO2<Scalar> so2 = SO2<Scalar>::exp(theta);
  497. Scalar sin_theta_by_theta;
  498. Scalar one_minus_cos_theta_by_theta;
  499. using std::abs;
  500. if (abs(theta) < Constants<Scalar>::epsilon()) {
  501. Scalar theta_sq = theta * theta;
  502. sin_theta_by_theta = Scalar(1.) - Scalar(1. / 6.) * theta_sq;
  503. one_minus_cos_theta_by_theta =
  504. Scalar(0.5) * theta - Scalar(1. / 24.) * theta * theta_sq;
  505. } else {
  506. sin_theta_by_theta = so2.unit_complex().y() / theta;
  507. one_minus_cos_theta_by_theta =
  508. (Scalar(1.) - so2.unit_complex().x()) / theta;
  509. }
  510. Vector2<Scalar> trans(
  511. sin_theta_by_theta * a[0] - one_minus_cos_theta_by_theta * a[1],
  512. one_minus_cos_theta_by_theta * a[0] + sin_theta_by_theta * a[1]);
  513. return SE2<Scalar>(so2, trans);
  514. }
  515. /// Returns closest SE3 given arbitrary 4x4 matrix.
  516. ///
  517. template <class S = Scalar>
  518. static SOPHUS_FUNC enable_if_t<std::is_floating_point<S>::value, SE2>
  519. fitToSE2(Matrix3<Scalar> const& T) {
  520. return SE2(SO2<Scalar>::fitToSO2(T.template block<2, 2>(0, 0)),
  521. T.template block<2, 1>(0, 2));
  522. }
  523. /// Returns the ith infinitesimal generators of SE(2).
  524. ///
  525. /// The infinitesimal generators of SE(2) are:
  526. ///
  527. /// ```
  528. /// | 0 0 1 |
  529. /// G_0 = | 0 0 0 |
  530. /// | 0 0 0 |
  531. ///
  532. /// | 0 0 0 |
  533. /// G_1 = | 0 0 1 |
  534. /// | 0 0 0 |
  535. ///
  536. /// | 0 -1 0 |
  537. /// G_2 = | 1 0 0 |
  538. /// | 0 0 0 |
  539. /// ```
  540. ///
  541. /// Precondition: ``i`` must be in 0, 1 or 2.
  542. ///
  543. SOPHUS_FUNC static Transformation generator(int i) {
  544. SOPHUS_ENSURE(i >= 0 || i <= 2, "i should be in range [0,2].");
  545. Tangent e;
  546. e.setZero();
  547. e[i] = Scalar(1);
  548. return hat(e);
  549. }
  550. /// hat-operator
  551. ///
  552. /// It takes in the 3-vector representation (= twist) and returns the
  553. /// corresponding matrix representation of Lie algebra element.
  554. ///
  555. /// Formally, the hat()-operator of SE(3) is defined as
  556. ///
  557. /// ``hat(.): R^3 -> R^{3x33}, hat(a) = sum_i a_i * G_i`` (for i=0,1,2)
  558. ///
  559. /// with ``G_i`` being the ith infinitesimal generator of SE(2).
  560. ///
  561. /// The corresponding inverse is the vee()-operator, see below.
  562. ///
  563. SOPHUS_FUNC static Transformation hat(Tangent const& a) {
  564. Transformation Omega;
  565. Omega.setZero();
  566. Omega.template topLeftCorner<2, 2>() = SO2<Scalar>::hat(a[2]);
  567. Omega.col(2).template head<2>() = a.template head<2>();
  568. return Omega;
  569. }
  570. /// Lie bracket
  571. ///
  572. /// It computes the Lie bracket of SE(2). To be more specific, it computes
  573. ///
  574. /// ``[omega_1, omega_2]_se2 := vee([hat(omega_1), hat(omega_2)])``
  575. ///
  576. /// with ``[A,B] := AB-BA`` being the matrix commutator, ``hat(.)`` the
  577. /// hat()-operator and ``vee(.)`` the vee()-operator of SE(2).
  578. ///
  579. SOPHUS_FUNC static Tangent lieBracket(Tangent const& a, Tangent const& b) {
  580. Vector2<Scalar> upsilon1 = a.template head<2>();
  581. Vector2<Scalar> upsilon2 = b.template head<2>();
  582. Scalar theta1 = a[2];
  583. Scalar theta2 = b[2];
  584. return Tangent(-theta1 * upsilon2[1] + theta2 * upsilon1[1],
  585. theta1 * upsilon2[0] - theta2 * upsilon1[0], Scalar(0));
  586. }
  587. /// Construct pure rotation.
  588. ///
  589. static SOPHUS_FUNC SE2 rot(Scalar const& x) {
  590. return SE2(SO2<Scalar>(x), Sophus::Vector2<Scalar>::Zero());
  591. }
  592. /// Draw uniform sample from SE(2) manifold.
  593. ///
  594. /// Translations are drawn component-wise from the range [-1, 1].
  595. ///
  596. template <class UniformRandomBitGenerator>
  597. static SE2 sampleUniform(UniformRandomBitGenerator& generator) {
  598. std::uniform_real_distribution<Scalar> uniform(Scalar(-1), Scalar(1));
  599. return SE2(SO2<Scalar>::sampleUniform(generator),
  600. Vector2<Scalar>(uniform(generator), uniform(generator)));
  601. }
  602. /// Construct a translation only SE(2) instance.
  603. ///
  604. template <class T0, class T1>
  605. static SOPHUS_FUNC SE2 trans(T0 const& x, T1 const& y) {
  606. return SE2(SO2<Scalar>(), Vector2<Scalar>(x, y));
  607. }
  608. static SOPHUS_FUNC SE2 trans(Vector2<Scalar> const& xy) {
  609. return SE2(SO2<Scalar>(), xy);
  610. }
  611. /// Construct x-axis translation.
  612. ///
  613. static SOPHUS_FUNC SE2 transX(Scalar const& x) {
  614. return SE2::trans(x, Scalar(0));
  615. }
  616. /// Construct y-axis translation.
  617. ///
  618. static SOPHUS_FUNC SE2 transY(Scalar const& y) {
  619. return SE2::trans(Scalar(0), y);
  620. }
  621. /// vee-operator
  622. ///
  623. /// It takes the 3x3-matrix representation ``Omega`` and maps it to the
  624. /// corresponding 3-vector representation of Lie algebra.
  625. ///
  626. /// This is the inverse of the hat()-operator, see above.
  627. ///
  628. /// Precondition: ``Omega`` must have the following structure:
  629. ///
  630. /// | 0 -d a |
  631. /// | d 0 b |
  632. /// | 0 0 0 |
  633. ///
  634. SOPHUS_FUNC static Tangent vee(Transformation const& Omega) {
  635. SOPHUS_ENSURE(
  636. Omega.row(2).template lpNorm<1>() < Constants<Scalar>::epsilon(),
  637. "Omega: \n%", Omega);
  638. Tangent upsilon_omega;
  639. upsilon_omega.template head<2>() = Omega.col(2).template head<2>();
  640. upsilon_omega[2] = SO2<Scalar>::vee(Omega.template topLeftCorner<2, 2>());
  641. return upsilon_omega;
  642. }
  643. protected:
  644. SO2Member so2_;
  645. TranslationMember translation_;
  646. };
  647. template <class Scalar, int Options>
  648. SE2<Scalar, Options>::SE2() : translation_(TranslationMember::Zero()) {
  649. static_assert(std::is_standard_layout<SE2>::value,
  650. "Assume standard layout for the use of offsetof check below.");
  651. static_assert(
  652. offsetof(SE2, so2_) + sizeof(Scalar) * SO2<Scalar>::num_parameters ==
  653. offsetof(SE2, translation_),
  654. "This class assumes packed storage and hence will only work "
  655. "correctly depending on the compiler (options) - in "
  656. "particular when using [this->data(), this-data() + "
  657. "num_parameters] to access the raw data in a contiguous fashion.");
  658. }
  659. } // namespace Sophus
  660. namespace Eigen {
  661. /// Specialization of Eigen::Map for ``SE2``; derived from SE2Base.
  662. ///
  663. /// Allows us to wrap SE2 objects around POD array.
  664. template <class Scalar_, int Options>
  665. class Map<Sophus::SE2<Scalar_>, Options>
  666. : public Sophus::SE2Base<Map<Sophus::SE2<Scalar_>, Options>> {
  667. public:
  668. using Base = Sophus::SE2Base<Map<Sophus::SE2<Scalar_>, Options>>;
  669. using Scalar = Scalar_;
  670. using Transformation = typename Base::Transformation;
  671. using Point = typename Base::Point;
  672. using HomogeneousPoint = typename Base::HomogeneousPoint;
  673. using Tangent = typename Base::Tangent;
  674. using Adjoint = typename Base::Adjoint;
  675. // LCOV_EXCL_START
  676. SOPHUS_INHERIT_ASSIGNMENT_OPERATORS(Map);
  677. // LCOV_EXCL_STOP
  678. using Base::operator*=;
  679. using Base::operator*;
  680. SOPHUS_FUNC
  681. Map(Scalar* coeffs)
  682. : so2_(coeffs),
  683. translation_(coeffs + Sophus::SO2<Scalar>::num_parameters) {}
  684. /// Mutator of SO3
  685. ///
  686. SOPHUS_FUNC Map<Sophus::SO2<Scalar>, Options>& so2() { return so2_; }
  687. /// Accessor of SO3
  688. ///
  689. SOPHUS_FUNC Map<Sophus::SO2<Scalar>, Options> const& so2() const {
  690. return so2_;
  691. }
  692. /// Mutator of translation vector
  693. ///
  694. SOPHUS_FUNC Map<Sophus::Vector2<Scalar>, Options>& translation() {
  695. return translation_;
  696. }
  697. /// Accessor of translation vector
  698. ///
  699. SOPHUS_FUNC Map<Sophus::Vector2<Scalar>, Options> const& translation() const {
  700. return translation_;
  701. }
  702. protected:
  703. Map<Sophus::SO2<Scalar>, Options> so2_;
  704. Map<Sophus::Vector2<Scalar>, Options> translation_;
  705. };
  706. /// Specialization of Eigen::Map for ``SE2 const``; derived from SE2Base.
  707. ///
  708. /// Allows us to wrap SE2 objects around POD array.
  709. template <class Scalar_, int Options>
  710. class Map<Sophus::SE2<Scalar_> const, Options>
  711. : public Sophus::SE2Base<Map<Sophus::SE2<Scalar_> const, Options>> {
  712. public:
  713. using Base = Sophus::SE2Base<Map<Sophus::SE2<Scalar_> const, Options>>;
  714. using Scalar = Scalar_;
  715. using Transformation = typename Base::Transformation;
  716. using Point = typename Base::Point;
  717. using HomogeneousPoint = typename Base::HomogeneousPoint;
  718. using Tangent = typename Base::Tangent;
  719. using Adjoint = typename Base::Adjoint;
  720. using Base::operator*=;
  721. using Base::operator*;
  722. SOPHUS_FUNC Map(Scalar const* coeffs)
  723. : so2_(coeffs),
  724. translation_(coeffs + Sophus::SO2<Scalar>::num_parameters) {}
  725. /// Accessor of SO3
  726. ///
  727. SOPHUS_FUNC Map<Sophus::SO2<Scalar> const, Options> const& so2() const {
  728. return so2_;
  729. }
  730. /// Accessor of translation vector
  731. ///
  732. SOPHUS_FUNC Map<Sophus::Vector2<Scalar> const, Options> const& translation()
  733. const {
  734. return translation_;
  735. }
  736. protected:
  737. Map<Sophus::SO2<Scalar> const, Options> const so2_;
  738. Map<Sophus::Vector2<Scalar> const, Options> const translation_;
  739. };
  740. } // namespace Eigen
  741. #endif