Go to the documentation of this file.
10 template <
class Scalar_,
int Options = 0>
19 template <
class Scalar_,
int Options>
20 struct traits<
Sophus::SE2<Scalar_, Options>> {
26 template <
class Scalar_,
int Options>
27 struct traits<Map<
Sophus::SE2<Scalar_>, Options>>
28 : traits<Sophus::SE2<Scalar_, Options>> {
31 using SO2Type = Map<Sophus::SO2<Scalar>, Options>;
34 template <
class Scalar_,
int Options>
35 struct traits<Map<
Sophus::SE2<Scalar_> const, Options>>
36 : traits<Sophus::SE2<Scalar_, Options> const> {
39 using SO2Type = Map<Sophus::SO2<Scalar>
const, Options>;
57 template <
class Derived>
60 using Scalar =
typename Eigen::internal::traits<Derived>::Scalar;
62 typename Eigen::internal::traits<Derived>::TranslationType;
63 using SO2Type =
typename Eigen::internal::traits<Derived>::SO2Type;
67 static int constexpr
DoF = 3;
72 static int constexpr
N = 3;
84 template <
typename OtherDerived>
85 using ReturnScalar =
typename Eigen::ScalarBinaryOpTraits<
86 Scalar,
typename OtherDerived::Scalar>::ReturnType;
88 template <
typename OtherDerived>
91 template <
typename Po
intDerived>
94 template <
typename HPo
intDerived>
107 res.template topLeftCorner<2, 2>() = R;
115 template <
class NewScalarType>
165 upsilon_theta[2] = theta;
167 Scalar halftheta_by_tan_of_halftheta;
172 halftheta_by_tan_of_halftheta =
175 halftheta_by_tan_of_halftheta = -(halftheta * z.y()) / (real_minus_one);
178 V_inv << halftheta_by_tan_of_halftheta, halftheta, -halftheta,
179 halftheta_by_tan_of_halftheta;
180 upsilon_theta.template head<2>() = V_inv *
translation();
181 return upsilon_theta;
202 homogenious_matrix.template topLeftCorner<2, 3>() =
matrix2x3();
203 homogenious_matrix.row(2) =
205 return homogenious_matrix;
223 template <
class OtherDerived>
232 template <
typename OtherDerived>
247 template <
typename PointDerived,
248 typename =
typename std::enable_if<
251 Eigen::MatrixBase<PointDerived>
const& p)
const {
257 template <
typename HPointDerived,
258 typename =
typename std::enable_if<
261 Eigen::MatrixBase<HPointDerived>
const& p)
const {
276 return Line((*
this) * l.origin(),
so2() * l.direction());
282 template <
typename OtherDerived,
283 typename =
typename std::enable_if<
284 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
286 *
static_cast<Derived*
>(
this) = *
this * other;
304 return so2().matrix();
312 return so2().setComplex(complex);
323 typename SO2Type::ComplexT
const complex(
Scalar(0.5) * (R(0, 0) + R(1, 1)),
324 Scalar(0.5) * (R(1, 0) - R(0, 1)));
325 so2().setComplex(complex);
337 return static_cast<Derived const*
>(
this)->
so2();
351 return static_cast<Derived const*
>(
this)->
translation();
357 typename Eigen::internal::traits<Derived>::SO2Type::ComplexT
const&
359 return so2().unit_complex();
364 template <
class Scalar_,
int Options>
365 class SE2 :
public SE2Base<SE2<Scalar_, Options>> {
380 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
392 template <
class OtherDerived>
395 static_assert(std::is_same<typename OtherDerived::Scalar, Scalar>::value,
396 "must be same Scalar type");
401 template <
class OtherDerived,
class D>
405 static_assert(std::is_same<typename OtherDerived::Scalar, Scalar>::value,
406 "must be same Scalar type");
407 static_assert(std::is_same<typename D::Scalar, Scalar>::value,
408 "must be same Scalar type");
438 :
so2_(T.template topLeftCorner<2, 2>().eval()),
479 Tangent const& upsilon_theta) {
486 Scalar theta = upsilon_theta[2];
493 J << o, o, o, o, o, i, i, o, -
Scalar(0.5) * upsilon[1], o, i,
520 -
c3 * upsilon[1] +
c6 * upsilon[0] -
c8 * upsilon[0] +
c9 * upsilon[1];
524 c3 * upsilon[0] +
c6 * upsilon[1] -
c8 * upsilon[1] -
c9 * upsilon[0];
537 J << o, o, o, o, o, i, i, o, o, o, i, o;
563 Scalar sin_theta_by_theta;
564 Scalar one_minus_cos_theta_by_theta;
568 Scalar theta_sq = theta * theta;
569 sin_theta_by_theta =
Scalar(1.) -
Scalar(1. / 6.) * theta_sq;
570 one_minus_cos_theta_by_theta =
571 Scalar(0.5) * theta -
Scalar(1. / 24.) * theta * theta_sq;
574 one_minus_cos_theta_by_theta =
578 sin_theta_by_theta * a[0] - one_minus_cos_theta_by_theta * a[1],
579 one_minus_cos_theta_by_theta * a[0] + sin_theta_by_theta * a[1]);
585 template <
class S = Scalar>
589 T.template block<2, 1>(0, 2));
613 SOPHUS_ENSURE(i >= 0 || i <= 2,
"i should be in range [0,2].");
637 Omega.col(2).template head<2>() = a.template head<2>();
656 return Tangent(-theta1 * upsilon2[1] + theta2 * upsilon1[1],
657 theta1 * upsilon2[0] - theta2 * upsilon1[0],
Scalar(0));
670 template <
class UniformRandomBitGenerator>
672 std::uniform_real_distribution<Scalar> uniform(
Scalar(-1),
Scalar(1));
679 template <
class T0,
class T1>
716 "Omega: \n%", Omega);
718 upsilon_omega.template head<2>() = Omega.col(2).template head<2>();
720 return upsilon_omega;
728 template <
class Scalar,
int Options>
730 static_assert(std::is_standard_layout<SE2>::value,
731 "Assume standard layout for the use of offsetof check below.");
735 "This class assumes packed storage and hence will only work "
736 "correctly depending on the compiler (options) - in "
737 "particular when using [this->data(), this-data() + "
738 "num_parameters] to access the raw data in a contiguous fashion.");
748 template <
class Scalar_,
int Options>
761 EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Map);
764 using Base::operator*=;
765 using Base::operator*;
770 translation_(coeffs +
Sophus::SO2<
Scalar>::num_parameters) {}
795 Map<Sophus::SO2<Scalar>, Options>
so2_;
802 template <
class Scalar_,
int Options>
803 class Map<
Sophus::SE2<Scalar_> const, Options>
814 using Base::operator*=;
815 using Base::operator*;
819 translation_(coeffs +
Sophus::SO2<
Scalar>::num_parameters) {}
835 Map<Sophus::SO2<Scalar>
const, Options>
const so2_;
Sophus::Vector2< Scalar, Options > TranslationType
SOPHUS_FUNC SE2Base< Derived > & operator=(SE2Base< OtherDerived > const &other)
typename Base::Transformation Transformation
Vector< Scalar, DoF > Tangent
Map< Sophus::SO2< Scalar >, Options > so2_
Vector3< ReturnScalar< HPointDerived > > HomogeneousPointProduct
static SOPHUS_FUNC SE2 trans(Vector2< Scalar > const &xy)
static constexpr int N
Group transformations are 3x3 matrices.
static SOPHUS_FUNC Transformation hat(Tangent const &a)
typename Base::Tangent Tangent
static SOPHUS_FUNC Sophus::Matrix< Scalar, num_parameters, DoF > Dx_exp_x_at_0()
SOPHUS_FUNC Map< Sophus::Vector2< Scalar >, Options > const & translation() const
SOPHUS_FUNC Map< Sophus::SO2< Scalar > const, Options > const & so2() const
typename Base::Tangent Tangent
typename Eigen::internal::traits< Map< Sophus::SE2< Scalar_ >, Options > >::SO2Type SO2Type
Vector< Scalar, 3, Options > Vector3
typename Base::Point Point
static SOPHUS_FUNC SO2< Scalar > exp(Tangent const &theta)
SOPHUS_FUNC TranslationType const & translation() const
SOPHUS_FUNC Map(Scalar const *coeffs)
typename Eigen::internal::traits< Map< Sophus::SE2< Scalar_ >, Options > >::TranslationType TranslationType
SOPHUS_FUNC SO2Type const & so2() const
SOPHUS_FUNC HomogeneousPointProduct< HPointDerived > operator*(Eigen::MatrixBase< HPointDerived > const &p) const
typename std::enable_if< B, T >::type enable_if_t
SOPHUS_FUNC Tangent log() const
SOPHUS_FUNC Matrix< Scalar, 2, 3 > matrix2x3() const
#define SOPHUS_ENSURE(expr,...)
SOPHUS_FUNC Matrix< Scalar, num_parameters, DoF > Dx_this_mul_exp_x_at_0() const
typename Base::HomogeneousPoint HomogeneousPoint
SOPHUS_FUNC SE2Product< OtherDerived > operator*(SE2Base< OtherDerived > const &other) const
typename Base::HomogeneousPoint HomogeneousPoint
Vector< Scalar, 2, Options > Vector2
SOPHUS_FUNC Map< Sophus::Vector2< Scalar > const, Options > const & translation() const
SOPHUS_FUNC void setRotationMatrix(Matrix< Scalar, 2, 2 > const &R)
SOPHUS_FUNC SO2Member & so2()
static constexpr int num_parameters
SOPHUS_FUNC TranslationType & translation()
typename Base::Adjoint Adjoint
SOPHUS_FUNC TranslationMember const & translation() const
SOPHUS_FUNC Map< Sophus::SO2< Scalar >, Options > const & so2() const
static SOPHUS_FUNC Transformation Dxi_exp_x_matrix_at_0(int i)
Matrix< Scalar, DoF, DoF > Adjoint
SOPHUS_FUNC SE2(typename SO2< Scalar >::Transformation const &rotation_matrix, Point const &translation)
SOPHUS_FUNC Sophus::Vector< Scalar, num_parameters > params() const
typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar >::ReturnType ReturnScalar
static SOPHUS_FUNC Tangent lieBracket(Tangent const &a, Tangent const &b)
static SOPHUS_FUNC Tangent vee(Transformation const &Omega)
SOPHUS_FUNC SE2< NewScalarType > cast() const
SOPHUS_FUNC PointProduct< PointDerived > operator*(Eigen::MatrixBase< PointDerived > const &p) const
typename Base::Transformation Transformation
Eigen::Matrix< Scalar, M, N > Matrix
SOPHUS_FUNC SE2(Transformation const &T)
typename Base::Tangent Tangent
ParametrizedLine2< Scalar > Line
SOPHUS_FUNC bool isOrthogonal(Eigen::MatrixBase< D > const &R)
Vector2< Scalar, Options > TranslationMember
SE2 using default storage; derived from SE2Base.
static SOPHUS_FUNC SE2< Scalar > exp(Tangent const &a)
SOPHUS_FUNC SE2(SO2Base< OtherDerived > const &so2, Eigen::MatrixBase< D > const &translation)
Vector2< ReturnScalar< PointDerived > > PointProduct
SOPHUS_FUNC SE2< Scalar > inverse() const
SOPHUS_FUNC void setComplex(Sophus::Vector2< Scalar > const &complex)
Map< Sophus::Vector2< Scalar > const, Options > TranslationType
const Map< Sophus::SO2< Scalar > const, Options > so2_
static SOPHUS_FUNC SE2 transY(Scalar const &y)
SOPHUS_FUNC Adjoint Adj() const
typename Base::Point Point
SOPHUS_FUNC Scalar const * data() const
SOPHUS_FUNC Scalar * data()
SOPHUS_FUNC SO2Type & so2()
static SOPHUS_FUNC SE2 rot(Scalar const &x)
typename Base::Point Point
SOPHUS_FUNC Line operator*(Line const &l) const
SOPHUS_FUNC SE2Base & operator=(SE2Base const &other)=default
static SOPHUS_FUNC Transformation hat(Tangent const &theta)
typename Base::HomogeneousPoint HomogeneousPoint
typename Base::Adjoint Adjoint
Map< Sophus::Vector2< Scalar >, Options > translation_
const Map< Sophus::Vector2< Scalar > const, Options > translation_
Matrix< Scalar, N, N > Transformation
Matrix< Scalar, 3, 3 > Matrix3
SOPHUS_FUNC SE2Base< Derived > & operator*=(SE2Base< OtherDerived > const &other)
SOPHUS_FUNC SE2(Scalar const &theta, Point const &translation)
SOPHUS_FUNC SE2(Vector2< Scalar > const &complex, Point const &translation)
Vector3< Scalar > HomogeneousPoint
SOPHUS_FUNC Matrix< Scalar, 2, 2 > rotationMatrix() const
SOPHUS_FUNC SE2(SE2Base< OtherDerived > const &other)
SOPHUS_FUNC void normalize()
SOPHUS_FUNC Map< Sophus::SO2< Scalar >, Options > & so2()
SOPHUS_FUNC TranslationMember & translation()
SOPHUS_FUNC Transformation matrix() const
static SOPHUS_FUNC enable_if_t< std::is_floating_point< S >::value, SE2 > fitToSE2(Matrix3< Scalar > const &T)
static SOPHUS_FUNC SE2 trans(T0 const &x, T1 const &y)
Eigen::Matrix< Scalar, M, 1, Options > Vector
SOPHUS_FUNC Map(Scalar *coeffs)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SOPHUS_FUNC SE2()
static SOPHUS_FUNC SE2 transX(Scalar const &x)
SOPHUS_FUNC Map< Sophus::Vector2< Scalar >, Options > & translation()
SOPHUS_FUNC SO2Member const & so2() const
typename Base::Transformation Transformation
ParametrizedLine< Scalar, 2, Options > ParametrizedLine2
typename Base::Transformation Transformation
TranslationMember translation_
static SOPHUS_FUNC Tangent vee(Transformation const &Omega)
static constexpr int num_parameters
static SOPHUS_FUNC Transformation generator(int i)
Map< Sophus::SO2< Scalar > const, Options > SO2Type
SOPHUS_FUNC ComplexMember const & unit_complex() const
typename Eigen::internal::traits< Map< Sophus::SE2< Scalar_ >, Options > >::Scalar Scalar
static SOPHUS_FUNC Sophus::Matrix< Scalar, num_parameters, DoF > Dx_exp_x(Tangent const &upsilon_theta)
static SE2 sampleUniform(UniformRandomBitGenerator &generator)
typename Base::Adjoint Adjoint
SOPHUS_FUNC Eigen::internal::traits< Derived >::SO2Type::ComplexT const & unit_complex() const
sophus
Author(s): Hauke Strasdat
autogenerated on Wed Mar 2 2022 01:01:48