Go to the documentation of this file.
   10 template <
class Scalar_, 
int Options = 0>
 
   19 template <
class Scalar_, 
int Options>
 
   20 struct traits<
Sophus::SE3<Scalar_, Options>> {
 
   26 template <
class Scalar_, 
int Options>
 
   27 struct traits<Map<
Sophus::SE3<Scalar_>, Options>>
 
   28     : traits<Sophus::SE3<Scalar_, Options>> {
 
   31   using SO3Type = Map<Sophus::SO3<Scalar>, Options>;
 
   34 template <
class Scalar_, 
int Options>
 
   35 struct traits<Map<
Sophus::SE3<Scalar_> const, Options>>
 
   36     : traits<Sophus::SE3<Scalar_, Options> const> {
 
   39   using SO3Type = Map<Sophus::SO3<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 SO3Type = 
typename Eigen::internal::traits<Derived>::SO3Type;
 
   67   static int constexpr 
DoF = 6;
 
   72   static int constexpr 
N = 4;
 
   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>
 
  106     res.block(0, 0, 3, 3) = R;
 
  107     res.block(3, 3, 3, 3) = R;
 
  127   template <
class NewScalarType>
 
  233     auto omega_and_theta = 
so3().logAndTheta();
 
  234     Scalar theta = omega_and_theta.theta;
 
  235     upsilon_omega.template tail<3>() = omega_and_theta.tangent;
 
  242                                     Scalar(1. / 12.) * (Omega * Omega);
 
  244       upsilon_omega.template head<3>() = V_inv * 
translation();
 
  251             theta * cos(half_theta) / (
Scalar(2) * sin(half_theta))) /
 
  252                (theta * theta) * (Omega * Omega));
 
  253       upsilon_omega.template head<3>() = V_inv * 
translation();
 
  255     return upsilon_omega;
 
  277     homogenious_matrix.template topLeftCorner<3, 4>() = 
matrix3x4();
 
  278     homogenious_matrix.row(3) =
 
  280     return homogenious_matrix;
 
  298   template <
class OtherDerived>
 
  307   template <
typename OtherDerived>
 
  322   template <
typename PointDerived,
 
  323             typename = 
typename std::enable_if<
 
  326       Eigen::MatrixBase<PointDerived> 
const& p)
 const {
 
  332   template <
typename HPointDerived,
 
  333             typename = 
typename std::enable_if<
 
  336       Eigen::MatrixBase<HPointDerived> 
const& p)
 const {
 
  351     return Line((*
this) * l.origin(), 
so3() * l.direction());
 
  357   template <
typename OtherDerived,
 
  358             typename = 
typename std::enable_if<
 
  359                 std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
 
  361     *
static_cast<Derived*
>(
this) = *
this * other;
 
  376     return static_cast<const Derived*
>(
this)->
so3();
 
  384     so3().setQuaternion(quat);
 
  395     so3().setQuaternion(Eigen::Quaternion<Scalar>(R));
 
  418     return static_cast<Derived const*
>(
this)->
translation();
 
  424     return this->
so3().unit_quaternion();
 
  429 template <
class Scalar_, 
int Options>
 
  430 class SE3 : 
public SE3Base<SE3<Scalar_, Options>> {
 
  446   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  458   template <
class OtherDerived>
 
  461     static_assert(std::is_same<typename OtherDerived::Scalar, Scalar>::value,
 
  462                   "must be same Scalar type");
 
  467   template <
class OtherDerived, 
class D>
 
  471     static_assert(std::is_same<typename OtherDerived::Scalar, Scalar>::value,
 
  472                   "must be same Scalar type");
 
  473     static_assert(std::is_same<typename D::Scalar, Scalar>::value,
 
  474                   "must be same Scalar type");
 
  500       : 
so3_(T.template topLeftCorner<3, 3>()),
 
  505                   "Last row is not (0,0,0,1), but (%).", T.row(3));
 
  546       Tangent const& upsilon_omega) {
 
  555     Scalar const c0 = omega[0] * omega[0];
 
  556     Scalar const c1 = omega[1] * omega[1];
 
  557     Scalar const c2 = omega[2] * omega[2];
 
  569       J << o, o, o, h, o, o, o, o, o, o, h, o, o, o, o, o, o, h, o, o, o, o, o,
 
  570           o, i, o, o, o, uz, -uy, o, i, o, -uz, o, ux, o, o, i, uy, -ux, o;
 
  704     J(5, 3) = upsilon[0] * (
c53 + 
c91) +
 
  719     J(6, 5) = upsilon[0] * (
c71 + 
c80) + upsilon[1] * (
c91 + 
c94) +
 
  735     J << o, o, o, h, o, o, o,
 
  778       Scalar theta_sq = theta * theta;
 
  780            (
Scalar(1) - cos(theta)) / (theta_sq)*Omega +
 
  781            (theta - sin(theta)) / (theta_sq * theta) * Omega_sq);
 
  788   template <
class S = Scalar>
 
  792                T.template block<3, 1>(0, 3));
 
  834     SOPHUS_ENSURE(i >= 0 && i <= 5, 
"i should be in range [0,5].");
 
  857     Omega.template topLeftCorner<3, 3>() =
 
  859     Omega.col(3).template head<3>() = a.template head<3>();
 
  879     res.template head<3>() = omega1.cross(upsilon2) + upsilon1.cross(omega2);
 
  880     res.template tail<3>() = omega1.cross(omega2);
 
  907   template <
class UniformRandomBitGenerator>
 
  909     std::uniform_real_distribution<Scalar> uniform(
Scalar(-1), 
Scalar(1));
 
  917   template <
class T0, 
class T1, 
class T2>
 
  960     upsilon_omega.template head<3>() = Omega.col(3).template head<3>();
 
  961     upsilon_omega.template tail<3>() =
 
  963     return upsilon_omega;
 
  971 template <
class Scalar, 
int Options>
 
  973   static_assert(std::is_standard_layout<SE3>::value,
 
  974                 "Assume standard layout for the use of offsetof check below.");
 
  978       "This class assumes packed storage and hence will only work " 
  979       "correctly depending on the compiler (options) - in " 
  980       "particular when using [this->data(), this-data() + " 
  981       "num_parameters] to access the raw data in a contiguous fashion.");
 
  990 template <
class Scalar_, 
int Options>
 
 1003   EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Map);
 
 1006   using Base::operator*=;
 
 1007   using Base::operator*;
 
 1011         translation_(coeffs + 
Sophus::SO3<
Scalar>::num_parameters) {}
 
 1026     return translation_;
 
 1032     return translation_;
 
 1036   Map<Sophus::SO3<Scalar>, Options> 
so3_;
 
 1043 template <
class Scalar_, 
int Options>
 
 1044 class Map<
Sophus::SE3<Scalar_> const, Options>
 
 1055   using Base::operator*=;
 
 1056   using Base::operator*;
 
 1060         translation_(coeffs + 
Sophus::SO3<
Scalar>::num_parameters) {}
 
 1072     return translation_;
 
 1076   Map<Sophus::SO3<Scalar> 
const, Options> 
const so3_;
 
  
const Map< Sophus::SO3< Scalar > const, Options > so3_
SOPHUS_FUNC void setRotationMatrix(Matrix3< Scalar > const &R)
static SOPHUS_FUNC SE3 rotY(Scalar const &y)
SOPHUS_FUNC SO3Member & so3()
SOPHUS_FUNC Map< Sophus::SO3< Scalar >, Options > & so3()
SOPHUS_FUNC SE3Base< Derived > & operator*=(SE3Base< OtherDerived > const &other)
SOPHUS_FUNC SE3Base & operator=(SE3Base const &other)=default
Sophus::Vector3< Scalar, Options > TranslationType
typename Base::Transformation Transformation
SOPHUS_FUNC Map(Scalar const *coeffs)
typename Base::Adjoint Adjoint
static constexpr int N
Group transformations are 4x4 matrices.
SOPHUS_FUNC SE3< Scalar > inverse() const
SOPHUS_FUNC Scalar * data()
static SOPHUS_FUNC Tangent vee(Transformation const &Omega)
SOPHUS_FUNC Map(Scalar *coeffs)
Map< Sophus::SO3< Scalar > const, Options > SO3Type
Vector< Scalar, 3, Options > Vector3
SOPHUS_FUNC SE3(SO3Base< OtherDerived > const &so3, Eigen::MatrixBase< D > const &translation)
SOPHUS_FUNC SE3(Eigen::Quaternion< Scalar > const &quaternion, Point const &translation)
typename Base::Tangent Tangent
typename std::enable_if< B, T >::type enable_if_t
#define SOPHUS_ENSURE(expr,...)
typename Base::Tangent Tangent
Matrix< Scalar, N, N > Transformation
Vector3< ReturnScalar< PointDerived > > PointProduct
static SE3 sampleUniform(UniformRandomBitGenerator &generator)
Map< Sophus::Vector3< Scalar > const, Options > TranslationType
static SOPHUS_FUNC SE3< Scalar > exp(Tangent const &a)
SOPHUS_FUNC SE3(Matrix4< Scalar > const &T)
typename Base::Adjoint Adjoint
static SOPHUS_FUNC Tangent lieBracket(Tangent const &a, Tangent const &b)
SOPHUS_FUNC Line operator*(Line const &l) const
SOPHUS_FUNC void setQuaternion(Eigen::Quaternion< Scalar > const &quat)
ParametrizedLine< Scalar, 3, Options > ParametrizedLine3
typename Base::Tangent Tangent
static SOPHUS_FUNC Sophus::Matrix< Scalar, num_parameters, DoF > Dx_exp_x(Tangent const &upsilon_omega)
SOPHUS_FUNC Map< Sophus::SO3< Scalar > const, Options > const  & so3() const
SOPHUS_FUNC SO3Type const  & so3() const
SOPHUS_FUNC QuaternionType const  & unit_quaternion() const
SOPHUS_FUNC SE3Base< Derived > & operator=(SE3Base< OtherDerived > const &other)
static SOPHUS_FUNC Transformation Dxi_exp_x_matrix_at_0(int i)
static SOPHUS_FUNC SE3 rotZ(Scalar const &z)
typename Base::HomogeneousPoint HomogeneousPoint
Vector4< Scalar > HomogeneousPoint
SOPHUS_FUNC HomogeneousPointProduct< HPointDerived > operator*(Eigen::MatrixBase< HPointDerived > const &p) const
SOPHUS_FUNC void normalize()
typename Eigen::internal::traits< Map< Sophus::SE3< Scalar_ >, Options > >::TranslationType TranslationType
SOPHUS_FUNC Adjoint Adj() const
Eigen::Matrix< Scalar, M, N > Matrix
static SOPHUS_FUNC Transformation hat(Tangent const &omega)
SOPHUS_FUNC SE3(Matrix3< Scalar > const &rotation_matrix, Point const &translation)
SOPHUS_FUNC Tangent log() const
TranslationMember translation_
SOPHUS_FUNC bool isOrthogonal(Eigen::MatrixBase< D > const &R)
SOPHUS_FUNC SE3Product< OtherDerived > operator*(SE3Base< OtherDerived > const &other) const
typename Base::Point Point
Vector4< ReturnScalar< HPointDerived > > HomogeneousPointProduct
SOPHUS_FUNC Sophus::Vector< Scalar, num_parameters > params() const
typename Base::Adjoint Adjoint
SOPHUS_FUNC Scalar const  * data() const
static SOPHUS_FUNC Sophus::Matrix< Scalar, num_parameters, DoF > Dx_exp_x_at_0()
typename Base::Transformation Transformation
SOPHUS_FUNC TranslationMember & translation()
SE3 using default storage; derived from SE3Base.
typename Base::Transformation Transformation
SOPHUS_FUNC Map< Sophus::Vector3< Scalar > const, Options > const  & translation() const
Map< Sophus::Vector3< Scalar >, Options > translation_
SOPHUS_FUNC SO3Member const  & so3() const
static SOPHUS_FUNC SE3 trans(T0 const &x, T1 const &y, T2 const &z)
static SOPHUS_FUNC enable_if_t< std::is_floating_point< S >::value, SE3 > fitToSE3(Matrix4< Scalar > const &T)
SOPHUS_FUNC Transformation matrix() const
static SOPHUS_FUNC SE3 transZ(Scalar const &z)
static SOPHUS_FUNC SE3 transX(Scalar const &x)
ParametrizedLine3< Scalar > Line
SOPHUS_FUNC TranslationType const  & translation() const
static constexpr int num_parameters
SOPHUS_FUNC SE3(SE3Base< OtherDerived > const &other)
auto squaredNorm(T const &p) -> decltype(details::SquaredNorm< T >::impl(p))
Matrix< Scalar, 3, 3 > Matrix3
typename Base::HomogeneousPoint HomogeneousPoint
typename Base::Point Point
static SOPHUS_FUNC SE3 trans(Vector3< Scalar > const &xyz)
Vector< Scalar, 4 > Vector4
typename SO3Type::QuaternionType QuaternionType
typename Base::HomogeneousPoint HomogeneousPoint
Eigen::Matrix< Scalar, M, 1, Options > Vector
SOPHUS_FUNC Map< Sophus::SO3< Scalar >, Options > const  & so3() const
Map< Sophus::SO3< Scalar >, Options > so3_
SOPHUS_FUNC TranslationType & translation()
static SOPHUS_FUNC Transformation hat(Tangent const &a)
static SOPHUS_FUNC Tangent vee(Transformation const &Omega)
static SOPHUS_FUNC SO3< Scalar > expAndTheta(Tangent const &omega, Scalar *theta)
Vector3< Scalar, Options > TranslationMember
Matrix< Scalar, DoF, DoF > Adjoint
SOPHUS_FUNC TranslationMember const  & translation() const
SOPHUS_FUNC Matrix< Scalar, 3, 4 > matrix3x4() const
static SOPHUS_FUNC SE3 rotX(Scalar const &x)
SOPHUS_FUNC Matrix3< Scalar > rotationMatrix() const
SOPHUS_FUNC PointProduct< PointDerived > operator*(Eigen::MatrixBase< PointDerived > const &p) const
SOPHUS_FUNC Map< Sophus::Vector3< Scalar, Options > > & translation()
static constexpr int num_parameters
static SOPHUS_FUNC SE3 transY(Scalar const &y)
SOPHUS_FUNC Matrix< Scalar, num_parameters, DoF > Dx_this_mul_exp_x_at_0() const
SOPHUS_FUNC SE3< NewScalarType > cast() const
Matrix< Scalar, 4, 4 > Matrix4
typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar >::ReturnType ReturnScalar
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SOPHUS_FUNC SE3()
static SOPHUS_FUNC Transformation generator(int i)
const Map< Sophus::Vector3< Scalar > const, Options > translation_
SOPHUS_FUNC SO3Type & so3()
SOPHUS_FUNC Map< Sophus::Vector3< Scalar, Options > > const  & translation() const
typename Eigen::internal::traits< Map< Sophus::SE3< Scalar_ >, Options > >::SO3Type SO3Type
typename Eigen::internal::traits< Map< Sophus::SE3< Scalar_ >, Options > >::Scalar Scalar
typename Base::Point Point
Vector< Scalar, DoF > Tangent
sophus
Author(s): Hauke Strasdat
autogenerated on Wed Mar 2 2022 01:01:48