/// @file /// Special Euclidean group SE(2) - rotation and translation in 2d. #ifndef SOPHUS_SE2_HPP #define SOPHUS_SE2_HPP #include "so2.hpp" namespace Sophus { template class SE2; using SE2d = SE2; using SE2f = SE2; } // namespace Sophus namespace Eigen { namespace internal { template struct traits> { using Scalar = Scalar_; using TranslationType = Sophus::Vector2; using SO2Type = Sophus::SO2; }; template struct traits, Options>> : traits> { using Scalar = Scalar_; using TranslationType = Map, Options>; using SO2Type = Map, Options>; }; template struct traits const, Options>> : traits const> { using Scalar = Scalar_; using TranslationType = Map const, Options>; using SO2Type = Map const, Options>; }; } // namespace internal } // namespace Eigen namespace Sophus { /// SE2 base type - implements SE2 class but is storage agnostic. /// /// SE(2) is the group of rotations and translation in 2d. It is the /// semi-direct product of SO(2) and the 2d Euclidean vector space. The class /// is represented using a composition of SO2Group for rotation and a 2-vector /// for translation. /// /// SE(2) is neither compact, nor a commutative group. /// /// See SO2Group for more details of the rotation representation in 2d. /// template class SE2Base { public: using Scalar = typename Eigen::internal::traits::Scalar; using TranslationType = typename Eigen::internal::traits::TranslationType; using SO2Type = typename Eigen::internal::traits::SO2Type; /// Degrees of freedom of manifold, number of dimensions in tangent space /// (two for translation, three for rotation). static int constexpr DoF = 3; /// Number of internal parameters used (tuple for complex, two for /// translation). static int constexpr num_parameters = 4; /// Group transformations are 3x3 matrices. static int constexpr N = 3; using Transformation = Matrix; using Point = Vector2; using HomogeneousPoint = Vector3; using Line = ParametrizedLine2; using Tangent = Vector; using Adjoint = Matrix; /// For binary operations the return type is determined with the /// ScalarBinaryOpTraits feature of Eigen. This allows mixing concrete and Map /// types, as well as other compatible scalar types such as Ceres::Jet and /// double scalars with SE2 operations. template using ReturnScalar = typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar>::ReturnType; template using SE2Product = SE2>; template using PointProduct = Vector2>; template using HomogeneousPointProduct = Vector3>; /// Adjoint transformation /// /// This function return the adjoint transformation ``Ad`` of the group /// element ``A`` such that for all ``x`` it holds that /// ``hat(Ad_A * x) = A * hat(x) A^{-1}``. See hat-operator below. /// SOPHUS_FUNC Adjoint Adj() const { Matrix const& R = so2().matrix(); Transformation res; res.setIdentity(); res.template topLeftCorner<2, 2>() = R; res(0, 2) = translation()[1]; res(1, 2) = -translation()[0]; return res; } /// Returns copy of instance casted to NewScalarType. /// template SOPHUS_FUNC SE2 cast() const { return SE2(so2().template cast(), translation().template cast()); } /// Returns derivative of this * exp(x) wrt x at x=0. /// SOPHUS_FUNC Matrix Dx_this_mul_exp_x_at_0() const { Matrix J; Sophus::Vector2 const c = unit_complex(); Scalar o(0); J(0, 0) = o; J(0, 1) = o; J(0, 2) = -c[1]; J(1, 0) = o; J(1, 1) = o; J(1, 2) = c[0]; J(2, 0) = c[0]; J(2, 1) = -c[1]; J(2, 2) = o; J(3, 0) = c[1]; J(3, 1) = c[0]; J(3, 2) = o; return J; } /// Returns group inverse. /// SOPHUS_FUNC SE2 inverse() const { SO2 const invR = so2().inverse(); return SE2(invR, invR * (translation() * Scalar(-1))); } /// Logarithmic map /// /// Computes the logarithm, the inverse of the group exponential which maps /// element of the group (rigid body transformations) to elements of the /// tangent space (twist). /// /// To be specific, this function computes ``vee(logmat(.))`` with /// ``logmat(.)`` being the matrix logarithm and ``vee(.)`` the vee-operator /// of SE(2). /// SOPHUS_FUNC Tangent log() const { using std::abs; Tangent upsilon_theta; Scalar theta = so2().log(); upsilon_theta[2] = theta; Scalar halftheta = Scalar(0.5) * theta; Scalar halftheta_by_tan_of_halftheta; Vector2 z = so2().unit_complex(); Scalar real_minus_one = z.x() - Scalar(1.); if (abs(real_minus_one) < Constants::epsilon()) { halftheta_by_tan_of_halftheta = Scalar(1.) - Scalar(1. / 12) * theta * theta; } else { halftheta_by_tan_of_halftheta = -(halftheta * z.y()) / (real_minus_one); } Matrix V_inv; V_inv << halftheta_by_tan_of_halftheta, halftheta, -halftheta, halftheta_by_tan_of_halftheta; upsilon_theta.template head<2>() = V_inv * translation(); return upsilon_theta; } /// Normalize SO2 element /// /// It re-normalizes the SO2 element. /// SOPHUS_FUNC void normalize() { so2().normalize(); } /// Returns 3x3 matrix representation of the instance. /// /// It has the following form: /// /// | R t | /// | o 1 | /// /// where ``R`` is a 2x2 rotation matrix, ``t`` a translation 2-vector and /// ``o`` a 2-column vector of zeros. /// SOPHUS_FUNC Transformation matrix() const { Transformation homogenious_matrix; homogenious_matrix.template topLeftCorner<2, 3>() = matrix2x3(); homogenious_matrix.row(2) = Matrix(Scalar(0), Scalar(0), Scalar(1)); return homogenious_matrix; } /// Returns the significant first two rows of the matrix above. /// SOPHUS_FUNC Matrix matrix2x3() const { Matrix matrix; matrix.template topLeftCorner<2, 2>() = rotationMatrix(); matrix.col(2) = translation(); return matrix; } /// Assignment-like operator from OtherDerived. /// template SOPHUS_FUNC SE2Base& operator=(SE2Base const& other) { so2() = other.so2(); translation() = other.translation(); return *this; } /// Group multiplication, which is rotation concatenation. /// template SOPHUS_FUNC SE2Product operator*( SE2Base const& other) const { return SE2Product( so2() * other.so2(), translation() + so2() * other.translation()); } /// Group action on 2-points. /// /// This function rotates and translates a two dimensional point ``p`` by the /// SE(2) element ``bar_T_foo = (bar_R_foo, t_bar)`` (= rigid body /// transformation): /// /// ``p_bar = bar_R_foo * p_foo + t_bar``. /// template ::value>::type> SOPHUS_FUNC PointProduct operator*( Eigen::MatrixBase const& p) const { return so2() * p + translation(); } /// Group action on homogeneous 2-points. See above for more details. /// template ::value>::type> SOPHUS_FUNC HomogeneousPointProduct operator*( Eigen::MatrixBase const& p) const { const PointProduct tp = so2() * p.template head<2>() + p(2) * translation(); return HomogeneousPointProduct(tp(0), tp(1), p(2)); } /// Group action on lines. /// /// This function rotates and translates a parametrized line /// ``l(t) = o + t * d`` by the SE(2) element: /// /// Origin ``o`` is rotated and translated using SE(2) action /// Direction ``d`` is rotated using SO(2) action /// SOPHUS_FUNC Line operator*(Line const& l) const { return Line((*this) * l.origin(), so2() * l.direction()); } /// In-place group multiplication. This method is only valid if the return /// type of the multiplication is compatible with this SO2's Scalar type. /// template >::value>::type> SOPHUS_FUNC SE2Base& operator*=(SE2Base const& other) { *static_cast(this) = *this * other; return *this; } /// Returns internal parameters of SE(2). /// /// It returns (c[0], c[1], t[0], t[1]), /// with c being the unit complex number, t the translation 3-vector. /// SOPHUS_FUNC Sophus::Vector params() const { Sophus::Vector p; p << so2().params(), translation(); return p; } /// Returns rotation matrix. /// SOPHUS_FUNC Matrix rotationMatrix() const { return so2().matrix(); } /// Takes in complex number, and normalizes it. /// /// Precondition: The complex number must not be close to zero. /// SOPHUS_FUNC void setComplex(Sophus::Vector2 const& complex) { return so2().setComplex(complex); } /// Sets ``so3`` using ``rotation_matrix``. /// /// Precondition: ``R`` must be orthogonal and ``det(R)=1``. /// SOPHUS_FUNC void setRotationMatrix(Matrix const& R) { SOPHUS_ENSURE(isOrthogonal(R), "R is not orthogonal:\n %", R); SOPHUS_ENSURE(R.determinant() > Scalar(0), "det(R) is not positive: %", R.determinant()); typename SO2Type::ComplexTemporaryType const complex( Scalar(0.5) * (R(0, 0) + R(1, 1)), Scalar(0.5) * (R(1, 0) - R(0, 1))); so2().setComplex(complex); } /// Mutator of SO3 group. /// SOPHUS_FUNC SO2Type& so2() { return static_cast(this)->so2(); } /// Accessor of SO3 group. /// SOPHUS_FUNC SO2Type const& so2() const { return static_cast(this)->so2(); } /// Mutator of translation vector. /// SOPHUS_FUNC TranslationType& translation() { return static_cast(this)->translation(); } /// Accessor of translation vector /// SOPHUS_FUNC TranslationType const& translation() const { return static_cast(this)->translation(); } /// Accessor of unit complex number. /// SOPHUS_FUNC typename Eigen::internal::traits::SO2Type::ComplexT const& unit_complex() const { return so2().unit_complex(); } }; /// SE2 using default storage; derived from SE2Base. template class SE2 : public SE2Base> { public: using Base = SE2Base>; static int constexpr DoF = Base::DoF; static int constexpr num_parameters = Base::num_parameters; using Scalar = Scalar_; using Transformation = typename Base::Transformation; using Point = typename Base::Point; using HomogeneousPoint = typename Base::HomogeneousPoint; using Tangent = typename Base::Tangent; using Adjoint = typename Base::Adjoint; using SO2Member = SO2; using TranslationMember = Vector2; using Base::operator=; EIGEN_MAKE_ALIGNED_OPERATOR_NEW /// Default constructor initializes rigid body motion to the identity. /// SOPHUS_FUNC SE2(); /// Copy constructor /// SOPHUS_FUNC SE2(SE2 const& other) = default; /// Copy-like constructor from OtherDerived /// template SOPHUS_FUNC SE2(SE2Base const& other) : so2_(other.so2()), translation_(other.translation()) { static_assert(std::is_same::value, "must be same Scalar type"); } /// Constructor from SO3 and translation vector /// template SOPHUS_FUNC SE2(SO2Base const& so2, Eigen::MatrixBase const& translation) : so2_(so2), translation_(translation) { static_assert(std::is_same::value, "must be same Scalar type"); static_assert(std::is_same::value, "must be same Scalar type"); } /// Constructor from rotation matrix and translation vector /// /// Precondition: Rotation matrix needs to be orthogonal with determinant /// of 1. /// SOPHUS_FUNC SE2(typename SO2::Transformation const& rotation_matrix, Point const& translation) : so2_(rotation_matrix), translation_(translation) {} /// Constructor from rotation angle and translation vector. /// SOPHUS_FUNC SE2(Scalar const& theta, Point const& translation) : so2_(theta), translation_(translation) {} /// Constructor from complex number and translation vector /// /// Precondition: ``complex`` must not be close to zero. SOPHUS_FUNC SE2(Vector2 const& complex, Point const& translation) : so2_(complex), translation_(translation) {} /// Constructor from 3x3 matrix /// /// Precondition: Rotation matrix needs to be orthogonal with determinant /// of 1. The last row must be ``(0, 0, 1)``. /// SOPHUS_FUNC explicit SE2(Transformation const& T) : so2_(T.template topLeftCorner<2, 2>().eval()), translation_(T.template block<2, 1>(0, 2)) {} /// This provides unsafe read/write access to internal data. SO(2) is /// represented by a complex number (two parameters). When using direct write /// access, the user needs to take care of that the complex number stays /// normalized. /// SOPHUS_FUNC Scalar* data() { // so2_ and translation_ are layed out sequentially with no padding return so2_.data(); } /// Const version of data() above. /// SOPHUS_FUNC Scalar const* data() const { /// so2_ and translation_ are layed out sequentially with no padding return so2_.data(); } /// Accessor of SO3 /// SOPHUS_FUNC SO2Member& so2() { return so2_; } /// Mutator of SO3 /// SOPHUS_FUNC SO2Member const& so2() const { return so2_; } /// Mutator of translation vector /// SOPHUS_FUNC TranslationMember& translation() { return translation_; } /// Accessor of translation vector /// SOPHUS_FUNC TranslationMember const& translation() const { return translation_; } /// Returns derivative of exp(x) wrt. x. /// SOPHUS_FUNC static Sophus::Matrix Dx_exp_x( Tangent const& upsilon_theta) { using std::abs; using std::cos; using std::pow; using std::sin; Sophus::Matrix J; Sophus::Vector upsilon = upsilon_theta.template head<2>(); Scalar theta = upsilon_theta[2]; if (abs(theta) < Constants::epsilon()) { Scalar const o(0); Scalar const i(1); // clang-format off J << o, o, o, o, o, i, i, o, -Scalar(0.5) * upsilon[1], o, i, Scalar(0.5) * upsilon[0]; // clang-format on return J; } Scalar const c0 = sin(theta); Scalar const c1 = cos(theta); Scalar const c2 = 1.0 / theta; Scalar const c3 = c0 * c2; Scalar const c4 = -c1 + Scalar(1); Scalar const c5 = c2 * c4; Scalar const c6 = c1 * c2; Scalar const c7 = pow(theta, -2); Scalar const c8 = c0 * c7; Scalar const c9 = c4 * c7; Scalar const o = Scalar(0); J(0, 0) = o; J(0, 1) = o; J(0, 2) = -c0; J(1, 0) = o; J(1, 1) = o; J(1, 2) = c1; J(2, 0) = c3; J(2, 1) = -c5; J(2, 2) = -c3 * upsilon[1] + c6 * upsilon[0] - c8 * upsilon[0] + c9 * upsilon[1]; J(3, 0) = c5; J(3, 1) = c3; J(3, 2) = c3 * upsilon[0] + c6 * upsilon[1] - c8 * upsilon[1] - c9 * upsilon[0]; return J; } /// Returns derivative of exp(x) wrt. x_i at x=0. /// SOPHUS_FUNC static Sophus::Matrix Dx_exp_x_at_0() { Sophus::Matrix J; Scalar const o(0); Scalar const i(1); // clang-format off J << o, o, o, o, o, i, i, o, o, o, i, o; // clang-format on return J; } /// Returns derivative of exp(x).matrix() wrt. ``x_i at x=0``. /// SOPHUS_FUNC static Transformation Dxi_exp_x_matrix_at_0(int i) { return generator(i); } /// Group exponential /// /// This functions takes in an element of tangent space (= twist ``a``) and /// returns the corresponding element of the group SE(2). /// /// The first two components of ``a`` represent the translational part /// ``upsilon`` in the tangent space of SE(2), while the last three components /// of ``a`` represents the rotation vector ``omega``. /// To be more specific, this function computes ``expmat(hat(a))`` with /// ``expmat(.)`` being the matrix exponential and ``hat(.)`` the hat-operator /// of SE(2), see below. /// SOPHUS_FUNC static SE2 exp(Tangent const& a) { Scalar theta = a[2]; SO2 so2 = SO2::exp(theta); Scalar sin_theta_by_theta; Scalar one_minus_cos_theta_by_theta; using std::abs; if (abs(theta) < Constants::epsilon()) { Scalar theta_sq = theta * theta; sin_theta_by_theta = Scalar(1.) - Scalar(1. / 6.) * theta_sq; one_minus_cos_theta_by_theta = Scalar(0.5) * theta - Scalar(1. / 24.) * theta * theta_sq; } else { sin_theta_by_theta = so2.unit_complex().y() / theta; one_minus_cos_theta_by_theta = (Scalar(1.) - so2.unit_complex().x()) / theta; } Vector2 trans( sin_theta_by_theta * a[0] - one_minus_cos_theta_by_theta * a[1], one_minus_cos_theta_by_theta * a[0] + sin_theta_by_theta * a[1]); return SE2(so2, trans); } /// Returns closest SE3 given arbitrary 4x4 matrix. /// template static SOPHUS_FUNC enable_if_t::value, SE2> fitToSE2(Matrix3 const& T) { return SE2(SO2::fitToSO2(T.template block<2, 2>(0, 0)), T.template block<2, 1>(0, 2)); } /// Returns the ith infinitesimal generators of SE(2). /// /// The infinitesimal generators of SE(2) are: /// /// ``` /// | 0 0 1 | /// G_0 = | 0 0 0 | /// | 0 0 0 | /// /// | 0 0 0 | /// G_1 = | 0 0 1 | /// | 0 0 0 | /// /// | 0 -1 0 | /// G_2 = | 1 0 0 | /// | 0 0 0 | /// ``` /// /// Precondition: ``i`` must be in 0, 1 or 2. /// SOPHUS_FUNC static Transformation generator(int i) { SOPHUS_ENSURE(i >= 0 || i <= 2, "i should be in range [0,2]."); Tangent e; e.setZero(); e[i] = Scalar(1); return hat(e); } /// hat-operator /// /// It takes in the 3-vector representation (= twist) and returns the /// corresponding matrix representation of Lie algebra element. /// /// Formally, the hat()-operator of SE(3) is defined as /// /// ``hat(.): R^3 -> R^{3x33}, hat(a) = sum_i a_i * G_i`` (for i=0,1,2) /// /// with ``G_i`` being the ith infinitesimal generator of SE(2). /// /// The corresponding inverse is the vee()-operator, see below. /// SOPHUS_FUNC static Transformation hat(Tangent const& a) { Transformation Omega; Omega.setZero(); Omega.template topLeftCorner<2, 2>() = SO2::hat(a[2]); Omega.col(2).template head<2>() = a.template head<2>(); return Omega; } /// Lie bracket /// /// It computes the Lie bracket of SE(2). To be more specific, it computes /// /// ``[omega_1, omega_2]_se2 := vee([hat(omega_1), hat(omega_2)])`` /// /// with ``[A,B] := AB-BA`` being the matrix commutator, ``hat(.)`` the /// hat()-operator and ``vee(.)`` the vee()-operator of SE(2). /// SOPHUS_FUNC static Tangent lieBracket(Tangent const& a, Tangent const& b) { Vector2 upsilon1 = a.template head<2>(); Vector2 upsilon2 = b.template head<2>(); Scalar theta1 = a[2]; Scalar theta2 = b[2]; return Tangent(-theta1 * upsilon2[1] + theta2 * upsilon1[1], theta1 * upsilon2[0] - theta2 * upsilon1[0], Scalar(0)); } /// Construct pure rotation. /// static SOPHUS_FUNC SE2 rot(Scalar const& x) { return SE2(SO2(x), Sophus::Vector2::Zero()); } /// Draw uniform sample from SE(2) manifold. /// /// Translations are drawn component-wise from the range [-1, 1]. /// template static SE2 sampleUniform(UniformRandomBitGenerator& generator) { std::uniform_real_distribution uniform(Scalar(-1), Scalar(1)); return SE2(SO2::sampleUniform(generator), Vector2(uniform(generator), uniform(generator))); } /// Construct a translation only SE(2) instance. /// template static SOPHUS_FUNC SE2 trans(T0 const& x, T1 const& y) { return SE2(SO2(), Vector2(x, y)); } static SOPHUS_FUNC SE2 trans(Vector2 const& xy) { return SE2(SO2(), xy); } /// Construct x-axis translation. /// static SOPHUS_FUNC SE2 transX(Scalar const& x) { return SE2::trans(x, Scalar(0)); } /// Construct y-axis translation. /// static SOPHUS_FUNC SE2 transY(Scalar const& y) { return SE2::trans(Scalar(0), y); } /// vee-operator /// /// It takes the 3x3-matrix representation ``Omega`` and maps it to the /// corresponding 3-vector representation of Lie algebra. /// /// This is the inverse of the hat()-operator, see above. /// /// Precondition: ``Omega`` must have the following structure: /// /// | 0 -d a | /// | d 0 b | /// | 0 0 0 | /// SOPHUS_FUNC static Tangent vee(Transformation const& Omega) { SOPHUS_ENSURE( Omega.row(2).template lpNorm<1>() < Constants::epsilon(), "Omega: \n%", Omega); Tangent upsilon_omega; upsilon_omega.template head<2>() = Omega.col(2).template head<2>(); upsilon_omega[2] = SO2::vee(Omega.template topLeftCorner<2, 2>()); return upsilon_omega; } protected: SO2Member so2_; TranslationMember translation_; }; template SE2::SE2() : translation_(TranslationMember::Zero()) { static_assert(std::is_standard_layout::value, "Assume standard layout for the use of offsetof check below."); static_assert( offsetof(SE2, so2_) + sizeof(Scalar) * SO2::num_parameters == offsetof(SE2, translation_), "This class assumes packed storage and hence will only work " "correctly depending on the compiler (options) - in " "particular when using [this->data(), this-data() + " "num_parameters] to access the raw data in a contiguous fashion."); } } // namespace Sophus namespace Eigen { /// Specialization of Eigen::Map for ``SE2``; derived from SE2Base. /// /// Allows us to wrap SE2 objects around POD array. template class Map, Options> : public Sophus::SE2Base, Options>> { public: using Base = Sophus::SE2Base, Options>>; using Scalar = Scalar_; using Transformation = typename Base::Transformation; using Point = typename Base::Point; using HomogeneousPoint = typename Base::HomogeneousPoint; using Tangent = typename Base::Tangent; using Adjoint = typename Base::Adjoint; using Base::operator=; using Base::operator*=; using Base::operator*; SOPHUS_FUNC Map(Scalar* coeffs) : so2_(coeffs), translation_(coeffs + Sophus::SO2::num_parameters) {} /// Mutator of SO3 /// SOPHUS_FUNC Map, Options>& so2() { return so2_; } /// Accessor of SO3 /// SOPHUS_FUNC Map, Options> const& so2() const { return so2_; } /// Mutator of translation vector /// SOPHUS_FUNC Map, Options>& translation() { return translation_; } /// Accessor of translation vector /// SOPHUS_FUNC Map, Options> const& translation() const { return translation_; } protected: Map, Options> so2_; Map, Options> translation_; }; /// Specialization of Eigen::Map for ``SE2 const``; derived from SE2Base. /// /// Allows us to wrap SE2 objects around POD array. template class Map const, Options> : public Sophus::SE2Base const, Options>> { public: using Base = Sophus::SE2Base const, Options>>; using Scalar = Scalar_; using Transformation = typename Base::Transformation; using Point = typename Base::Point; using HomogeneousPoint = typename Base::HomogeneousPoint; using Tangent = typename Base::Tangent; using Adjoint = typename Base::Adjoint; using Base::operator*=; using Base::operator*; SOPHUS_FUNC Map(Scalar const* coeffs) : so2_(coeffs), translation_(coeffs + Sophus::SO2::num_parameters) {} /// Accessor of SO3 /// SOPHUS_FUNC Map const, Options> const& so2() const { return so2_; } /// Accessor of translation vector /// SOPHUS_FUNC Map const, Options> const& translation() const { return translation_; } protected: Map const, Options> const so2_; Map const, Options> const translation_; }; } // namespace Eigen #endif