se3.hpp 35 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076
  1. /// @file
  2. /// Special Euclidean group SE(3) - rotation and translation in 3d.
  3. #ifndef SOPHUS_SE3_HPP
  4. #define SOPHUS_SE3_HPP
  5. #include "so3.hpp"
  6. namespace Sophus {
  7. template <class Scalar_, int Options = 0>
  8. class SE3;
  9. using SE3d = SE3<double>;
  10. using SE3f = SE3<float>;
  11. } // namespace Sophus
  12. namespace Eigen {
  13. namespace internal {
  14. template <class Scalar_, int Options>
  15. struct traits<Sophus::SE3<Scalar_, Options>> {
  16. using Scalar = Scalar_;
  17. using TranslationType = Sophus::Vector3<Scalar, Options>;
  18. using SO3Type = Sophus::SO3<Scalar, Options>;
  19. };
  20. template <class Scalar_, int Options>
  21. struct traits<Map<Sophus::SE3<Scalar_>, Options>>
  22. : traits<Sophus::SE3<Scalar_, Options>> {
  23. using Scalar = Scalar_;
  24. using TranslationType = Map<Sophus::Vector3<Scalar>, Options>;
  25. using SO3Type = Map<Sophus::SO3<Scalar>, Options>;
  26. };
  27. template <class Scalar_, int Options>
  28. struct traits<Map<Sophus::SE3<Scalar_> const, Options>>
  29. : traits<Sophus::SE3<Scalar_, Options> const> {
  30. using Scalar = Scalar_;
  31. using TranslationType = Map<Sophus::Vector3<Scalar> const, Options>;
  32. using SO3Type = Map<Sophus::SO3<Scalar> const, Options>;
  33. };
  34. } // namespace internal
  35. } // namespace Eigen
  36. namespace Sophus {
  37. /// SE3 base type - implements SE3 class but is storage agnostic.
  38. ///
  39. /// SE(3) is the group of rotations and translation in 3d. It is the
  40. /// semi-direct product of SO(3) and the 3d Euclidean vector space. The class
  41. /// is represented using a composition of SO3 for rotation and a one 3-vector
  42. /// for translation.
  43. ///
  44. /// SE(3) is neither compact, nor a commutative group.
  45. ///
  46. /// See SO3 for more details of the rotation representation in 3d.
  47. ///
  48. template <class Derived>
  49. class SE3Base {
  50. public:
  51. using Scalar = typename Eigen::internal::traits<Derived>::Scalar;
  52. using TranslationType =
  53. typename Eigen::internal::traits<Derived>::TranslationType;
  54. using SO3Type = typename Eigen::internal::traits<Derived>::SO3Type;
  55. using QuaternionType = typename SO3Type::QuaternionType;
  56. /// Degrees of freedom of manifold, number of dimensions in tangent space
  57. /// (three for translation, three for rotation).
  58. static int constexpr DoF = 6;
  59. /// Number of internal parameters used (4-tuple for quaternion, three for
  60. /// translation).
  61. static int constexpr num_parameters = 7;
  62. /// Group transformations are 4x4 matrices.
  63. static int constexpr N = 4;
  64. using Transformation = Matrix<Scalar, N, N>;
  65. using Point = Vector3<Scalar>;
  66. using HomogeneousPoint = Vector4<Scalar>;
  67. using Line = ParametrizedLine3<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 SE3 operations.
  74. template <typename OtherDerived>
  75. using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<
  76. Scalar, typename OtherDerived::Scalar>::ReturnType;
  77. template <typename OtherDerived>
  78. using SE3Product = SE3<ReturnScalar<OtherDerived>>;
  79. template <typename PointDerived>
  80. using PointProduct = Vector3<ReturnScalar<PointDerived>>;
  81. template <typename HPointDerived>
  82. using HomogeneousPointProduct = Vector4<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. Sophus::Matrix3<Scalar> const R = so3().matrix();
  91. Adjoint res;
  92. res.block(0, 0, 3, 3) = R;
  93. res.block(3, 3, 3, 3) = R;
  94. res.block(0, 3, 3, 3) = SO3<Scalar>::hat(translation()) * R;
  95. res.block(3, 0, 3, 3) = Matrix3<Scalar>::Zero(3, 3);
  96. return res;
  97. }
  98. /// Extract rotation angle about canonical X-axis
  99. ///
  100. Scalar angleX() const { return so3().angleX(); }
  101. /// Extract rotation angle about canonical Y-axis
  102. ///
  103. Scalar angleY() const { return so3().angleY(); }
  104. /// Extract rotation angle about canonical Z-axis
  105. ///
  106. Scalar angleZ() const { return so3().angleZ(); }
  107. /// Returns copy of instance casted to NewScalarType.
  108. ///
  109. template <class NewScalarType>
  110. SOPHUS_FUNC SE3<NewScalarType> cast() const {
  111. return SE3<NewScalarType>(so3().template cast<NewScalarType>(),
  112. translation().template cast<NewScalarType>());
  113. }
  114. /// Returns derivative of this * exp(x) wrt x at x=0.
  115. ///
  116. SOPHUS_FUNC Matrix<Scalar, num_parameters, DoF> Dx_this_mul_exp_x_at_0()
  117. const {
  118. Matrix<Scalar, num_parameters, DoF> J;
  119. Eigen::Quaternion<Scalar> const q = unit_quaternion();
  120. Scalar const c0 = Scalar(0.5) * q.w();
  121. Scalar const c1 = Scalar(0.5) * q.z();
  122. Scalar const c2 = -c1;
  123. Scalar const c3 = Scalar(0.5) * q.y();
  124. Scalar const c4 = Scalar(0.5) * q.x();
  125. Scalar const c5 = -c4;
  126. Scalar const c6 = -c3;
  127. Scalar const c7 = q.w() * q.w();
  128. Scalar const c8 = q.x() * q.x();
  129. Scalar const c9 = q.y() * q.y();
  130. Scalar const c10 = -c9;
  131. Scalar const c11 = q.z() * q.z();
  132. Scalar const c12 = -c11;
  133. Scalar const c13 = Scalar(2) * q.w();
  134. Scalar const c14 = c13 * q.z();
  135. Scalar const c15 = Scalar(2) * q.x();
  136. Scalar const c16 = c15 * q.y();
  137. Scalar const c17 = c13 * q.y();
  138. Scalar const c18 = c15 * q.z();
  139. Scalar const c19 = c7 - c8;
  140. Scalar const c20 = c13 * q.x();
  141. Scalar const c21 = Scalar(2) * q.y() * q.z();
  142. J(0, 0) = 0;
  143. J(0, 1) = 0;
  144. J(0, 2) = 0;
  145. J(0, 3) = c0;
  146. J(0, 4) = c2;
  147. J(0, 5) = c3;
  148. J(1, 0) = 0;
  149. J(1, 1) = 0;
  150. J(1, 2) = 0;
  151. J(1, 3) = c1;
  152. J(1, 4) = c0;
  153. J(1, 5) = c5;
  154. J(2, 0) = 0;
  155. J(2, 1) = 0;
  156. J(2, 2) = 0;
  157. J(2, 3) = c6;
  158. J(2, 4) = c4;
  159. J(2, 5) = c0;
  160. J(3, 0) = 0;
  161. J(3, 1) = 0;
  162. J(3, 2) = 0;
  163. J(3, 3) = c5;
  164. J(3, 4) = c6;
  165. J(3, 5) = c2;
  166. J(4, 0) = c10 + c12 + c7 + c8;
  167. J(4, 1) = -c14 + c16;
  168. J(4, 2) = c17 + c18;
  169. J(4, 3) = 0;
  170. J(4, 4) = 0;
  171. J(4, 5) = 0;
  172. J(5, 0) = c14 + c16;
  173. J(5, 1) = c12 + c19 + c9;
  174. J(5, 2) = -c20 + c21;
  175. J(5, 3) = 0;
  176. J(5, 4) = 0;
  177. J(5, 5) = 0;
  178. J(6, 0) = -c17 + c18;
  179. J(6, 1) = c20 + c21;
  180. J(6, 2) = c10 + c11 + c19;
  181. J(6, 3) = 0;
  182. J(6, 4) = 0;
  183. J(6, 5) = 0;
  184. return J;
  185. }
  186. /// Returns group inverse.
  187. ///
  188. SOPHUS_FUNC SE3<Scalar> inverse() const {
  189. SO3<Scalar> invR = so3().inverse();
  190. return SE3<Scalar>(invR, invR * (translation() * Scalar(-1)));
  191. }
  192. /// Logarithmic map
  193. ///
  194. /// Computes the logarithm, the inverse of the group exponential which maps
  195. /// element of the group (rigid body transformations) to elements of the
  196. /// tangent space (twist).
  197. ///
  198. /// To be specific, this function computes ``vee(logmat(.))`` with
  199. /// ``logmat(.)`` being the matrix logarithm and ``vee(.)`` the vee-operator
  200. /// of SE(3).
  201. ///
  202. SOPHUS_FUNC Tangent log() const {
  203. // For the derivation of the logarithm of SE(3), see
  204. // J. Gallier, D. Xu, "Computing exponentials of skew symmetric matrices
  205. // and logarithms of orthogonal matrices", IJRA 2002.
  206. // https:///pdfs.semanticscholar.org/cfe3/e4b39de63c8cabd89bf3feff7f5449fc981d.pdf
  207. // (Sec. 6., pp. 8)
  208. using std::abs;
  209. using std::cos;
  210. using std::sin;
  211. Tangent upsilon_omega;
  212. auto omega_and_theta = so3().logAndTheta();
  213. Scalar theta = omega_and_theta.theta;
  214. upsilon_omega.template tail<3>() = omega_and_theta.tangent;
  215. Matrix3<Scalar> const Omega =
  216. SO3<Scalar>::hat(upsilon_omega.template tail<3>());
  217. if (abs(theta) < Constants<Scalar>::epsilon()) {
  218. Matrix3<Scalar> const V_inv = Matrix3<Scalar>::Identity() -
  219. Scalar(0.5) * Omega +
  220. Scalar(1. / 12.) * (Omega * Omega);
  221. upsilon_omega.template head<3>() = V_inv * translation();
  222. } else {
  223. Scalar const half_theta = Scalar(0.5) * theta;
  224. Matrix3<Scalar> const V_inv =
  225. (Matrix3<Scalar>::Identity() - Scalar(0.5) * Omega +
  226. (Scalar(1) -
  227. theta * cos(half_theta) / (Scalar(2) * sin(half_theta))) /
  228. (theta * theta) * (Omega * Omega));
  229. upsilon_omega.template head<3>() = V_inv * translation();
  230. }
  231. return upsilon_omega;
  232. }
  233. /// It re-normalizes the SO3 element.
  234. ///
  235. /// Note: Because of the class invariant of SO3, there is typically no need to
  236. /// call this function directly.
  237. ///
  238. SOPHUS_FUNC void normalize() { so3().normalize(); }
  239. /// Returns 4x4 matrix representation of the instance.
  240. ///
  241. /// It has the following form:
  242. ///
  243. /// | R t |
  244. /// | o 1 |
  245. ///
  246. /// where ``R`` is a 3x3 rotation matrix, ``t`` a translation 3-vector and
  247. /// ``o`` a 3-column vector of zeros.
  248. ///
  249. SOPHUS_FUNC Transformation matrix() const {
  250. Transformation homogenious_matrix;
  251. homogenious_matrix.template topLeftCorner<3, 4>() = matrix3x4();
  252. homogenious_matrix.row(3) =
  253. Matrix<Scalar, 1, 4>(Scalar(0), Scalar(0), Scalar(0), Scalar(1));
  254. return homogenious_matrix;
  255. }
  256. /// Returns the significant first three rows of the matrix above.
  257. ///
  258. SOPHUS_FUNC Matrix<Scalar, 3, 4> matrix3x4() const {
  259. Matrix<Scalar, 3, 4> matrix;
  260. matrix.template topLeftCorner<3, 3>() = rotationMatrix();
  261. matrix.col(3) = translation();
  262. return matrix;
  263. }
  264. /// Assignment-like operator from OtherDerived.
  265. ///
  266. template <class OtherDerived>
  267. SOPHUS_FUNC SE3Base<Derived>& operator=(SE3Base<OtherDerived> const& other) {
  268. so3() = other.so3();
  269. translation() = other.translation();
  270. return *this;
  271. }
  272. /// Group multiplication, which is rotation concatenation.
  273. ///
  274. template <typename OtherDerived>
  275. SOPHUS_FUNC SE3Product<OtherDerived> operator*(
  276. SE3Base<OtherDerived> const& other) const {
  277. return SE3Product<OtherDerived>(
  278. so3() * other.so3(), translation() + so3() * other.translation());
  279. }
  280. /// Group action on 3-points.
  281. ///
  282. /// This function rotates and translates a three dimensional point ``p`` by
  283. /// the SE(3) element ``bar_T_foo = (bar_R_foo, t_bar)`` (= rigid body
  284. /// transformation):
  285. ///
  286. /// ``p_bar = bar_R_foo * p_foo + t_bar``.
  287. ///
  288. template <typename PointDerived,
  289. typename = typename std::enable_if<
  290. IsFixedSizeVector<PointDerived, 3>::value>::type>
  291. SOPHUS_FUNC PointProduct<PointDerived> operator*(
  292. Eigen::MatrixBase<PointDerived> const& p) const {
  293. return so3() * p + translation();
  294. }
  295. /// Group action on homogeneous 3-points. See above for more details.
  296. ///
  297. template <typename HPointDerived,
  298. typename = typename std::enable_if<
  299. IsFixedSizeVector<HPointDerived, 4>::value>::type>
  300. SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> operator*(
  301. Eigen::MatrixBase<HPointDerived> const& p) const {
  302. const PointProduct<HPointDerived> tp =
  303. so3() * p.template head<3>() + p(3) * translation();
  304. return HomogeneousPointProduct<HPointDerived>(tp(0), tp(1), tp(2), p(3));
  305. }
  306. /// Group action on lines.
  307. ///
  308. /// This function rotates and translates a parametrized line
  309. /// ``l(t) = o + t * d`` by the SE(3) element:
  310. ///
  311. /// Origin is transformed using SE(3) action
  312. /// Direction is transformed using rotation part
  313. ///
  314. SOPHUS_FUNC Line operator*(Line const& l) const {
  315. return Line((*this) * l.origin(), so3() * l.direction());
  316. }
  317. /// In-place group multiplication. This method is only valid if the return
  318. /// type of the multiplication is compatible with this SE3's Scalar type.
  319. ///
  320. template <typename OtherDerived,
  321. typename = typename std::enable_if<
  322. std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
  323. SOPHUS_FUNC SE3Base<Derived>& operator*=(SE3Base<OtherDerived> const& other) {
  324. *static_cast<Derived*>(this) = *this * other;
  325. return *this;
  326. }
  327. /// Returns rotation matrix.
  328. ///
  329. SOPHUS_FUNC Matrix3<Scalar> rotationMatrix() const { return so3().matrix(); }
  330. /// Mutator of SO3 group.
  331. ///
  332. SOPHUS_FUNC SO3Type& so3() { return static_cast<Derived*>(this)->so3(); }
  333. /// Accessor of SO3 group.
  334. ///
  335. SOPHUS_FUNC SO3Type const& so3() const {
  336. return static_cast<const Derived*>(this)->so3();
  337. }
  338. /// Takes in quaternion, and normalizes it.
  339. ///
  340. /// Precondition: The quaternion must not be close to zero.
  341. ///
  342. SOPHUS_FUNC void setQuaternion(Eigen::Quaternion<Scalar> const& quat) {
  343. so3().setQuaternion(quat);
  344. }
  345. /// Sets ``so3`` using ``rotation_matrix``.
  346. ///
  347. /// Precondition: ``R`` must be orthogonal and ``det(R)=1``.
  348. ///
  349. SOPHUS_FUNC void setRotationMatrix(Matrix3<Scalar> const& R) {
  350. SOPHUS_ENSURE(isOrthogonal(R), "R is not orthogonal:\n %", R);
  351. SOPHUS_ENSURE(R.determinant() > Scalar(0), "det(R) is not positive: %",
  352. R.determinant());
  353. so3().setQuaternion(Eigen::Quaternion<Scalar>(R));
  354. }
  355. /// Returns internal parameters of SE(3).
  356. ///
  357. /// It returns (q.imag[0], q.imag[1], q.imag[2], q.real, t[0], t[1], t[2]),
  358. /// with q being the unit quaternion, t the translation 3-vector.
  359. ///
  360. SOPHUS_FUNC Sophus::Vector<Scalar, num_parameters> params() const {
  361. Sophus::Vector<Scalar, num_parameters> p;
  362. p << so3().params(), translation();
  363. return p;
  364. }
  365. /// Mutator of translation vector.
  366. ///
  367. SOPHUS_FUNC TranslationType& translation() {
  368. return static_cast<Derived*>(this)->translation();
  369. }
  370. /// Accessor of translation vector
  371. ///
  372. SOPHUS_FUNC TranslationType const& translation() const {
  373. return static_cast<Derived const*>(this)->translation();
  374. }
  375. /// Accessor of unit quaternion.
  376. ///
  377. SOPHUS_FUNC QuaternionType const& unit_quaternion() const {
  378. return this->so3().unit_quaternion();
  379. }
  380. };
  381. /// SE3 using default storage; derived from SE3Base.
  382. template <class Scalar_, int Options>
  383. class SE3 : public SE3Base<SE3<Scalar_, Options>> {
  384. using Base = SE3Base<SE3<Scalar_, Options>>;
  385. public:
  386. static int constexpr DoF = Base::DoF;
  387. static int constexpr num_parameters = Base::num_parameters;
  388. using Scalar = Scalar_;
  389. using Transformation = typename Base::Transformation;
  390. using Point = typename Base::Point;
  391. using HomogeneousPoint = typename Base::HomogeneousPoint;
  392. using Tangent = typename Base::Tangent;
  393. using Adjoint = typename Base::Adjoint;
  394. using SO3Member = SO3<Scalar, Options>;
  395. using TranslationMember = Vector3<Scalar, Options>;
  396. using Base::operator=;
  397. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  398. /// Default constructor initializes rigid body motion to the identity.
  399. ///
  400. SOPHUS_FUNC SE3();
  401. /// Copy constructor
  402. ///
  403. SOPHUS_FUNC SE3(SE3 const& other) = default;
  404. /// Copy-like constructor from OtherDerived.
  405. ///
  406. template <class OtherDerived>
  407. SOPHUS_FUNC SE3(SE3Base<OtherDerived> const& other)
  408. : so3_(other.so3()), translation_(other.translation()) {
  409. static_assert(std::is_same<typename OtherDerived::Scalar, Scalar>::value,
  410. "must be same Scalar type");
  411. }
  412. /// Constructor from SO3 and translation vector
  413. ///
  414. template <class OtherDerived, class D>
  415. SOPHUS_FUNC SE3(SO3Base<OtherDerived> const& so3,
  416. Eigen::MatrixBase<D> const& translation)
  417. : so3_(so3), translation_(translation) {
  418. static_assert(std::is_same<typename OtherDerived::Scalar, Scalar>::value,
  419. "must be same Scalar type");
  420. static_assert(std::is_same<typename D::Scalar, Scalar>::value,
  421. "must be same Scalar type");
  422. }
  423. /// Constructor from rotation matrix and translation vector
  424. ///
  425. /// Precondition: Rotation matrix needs to be orthogonal with determinant
  426. /// of 1.
  427. ///
  428. SOPHUS_FUNC
  429. SE3(Matrix3<Scalar> const& rotation_matrix, Point const& translation)
  430. : so3_(rotation_matrix), translation_(translation) {}
  431. /// Constructor from quaternion and translation vector.
  432. ///
  433. /// Precondition: ``quaternion`` must not be close to zero.
  434. ///
  435. SOPHUS_FUNC SE3(Eigen::Quaternion<Scalar> const& quaternion,
  436. Point const& translation)
  437. : so3_(quaternion), translation_(translation) {}
  438. /// Constructor from 4x4 matrix
  439. ///
  440. /// Precondition: Rotation matrix needs to be orthogonal with determinant
  441. /// of 1. The last row must be ``(0, 0, 0, 1)``.
  442. ///
  443. SOPHUS_FUNC explicit SE3(Matrix4<Scalar> const& T)
  444. : so3_(T.template topLeftCorner<3, 3>()),
  445. translation_(T.template block<3, 1>(0, 3)) {
  446. SOPHUS_ENSURE((T.row(3) - Matrix<Scalar, 1, 4>(Scalar(0), Scalar(0),
  447. Scalar(0), Scalar(1)))
  448. .squaredNorm() < Constants<Scalar>::epsilon(),
  449. "Last row is not (0,0,0,1), but (%).", T.row(3));
  450. }
  451. /// This provides unsafe read/write access to internal data. SO(3) is
  452. /// represented by an Eigen::Quaternion (four parameters). When using direct
  453. /// write access, the user needs to take care of that the quaternion stays
  454. /// normalized.
  455. ///
  456. SOPHUS_FUNC Scalar* data() {
  457. // so3_ and translation_ are laid out sequentially with no padding
  458. return so3_.data();
  459. }
  460. /// Const version of data() above.
  461. ///
  462. SOPHUS_FUNC Scalar const* data() const {
  463. // so3_ and translation_ are laid out sequentially with no padding
  464. return so3_.data();
  465. }
  466. /// Mutator of SO3
  467. ///
  468. SOPHUS_FUNC SO3Member& so3() { return so3_; }
  469. /// Accessor of SO3
  470. ///
  471. SOPHUS_FUNC SO3Member const& so3() const { return so3_; }
  472. /// Mutator of translation vector
  473. ///
  474. SOPHUS_FUNC TranslationMember& translation() { return translation_; }
  475. /// Accessor of translation vector
  476. ///
  477. SOPHUS_FUNC TranslationMember const& translation() const {
  478. return translation_;
  479. }
  480. /// Returns derivative of exp(x) wrt. x.
  481. ///
  482. SOPHUS_FUNC static Sophus::Matrix<Scalar, num_parameters, DoF> Dx_exp_x(
  483. Tangent const& upsilon_omega) {
  484. using std::cos;
  485. using std::pow;
  486. using std::sin;
  487. using std::sqrt;
  488. Sophus::Matrix<Scalar, num_parameters, DoF> J;
  489. Sophus::Vector<Scalar, 3> upsilon = upsilon_omega.template head<3>();
  490. Sophus::Vector<Scalar, 3> omega = upsilon_omega.template tail<3>();
  491. Scalar const c0 = omega[0] * omega[0];
  492. Scalar const c1 = omega[1] * omega[1];
  493. Scalar const c2 = omega[2] * omega[2];
  494. Scalar const c3 = c0 + c1 + c2;
  495. Scalar const o(0);
  496. Scalar const h(0.5);
  497. Scalar const i(1);
  498. if (c3 < Constants<Scalar>::epsilon()) {
  499. Scalar const ux = Scalar(0.5) * upsilon[0];
  500. Scalar const uy = Scalar(0.5) * upsilon[1];
  501. Scalar const uz = Scalar(0.5) * upsilon[2];
  502. /// clang-format off
  503. J << o, o, o, h, o, o, o, o, o, o, h, o, o, o, o, o, o, h, o, o, o, o, o,
  504. o, i, o, o, o, uz, -uy, o, i, o, -uz, o, ux, o, o, i, uy, -ux, o;
  505. /// clang-format on
  506. return J;
  507. }
  508. Scalar const c4 = sqrt(c3);
  509. Scalar const c5 = Scalar(1.0) / c4;
  510. Scalar const c6 = Scalar(0.5) * c4;
  511. Scalar const c7 = sin(c6);
  512. Scalar const c8 = c5 * c7;
  513. Scalar const c9 = pow(c3, -3.0L / 2.0L);
  514. Scalar const c10 = c7 * c9;
  515. Scalar const c11 = Scalar(1.0) / c3;
  516. Scalar const c12 = cos(c6);
  517. Scalar const c13 = Scalar(0.5) * c11 * c12;
  518. Scalar const c14 = c7 * c9 * omega[0];
  519. Scalar const c15 = Scalar(0.5) * c11 * c12 * omega[0];
  520. Scalar const c16 = -c14 * omega[1] + c15 * omega[1];
  521. Scalar const c17 = -c14 * omega[2] + c15 * omega[2];
  522. Scalar const c18 = omega[1] * omega[2];
  523. Scalar const c19 = -c10 * c18 + c13 * c18;
  524. Scalar const c20 = c5 * omega[0];
  525. Scalar const c21 = Scalar(0.5) * c7;
  526. Scalar const c22 = c5 * omega[1];
  527. Scalar const c23 = c5 * omega[2];
  528. Scalar const c24 = -c1;
  529. Scalar const c25 = -c2;
  530. Scalar const c26 = c24 + c25;
  531. Scalar const c27 = sin(c4);
  532. Scalar const c28 = -c27 + c4;
  533. Scalar const c29 = c28 * c9;
  534. Scalar const c30 = cos(c4);
  535. Scalar const c31 = -c30 + Scalar(1);
  536. Scalar const c32 = c11 * c31;
  537. Scalar const c33 = c32 * omega[2];
  538. Scalar const c34 = c29 * omega[0];
  539. Scalar const c35 = c34 * omega[1];
  540. Scalar const c36 = c32 * omega[1];
  541. Scalar const c37 = c34 * omega[2];
  542. Scalar const c38 = pow(c3, -5.0L / 2.0L);
  543. Scalar const c39 = Scalar(3) * c28 * c38 * omega[0];
  544. Scalar const c40 = c26 * c9;
  545. Scalar const c41 = -c20 * c30 + c20;
  546. Scalar const c42 = c27 * c9 * omega[0];
  547. Scalar const c43 = c42 * omega[1];
  548. Scalar const c44 = pow(c3, -2);
  549. Scalar const c45 = Scalar(2) * c31 * c44 * omega[0];
  550. Scalar const c46 = c45 * omega[1];
  551. Scalar const c47 = c29 * omega[2];
  552. Scalar const c48 = c43 - c46 + c47;
  553. Scalar const c49 = Scalar(3) * c0 * c28 * c38;
  554. Scalar const c50 = c9 * omega[0] * omega[2];
  555. Scalar const c51 = c41 * c50 - c49 * omega[2];
  556. Scalar const c52 = c9 * omega[0] * omega[1];
  557. Scalar const c53 = c41 * c52 - c49 * omega[1];
  558. Scalar const c54 = c42 * omega[2];
  559. Scalar const c55 = c45 * omega[2];
  560. Scalar const c56 = c29 * omega[1];
  561. Scalar const c57 = -c54 + c55 + c56;
  562. Scalar const c58 = Scalar(-2) * c56;
  563. Scalar const c59 = Scalar(3) * c28 * c38 * omega[1];
  564. Scalar const c60 = -c22 * c30 + c22;
  565. Scalar const c61 = -c18 * c39;
  566. Scalar const c62 = c32 + c61;
  567. Scalar const c63 = c27 * c9;
  568. Scalar const c64 = c1 * c63;
  569. Scalar const c65 = Scalar(2) * c31 * c44;
  570. Scalar const c66 = c1 * c65;
  571. Scalar const c67 = c50 * c60;
  572. Scalar const c68 = -c1 * c39 + c52 * c60;
  573. Scalar const c69 = c18 * c63;
  574. Scalar const c70 = c18 * c65;
  575. Scalar const c71 = c34 - c69 + c70;
  576. Scalar const c72 = Scalar(-2) * c47;
  577. Scalar const c73 = Scalar(3) * c28 * c38 * omega[2];
  578. Scalar const c74 = -c23 * c30 + c23;
  579. Scalar const c75 = -c32 + c61;
  580. Scalar const c76 = c2 * c63;
  581. Scalar const c77 = c2 * c65;
  582. Scalar const c78 = c52 * c74;
  583. Scalar const c79 = c34 + c69 - c70;
  584. Scalar const c80 = -c2 * c39 + c50 * c74;
  585. Scalar const c81 = -c0;
  586. Scalar const c82 = c25 + c81;
  587. Scalar const c83 = c32 * omega[0];
  588. Scalar const c84 = c18 * c29;
  589. Scalar const c85 = Scalar(-2) * c34;
  590. Scalar const c86 = c82 * c9;
  591. Scalar const c87 = c0 * c63;
  592. Scalar const c88 = c0 * c65;
  593. Scalar const c89 = c9 * omega[1] * omega[2];
  594. Scalar const c90 = c41 * c89;
  595. Scalar const c91 = c54 - c55 + c56;
  596. Scalar const c92 = -c1 * c73 + c60 * c89;
  597. Scalar const c93 = -c43 + c46 + c47;
  598. Scalar const c94 = -c2 * c59 + c74 * c89;
  599. Scalar const c95 = c24 + c81;
  600. Scalar const c96 = c9 * c95;
  601. J(0, 0) = o;
  602. J(0, 1) = o;
  603. J(0, 2) = o;
  604. J(0, 3) = -c0 * c10 + c0 * c13 + c8;
  605. J(0, 4) = c16;
  606. J(0, 5) = c17;
  607. J(1, 0) = o;
  608. J(1, 1) = o;
  609. J(1, 2) = o;
  610. J(1, 3) = c16;
  611. J(1, 4) = -c1 * c10 + c1 * c13 + c8;
  612. J(1, 5) = c19;
  613. J(2, 0) = o;
  614. J(2, 1) = o;
  615. J(2, 2) = o;
  616. J(2, 3) = c17;
  617. J(2, 4) = c19;
  618. J(2, 5) = -c10 * c2 + c13 * c2 + c8;
  619. J(3, 0) = o;
  620. J(3, 1) = o;
  621. J(3, 2) = o;
  622. J(3, 3) = -c20 * c21;
  623. J(3, 4) = -c21 * c22;
  624. J(3, 5) = -c21 * c23;
  625. J(4, 0) = c26 * c29 + Scalar(1);
  626. J(4, 1) = -c33 + c35;
  627. J(4, 2) = c36 + c37;
  628. J(4, 3) = upsilon[0] * (-c26 * c39 + c40 * c41) + upsilon[1] * (c53 + c57) +
  629. upsilon[2] * (c48 + c51);
  630. J(4, 4) = upsilon[0] * (-c26 * c59 + c40 * c60 + c58) +
  631. upsilon[1] * (c68 + c71) + upsilon[2] * (c62 + c64 - c66 + c67);
  632. J(4, 5) = upsilon[0] * (-c26 * c73 + c40 * c74 + c72) +
  633. upsilon[1] * (c75 - c76 + c77 + c78) + upsilon[2] * (c79 + c80);
  634. J(5, 0) = c33 + c35;
  635. J(5, 1) = c29 * c82 + Scalar(1);
  636. J(5, 2) = -c83 + c84;
  637. J(5, 3) = upsilon[0] * (c53 + c91) +
  638. upsilon[1] * (-c39 * c82 + c41 * c86 + c85) +
  639. upsilon[2] * (c75 - c87 + c88 + c90);
  640. J(5, 4) = upsilon[0] * (c68 + c79) + upsilon[1] * (-c59 * c82 + c60 * c86) +
  641. upsilon[2] * (c92 + c93);
  642. J(5, 5) = upsilon[0] * (c62 + c76 - c77 + c78) +
  643. upsilon[1] * (c72 - c73 * c82 + c74 * c86) +
  644. upsilon[2] * (c57 + c94);
  645. J(6, 0) = -c36 + c37;
  646. J(6, 1) = c83 + c84;
  647. J(6, 2) = c29 * c95 + Scalar(1);
  648. J(6, 3) = upsilon[0] * (c51 + c93) + upsilon[1] * (c62 + c87 - c88 + c90) +
  649. upsilon[2] * (-c39 * c95 + c41 * c96 + c85);
  650. J(6, 4) = upsilon[0] * (-c64 + c66 + c67 + c75) + upsilon[1] * (c48 + c92) +
  651. upsilon[2] * (c58 - c59 * c95 + c60 * c96);
  652. J(6, 5) = upsilon[0] * (c71 + c80) + upsilon[1] * (c91 + c94) +
  653. upsilon[2] * (-c73 * c95 + c74 * c96);
  654. return J;
  655. }
  656. /// Returns derivative of exp(x) wrt. x_i at x=0.
  657. ///
  658. SOPHUS_FUNC static Sophus::Matrix<Scalar, num_parameters, DoF>
  659. Dx_exp_x_at_0() {
  660. Sophus::Matrix<Scalar, num_parameters, DoF> J;
  661. Scalar const o(0);
  662. Scalar const h(0.5);
  663. Scalar const i(1);
  664. // clang-format off
  665. J << o, o, o, h, o, o, o,
  666. o, o, o, h, o, o, o,
  667. o, o, o, h, o, o, o,
  668. o, o, o, i, o, o, o,
  669. o, o, o, i, o, o, o,
  670. o, o, o, i, o, o, o;
  671. // clang-format on
  672. return J;
  673. }
  674. /// Returns derivative of exp(x).matrix() wrt. ``x_i at x=0``.
  675. ///
  676. SOPHUS_FUNC static Transformation Dxi_exp_x_matrix_at_0(int i) {
  677. return generator(i);
  678. }
  679. /// Group exponential
  680. ///
  681. /// This functions takes in an element of tangent space (= twist ``a``) and
  682. /// returns the corresponding element of the group SE(3).
  683. ///
  684. /// The first three components of ``a`` represent the translational part
  685. /// ``upsilon`` in the tangent space of SE(3), while the last three components
  686. /// of ``a`` represents the rotation vector ``omega``.
  687. /// To be more specific, this function computes ``expmat(hat(a))`` with
  688. /// ``expmat(.)`` being the matrix exponential and ``hat(.)`` the hat-operator
  689. /// of SE(3), see below.
  690. ///
  691. SOPHUS_FUNC static SE3<Scalar> exp(Tangent const& a) {
  692. using std::cos;
  693. using std::sin;
  694. Vector3<Scalar> const omega = a.template tail<3>();
  695. Scalar theta;
  696. SO3<Scalar> const so3 = SO3<Scalar>::expAndTheta(omega, &theta);
  697. Matrix3<Scalar> const Omega = SO3<Scalar>::hat(omega);
  698. Matrix3<Scalar> const Omega_sq = Omega * Omega;
  699. Matrix3<Scalar> V;
  700. if (theta < Constants<Scalar>::epsilon()) {
  701. V = so3.matrix();
  702. /// Note: That is an accurate expansion!
  703. } else {
  704. Scalar theta_sq = theta * theta;
  705. V = (Matrix3<Scalar>::Identity() +
  706. (Scalar(1) - cos(theta)) / (theta_sq)*Omega +
  707. (theta - sin(theta)) / (theta_sq * theta) * Omega_sq);
  708. }
  709. return SE3<Scalar>(so3, V * a.template head<3>());
  710. }
  711. /// Returns closest SE3 given arbirary 4x4 matrix.
  712. ///
  713. template <class S = Scalar>
  714. SOPHUS_FUNC static enable_if_t<std::is_floating_point<S>::value, SE3>
  715. fitToSE3(Matrix4<Scalar> const& T) {
  716. return SE3(SO3<Scalar>::fitToSO3(T.template block<3, 3>(0, 0)),
  717. T.template block<3, 1>(0, 3));
  718. }
  719. /// Returns the ith infinitesimal generators of SE(3).
  720. ///
  721. /// The infinitesimal generators of SE(3) are:
  722. ///
  723. /// ```
  724. /// | 0 0 0 1 |
  725. /// G_0 = | 0 0 0 0 |
  726. /// | 0 0 0 0 |
  727. /// | 0 0 0 0 |
  728. ///
  729. /// | 0 0 0 0 |
  730. /// G_1 = | 0 0 0 1 |
  731. /// | 0 0 0 0 |
  732. /// | 0 0 0 0 |
  733. ///
  734. /// | 0 0 0 0 |
  735. /// G_2 = | 0 0 0 0 |
  736. /// | 0 0 0 1 |
  737. /// | 0 0 0 0 |
  738. ///
  739. /// | 0 0 0 0 |
  740. /// G_3 = | 0 0 -1 0 |
  741. /// | 0 1 0 0 |
  742. /// | 0 0 0 0 |
  743. ///
  744. /// | 0 0 1 0 |
  745. /// G_4 = | 0 0 0 0 |
  746. /// | -1 0 0 0 |
  747. /// | 0 0 0 0 |
  748. ///
  749. /// | 0 -1 0 0 |
  750. /// G_5 = | 1 0 0 0 |
  751. /// | 0 0 0 0 |
  752. /// | 0 0 0 0 |
  753. /// ```
  754. ///
  755. /// Precondition: ``i`` must be in [0, 5].
  756. ///
  757. SOPHUS_FUNC static Transformation generator(int i) {
  758. SOPHUS_ENSURE(i >= 0 && i <= 5, "i should be in range [0,5].");
  759. Tangent e;
  760. e.setZero();
  761. e[i] = Scalar(1);
  762. return hat(e);
  763. }
  764. /// hat-operator
  765. ///
  766. /// It takes in the 6-vector representation (= twist) and returns the
  767. /// corresponding matrix representation of Lie algebra element.
  768. ///
  769. /// Formally, the hat()-operator of SE(3) is defined as
  770. ///
  771. /// ``hat(.): R^6 -> R^{4x4}, hat(a) = sum_i a_i * G_i`` (for i=0,...,5)
  772. ///
  773. /// with ``G_i`` being the ith infinitesimal generator of SE(3).
  774. ///
  775. /// The corresponding inverse is the vee()-operator, see below.
  776. ///
  777. SOPHUS_FUNC static Transformation hat(Tangent const& a) {
  778. Transformation Omega;
  779. Omega.setZero();
  780. Omega.template topLeftCorner<3, 3>() =
  781. SO3<Scalar>::hat(a.template tail<3>());
  782. Omega.col(3).template head<3>() = a.template head<3>();
  783. return Omega;
  784. }
  785. /// Lie bracket
  786. ///
  787. /// It computes the Lie bracket of SE(3). To be more specific, it computes
  788. ///
  789. /// ``[omega_1, omega_2]_se3 := vee([hat(omega_1), hat(omega_2)])``
  790. ///
  791. /// with ``[A,B] := AB-BA`` being the matrix commutator, ``hat(.)`` the
  792. /// hat()-operator and ``vee(.)`` the vee()-operator of SE(3).
  793. ///
  794. SOPHUS_FUNC static Tangent lieBracket(Tangent const& a, Tangent const& b) {
  795. Vector3<Scalar> const upsilon1 = a.template head<3>();
  796. Vector3<Scalar> const upsilon2 = b.template head<3>();
  797. Vector3<Scalar> const omega1 = a.template tail<3>();
  798. Vector3<Scalar> const omega2 = b.template tail<3>();
  799. Tangent res;
  800. res.template head<3>() = omega1.cross(upsilon2) + upsilon1.cross(omega2);
  801. res.template tail<3>() = omega1.cross(omega2);
  802. return res;
  803. }
  804. /// Construct x-axis rotation.
  805. ///
  806. static SOPHUS_FUNC SE3 rotX(Scalar const& x) {
  807. return SE3(SO3<Scalar>::rotX(x), Sophus::Vector3<Scalar>::Zero());
  808. }
  809. /// Construct y-axis rotation.
  810. ///
  811. static SOPHUS_FUNC SE3 rotY(Scalar const& y) {
  812. return SE3(SO3<Scalar>::rotY(y), Sophus::Vector3<Scalar>::Zero());
  813. }
  814. /// Construct z-axis rotation.
  815. ///
  816. static SOPHUS_FUNC SE3 rotZ(Scalar const& z) {
  817. return SE3(SO3<Scalar>::rotZ(z), Sophus::Vector3<Scalar>::Zero());
  818. }
  819. /// Draw uniform sample from SE(3) manifold.
  820. ///
  821. /// Translations are drawn component-wise from the range [-1, 1].
  822. ///
  823. template <class UniformRandomBitGenerator>
  824. static SE3 sampleUniform(UniformRandomBitGenerator& generator) {
  825. std::uniform_real_distribution<Scalar> uniform(Scalar(-1), Scalar(1));
  826. return SE3(SO3<Scalar>::sampleUniform(generator),
  827. Vector3<Scalar>(uniform(generator), uniform(generator),
  828. uniform(generator)));
  829. }
  830. /// Construct a translation only SE3 instance.
  831. ///
  832. template <class T0, class T1, class T2>
  833. static SOPHUS_FUNC SE3 trans(T0 const& x, T1 const& y, T2 const& z) {
  834. return SE3(SO3<Scalar>(), Vector3<Scalar>(x, y, z));
  835. }
  836. static SOPHUS_FUNC SE3 trans(Vector3<Scalar> const& xyz) {
  837. return SE3(SO3<Scalar>(), xyz);
  838. }
  839. /// Construct x-axis translation.
  840. ///
  841. static SOPHUS_FUNC SE3 transX(Scalar const& x) {
  842. return SE3::trans(x, Scalar(0), Scalar(0));
  843. }
  844. /// Construct y-axis translation.
  845. ///
  846. static SOPHUS_FUNC SE3 transY(Scalar const& y) {
  847. return SE3::trans(Scalar(0), y, Scalar(0));
  848. }
  849. /// Construct z-axis translation.
  850. ///
  851. static SOPHUS_FUNC SE3 transZ(Scalar const& z) {
  852. return SE3::trans(Scalar(0), Scalar(0), z);
  853. }
  854. /// vee-operator
  855. ///
  856. /// It takes 4x4-matrix representation ``Omega`` and maps it to the
  857. /// corresponding 6-vector representation of Lie algebra.
  858. ///
  859. /// This is the inverse of the hat()-operator, see above.
  860. ///
  861. /// Precondition: ``Omega`` must have the following structure:
  862. ///
  863. /// | 0 -f e a |
  864. /// | f 0 -d b |
  865. /// | -e d 0 c
  866. /// | 0 0 0 0 | .
  867. ///
  868. SOPHUS_FUNC static Tangent vee(Transformation const& Omega) {
  869. Tangent upsilon_omega;
  870. upsilon_omega.template head<3>() = Omega.col(3).template head<3>();
  871. upsilon_omega.template tail<3>() =
  872. SO3<Scalar>::vee(Omega.template topLeftCorner<3, 3>());
  873. return upsilon_omega;
  874. }
  875. protected:
  876. SO3Member so3_;
  877. TranslationMember translation_;
  878. };
  879. template <class Scalar, int Options>
  880. SE3<Scalar, Options>::SE3() : translation_(TranslationMember::Zero()) {
  881. static_assert(std::is_standard_layout<SE3>::value,
  882. "Assume standard layout for the use of offsetof check below.");
  883. static_assert(
  884. offsetof(SE3, so3_) + sizeof(Scalar) * SO3<Scalar>::num_parameters ==
  885. offsetof(SE3, translation_),
  886. "This class assumes packed storage and hence will only work "
  887. "correctly depending on the compiler (options) - in "
  888. "particular when using [this->data(), this-data() + "
  889. "num_parameters] to access the raw data in a contiguous fashion.");
  890. }
  891. } // namespace Sophus
  892. namespace Eigen {
  893. /// Specialization of Eigen::Map for ``SE3``; derived from SE3Base.
  894. ///
  895. /// Allows us to wrap SE3 objects around POD array.
  896. template <class Scalar_, int Options>
  897. class Map<Sophus::SE3<Scalar_>, Options>
  898. : public Sophus::SE3Base<Map<Sophus::SE3<Scalar_>, Options>> {
  899. public:
  900. using Base = Sophus::SE3Base<Map<Sophus::SE3<Scalar_>, Options>>;
  901. using Scalar = Scalar_;
  902. using Transformation = typename Base::Transformation;
  903. using Point = typename Base::Point;
  904. using HomogeneousPoint = typename Base::HomogeneousPoint;
  905. using Tangent = typename Base::Tangent;
  906. using Adjoint = typename Base::Adjoint;
  907. using Base::operator=;
  908. using Base::operator*=;
  909. using Base::operator*;
  910. SOPHUS_FUNC Map(Scalar* coeffs)
  911. : so3_(coeffs),
  912. translation_(coeffs + Sophus::SO3<Scalar>::num_parameters) {}
  913. /// Mutator of SO3
  914. ///
  915. SOPHUS_FUNC Map<Sophus::SO3<Scalar>, Options>& so3() { return so3_; }
  916. /// Accessor of SO3
  917. ///
  918. SOPHUS_FUNC Map<Sophus::SO3<Scalar>, Options> const& so3() const {
  919. return so3_;
  920. }
  921. /// Mutator of translation vector
  922. ///
  923. SOPHUS_FUNC Map<Sophus::Vector3<Scalar, Options>>& translation() {
  924. return translation_;
  925. }
  926. /// Accessor of translation vector
  927. ///
  928. SOPHUS_FUNC Map<Sophus::Vector3<Scalar, Options>> const& translation() const {
  929. return translation_;
  930. }
  931. protected:
  932. Map<Sophus::SO3<Scalar>, Options> so3_;
  933. Map<Sophus::Vector3<Scalar>, Options> translation_;
  934. };
  935. /// Specialization of Eigen::Map for ``SE3 const``; derived from SE3Base.
  936. ///
  937. /// Allows us to wrap SE3 objects around POD array.
  938. template <class Scalar_, int Options>
  939. class Map<Sophus::SE3<Scalar_> const, Options>
  940. : public Sophus::SE3Base<Map<Sophus::SE3<Scalar_> const, Options>> {
  941. public:
  942. using Base = Sophus::SE3Base<Map<Sophus::SE3<Scalar_> const, Options>>;
  943. using Scalar = Scalar_;
  944. using Transformation = typename Base::Transformation;
  945. using Point = typename Base::Point;
  946. using HomogeneousPoint = typename Base::HomogeneousPoint;
  947. using Tangent = typename Base::Tangent;
  948. using Adjoint = typename Base::Adjoint;
  949. using Base::operator*=;
  950. using Base::operator*;
  951. SOPHUS_FUNC Map(Scalar const* coeffs)
  952. : so3_(coeffs),
  953. translation_(coeffs + Sophus::SO3<Scalar>::num_parameters) {}
  954. /// Accessor of SO3
  955. ///
  956. SOPHUS_FUNC Map<Sophus::SO3<Scalar> const, Options> const& so3() const {
  957. return so3_;
  958. }
  959. /// Accessor of translation vector
  960. ///
  961. SOPHUS_FUNC Map<Sophus::Vector3<Scalar> const, Options> const& translation()
  962. const {
  963. return translation_;
  964. }
  965. protected:
  966. Map<Sophus::SO3<Scalar> const, Options> const so3_;
  967. Map<Sophus::Vector3<Scalar> const, Options> const translation_;
  968. };
  969. } // namespace Eigen
  970. #endif