.. _program_listing_file_sophus_sim2.hpp: Program Listing for File sim2.hpp ================================= |exhale_lsh| :ref:`Return to documentation for file ` (``sophus/sim2.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp #pragma once #include "rxso2.hpp" #include "sim_details.hpp" namespace Sophus { template class Sim2; using Sim2d = Sim2; using Sim2f = Sim2; } // namespace Sophus namespace Eigen { namespace internal { template struct traits> { using Scalar = Scalar_; using TranslationType = Sophus::Vector2; using RxSO2Type = Sophus::RxSO2; }; template struct traits, Options>> : traits> { using Scalar = Scalar_; using TranslationType = Map, Options>; using RxSO2Type = Map, Options>; }; template struct traits const, Options>> : traits const> { using Scalar = Scalar_; using TranslationType = Map const, Options>; using RxSO2Type = Map const, Options>; }; } // namespace internal } // namespace Eigen namespace Sophus { template class Sim2Base { public: using Scalar = typename Eigen::internal::traits::Scalar; using TranslationType = typename Eigen::internal::traits::TranslationType; using RxSO2Type = typename Eigen::internal::traits::RxSO2Type; static int constexpr DoF = 4; static int constexpr num_parameters = 4; static int constexpr N = 3; static int constexpr Dim = 2; using Transformation = Matrix; using Point = Vector2; using HomogeneousPoint = Vector3; using Line = ParametrizedLine2; using Hyperplane = Hyperplane2; using Tangent = Vector; using Adjoint = Matrix; template using ReturnScalar = typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar>::ReturnType; template using Sim2Product = Sim2>; template using PointProduct = Vector2>; template using HomogeneousPointProduct = Vector3>; SOPHUS_FUNC Adjoint Adj() const { Adjoint res; res.setZero(); res.template block<2, 2>(0, 0) = rxso2().matrix(); res(0, 2) = translation()[1]; res(1, 2) = -translation()[0]; res.template block<2, 1>(0, 3) = -translation(); res(2, 2) = Scalar(1); res(3, 3) = Scalar(1); return res; } template SOPHUS_FUNC Sim2 cast() const { return Sim2(rxso2().template cast(), translation().template cast()); } SOPHUS_FUNC Sim2 inverse() const { RxSO2 invR = rxso2().inverse(); return Sim2(invR, invR * (translation() * Scalar(-1))); } SOPHUS_FUNC Tangent log() const { Tangent res; Vector2 const theta_sigma = rxso2().log(); Scalar const theta = theta_sigma[0]; Scalar const sigma = theta_sigma[1]; Matrix2 const Omega = SO2::hat(theta); Matrix2 const W_inv = details::calcWInv(Omega, theta, sigma, scale()); res.segment(0, 2) = W_inv * translation(); res[2] = theta; res[3] = sigma; return res; } SOPHUS_FUNC Transformation matrix() const { Transformation homogeneous_matrix; homogeneous_matrix.template topLeftCorner<2, 3>() = matrix2x3(); homogeneous_matrix.row(2) = Matrix(Scalar(0), Scalar(0), Scalar(1)); return homogeneous_matrix; } SOPHUS_FUNC Matrix matrix2x3() const { Matrix matrix; matrix.template topLeftCorner<2, 2>() = rxso2().matrix(); matrix.col(2) = translation(); return matrix; } template SOPHUS_FUNC Sim2Base& operator=( Sim2Base const& other) { rxso2() = other.rxso2(); translation() = other.translation(); return *this; } template SOPHUS_FUNC Sim2Product operator*( Sim2Base const& other) const { return Sim2Product( rxso2() * other.rxso2(), translation() + rxso2() * other.translation()); } template ::value>::type> SOPHUS_FUNC PointProduct operator*( Eigen::MatrixBase const& p) const { return rxso2() * p + translation(); } template ::value>::type> SOPHUS_FUNC HomogeneousPointProduct operator*( Eigen::MatrixBase const& p) const { const PointProduct tp = rxso2() * p.template head<2>() + p(2) * translation(); return HomogeneousPointProduct(tp(0), tp(1), p(2)); } SOPHUS_FUNC Line operator*(Line const& l) const { Line rotatedLine = rxso2() * l; return Line(rotatedLine.origin() + translation(), rotatedLine.direction()); } SOPHUS_FUNC Hyperplane operator*(Hyperplane const& p) const { Hyperplane const rotated = rxso2() * p; return Hyperplane(rotated.normal(), rotated.offset() - translation().dot(rotated.normal())); } SOPHUS_FUNC Sophus::Vector params() const { Sophus::Vector p; p << rxso2().params(), translation(); return p; } template >::value>::type> SOPHUS_FUNC Sim2Base& operator*=( Sim2Base const& other) { *static_cast(this) = *this * other; return *this; } SOPHUS_FUNC Matrix Dx_this_mul_exp_x_at_0() const { Matrix J; J.template block<2, 2>(0, 0).setZero(); J.template block<2, 2>(0, 2) = rxso2().Dx_this_mul_exp_x_at_0(); J.template block<2, 2>(2, 2).setZero(); J.template block<2, 2>(2, 0) = rxso2().matrix(); return J; } SOPHUS_FUNC Matrix Dx_log_this_inv_by_x_at_this() const { Matrix J; J.template block<2, 2>(0, 0).setZero(); J.template block<2, 2>(0, 2) = rxso2().inverse().matrix(); J.template block<2, 2>(2, 0) = rxso2().Dx_log_this_inv_by_x_at_this(); J.template block<2, 2>(2, 2).setZero(); return J; } SOPHUS_FUNC void setComplex(Vector2 const& z) { rxso2().setComplex(z); } SOPHUS_FUNC typename Eigen::internal::traits::RxSO2Type::ComplexType const& complex() const { return rxso2().complex(); } SOPHUS_FUNC Matrix2 rotationMatrix() const { return rxso2().rotationMatrix(); } SOPHUS_FUNC RxSO2Type& rxso2() { return static_cast(this)->rxso2(); } SOPHUS_FUNC RxSO2Type const& rxso2() const { return static_cast(this)->rxso2(); } SOPHUS_FUNC Scalar scale() const { return rxso2().scale(); } SOPHUS_FUNC void setRotationMatrix(Matrix2& R) { rxso2().setRotationMatrix(R); } SOPHUS_FUNC void setScale(Scalar const& scale) { rxso2().setScale(scale); } SOPHUS_FUNC void setScaledRotationMatrix(Matrix2 const& sR) { rxso2().setScaledRotationMatrix(sR); } SOPHUS_FUNC TranslationType& translation() { return static_cast(this)->translation(); } SOPHUS_FUNC TranslationType const& translation() const { return static_cast(this)->translation(); } }; template class Sim2 : public Sim2Base> { public: using Base = Sim2Base>; 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 RxSo2Member = RxSO2; using TranslationMember = Vector2; using Base::operator=; SOPHUS_FUNC Sim2& operator=(Sim2 const& other) = default; static int constexpr DoF = Base::DoF; static int constexpr num_parameters = Base::num_parameters; EIGEN_MAKE_ALIGNED_OPERATOR_NEW SOPHUS_FUNC Sim2(); SOPHUS_FUNC Sim2(Sim2 const& other) = default; template SOPHUS_FUNC Sim2(Sim2Base const& other) : rxso2_(other.rxso2()), translation_(other.translation()) { static_assert(std::is_same::value, "must be same Scalar type"); } template SOPHUS_FUNC Sim2(RxSO2Base const& rxso2, Eigen::MatrixBase const& translation) : rxso2_(rxso2), translation_(translation) { static_assert(std::is_same::value, "must be same Scalar type"); static_assert(std::is_same::value, "must be same Scalar type"); } template SOPHUS_FUNC Sim2(Vector2 const& complex_number, Eigen::MatrixBase const& translation) : rxso2_(complex_number), translation_(translation) { static_assert(std::is_same::value, "must be same Scalar type"); } SOPHUS_FUNC explicit Sim2(Matrix const& T) : rxso2_((T.template topLeftCorner<2, 2>()).eval()), translation_(T.template block<2, 1>(0, 2)) {} SOPHUS_FUNC Scalar* data() { // rxso2_ and translation_ are laid out sequentially with no padding return rxso2_.data(); } SOPHUS_FUNC Scalar const* data() const { // rxso2_ and translation_ are laid out sequentially with no padding return rxso2_.data(); } SOPHUS_FUNC RxSo2Member& rxso2() { return rxso2_; } SOPHUS_FUNC RxSo2Member const& rxso2() const { return rxso2_; } SOPHUS_FUNC TranslationMember& translation() { return translation_; } SOPHUS_FUNC TranslationMember const& translation() const { return translation_; } SOPHUS_FUNC static Sophus::Matrix Dx_exp_x_at_0() { Sophus::Matrix J; J.template block<2, 2>(0, 0).setZero(); J.template block<2, 2>(0, 2) = RxSO2::Dx_exp_x_at_0(); J.template block<2, 2>(2, 0).setIdentity(); J.template block<2, 2>(2, 2).setZero(); return J; } SOPHUS_FUNC static Sophus::Matrix Dx_exp_x( const Tangent& a) { static Matrix2 const I = Matrix2::Identity(); static Scalar const one(1.0); Scalar const theta = a[2]; Scalar const sigma = a[3]; Matrix2 const Omega = SO2::hat(theta); Matrix2 const Omega_dtheta = SO2::hat(one); Matrix2 const Omega2 = Omega * Omega; Matrix2 const Omega2_dtheta = Omega_dtheta * Omega + Omega * Omega_dtheta; Matrix2 const W = details::calcW(Omega, theta, sigma); Vector2 const upsilon = a.segment(0, 2); Sophus::Matrix J; J.template block<2, 2>(0, 0).setZero(); J.template block<2, 2>(0, 2) = RxSO2::Dx_exp_x(a.template tail<2>()); J.template block<2, 2>(2, 0) = W; Scalar A, B, C, A_dtheta, B_dtheta, A_dsigma, B_dsigma, C_dsigma; details::calcW_derivatives(theta, sigma, A, B, C, A_dsigma, B_dsigma, C_dsigma, A_dtheta, B_dtheta); J.template block<2, 1>(2, 2) = (A_dtheta * Omega + A * Omega_dtheta + B_dtheta * Omega2 + B * Omega2_dtheta) * upsilon; J.template block<2, 1>(2, 3) = (A_dsigma * Omega + B_dsigma * Omega2 + C_dsigma * I) * upsilon; return J; } SOPHUS_FUNC static Sophus::Matrix Dx_exp_x_times_point_at_0( Point const& point) { Sophus::Matrix J; J << Sophus::Matrix2::Identity(), Sophus::RxSO2::Dx_exp_x_times_point_at_0(point); return J; } SOPHUS_FUNC static Transformation Dxi_exp_x_matrix_at_0(int i) { return generator(i); } SOPHUS_FUNC static Sim2 exp(Tangent const& a) { // For the derivation of the exponential map of Sim(N) see // H. Strasdat, "Local Accuracy and Global Consistency for Efficient Visual // SLAM", PhD thesis, 2012. // http:///hauke.strasdat.net/files/strasdat_thesis_2012.pdf (A.5, pp. 186) Vector2 const upsilon = a.segment(0, 2); Scalar const theta = a[2]; Scalar const sigma = a[3]; RxSO2 rxso2 = RxSO2::exp(a.template tail<2>()); Matrix2 const Omega = SO2::hat(theta); Matrix2 const W = details::calcW(Omega, theta, sigma); return Sim2(rxso2, W * upsilon); } SOPHUS_FUNC static Transformation generator(int i) { SOPHUS_ENSURE(i >= 0 || i <= 3, "i should be in range [0,3]."); Tangent e; e.setZero(); e[i] = Scalar(1); return hat(e); } SOPHUS_FUNC static Transformation hat(Tangent const& a) { Transformation Omega; Omega.template topLeftCorner<2, 2>() = RxSO2::hat(a.template tail<2>()); Omega.col(2).template head<2>() = a.template head<2>(); Omega.row(2).setZero(); return Omega; } SOPHUS_FUNC static Tangent lieBracket(Tangent const& a, Tangent const& b) { Vector2 const upsilon1 = a.template head<2>(); Vector2 const upsilon2 = b.template head<2>(); Scalar const theta1 = a[2]; Scalar const theta2 = b[2]; Scalar const sigma1 = a[3]; Scalar const sigma2 = b[3]; Tangent res; res[0] = -theta1 * upsilon2[1] + theta2 * upsilon1[1] + sigma1 * upsilon2[0] - sigma2 * upsilon1[0]; res[1] = theta1 * upsilon2[0] - theta2 * upsilon1[0] + sigma1 * upsilon2[1] - sigma2 * upsilon1[1]; res[2] = Scalar(0); res[3] = Scalar(0); return res; } template static Sim2 sampleUniform(UniformRandomBitGenerator& generator) { std::uniform_real_distribution uniform(Scalar(-1), Scalar(1)); return Sim2(RxSO2::sampleUniform(generator), Vector2(uniform(generator), uniform(generator))); } SOPHUS_FUNC static Tangent vee(Transformation const& Omega) { Tangent upsilon_omega_sigma; upsilon_omega_sigma.template head<2>() = Omega.col(2).template head<2>(); upsilon_omega_sigma.template tail<2>() = RxSO2::vee(Omega.template topLeftCorner<2, 2>()); return upsilon_omega_sigma; } protected: RxSo2Member rxso2_; TranslationMember translation_; }; template SOPHUS_FUNC Sim2::Sim2() : translation_(TranslationMember::Zero()) { static_assert(std::is_standard_layout::value, "Assume standard layout for the use of offset of check below."); static_assert( offsetof(Sim2, rxso2_) + sizeof(Scalar) * RxSO2::num_parameters == offsetof(Sim2, 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 { template class Map, Options> : public Sophus::Sim2Base, Options>> { public: using Base = Sophus::Sim2Base, 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 explicit Map(Scalar* coeffs) : rxso2_(coeffs), translation_(coeffs + Sophus::RxSO2::num_parameters) {} SOPHUS_FUNC Map, Options>& rxso2() { return rxso2_; } SOPHUS_FUNC Map, Options> const& rxso2() const { return rxso2_; } SOPHUS_FUNC Map, Options>& translation() { return translation_; } SOPHUS_FUNC Map, Options> const& translation() const { return translation_; } protected: Map, Options> rxso2_; Map, Options> translation_; }; template class Map const, Options> : public Sophus::Sim2Base const, Options>> { public: using Base = Sophus::Sim2Base 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 explicit Map(Scalar const* coeffs) : rxso2_(coeffs), translation_(coeffs + Sophus::RxSO2::num_parameters) {} SOPHUS_FUNC Map const, Options> const& rxso2() const { return rxso2_; } SOPHUS_FUNC Map const, Options> const& translation() const { return translation_; } protected: Map const, Options> const rxso2_; Map const, Options> const translation_; }; } // namespace Eigen