Template Class RxSO2Base

Inheritance Relationships

Derived Type

Class Documentation

template<class Derived>
class RxSO2Base

RxSO2 base type - implements RxSO2 class but is storage agnostic

This class implements the group R+ x SO(2), the direct product of the group of positive scalar 2x2 matrices (= isomorph to the positive real numbers) and the two-dimensional special orthogonal group SO(2). Geometrically, it is the group of rotation and scaling in two dimensions. As a matrix groups, R+ x SO(2) consists of matrices of the form s * R where R is an orthogonal matrix with det(R) = 1 and s > 0 being a positive real number. In particular, it has the following form:

| s * cos(theta)  s * -sin(theta) |
| s * sin(theta)  s *  cos(theta) |
where theta being the rotation angle. Internally, it is represented by the first column of the rotation matrix, or in other words by a non-zero complex number.

R+ x SO(2) is not compact, but a commutative group. First it is not compact since the scale factor is not bound. Second it is commutative since sR(alpha, s1) * sR(beta, s2) = sR(beta, s2) * sR(alpha, s1), simply because alpha + beta = beta + alpha and s1 * s2 = s2 * s1 with alpha and beta being rotation angles and s1, s2 being scale factors.

This class has the explicit class invariant that the scale s is not too close to either zero or infinity. Strictly speaking, it must hold that:

complex().norm() >= Constants::epsilon() and 1. / complex().norm() >= Constants::epsilon().

In order to obey this condition, group multiplication is implemented with saturation such that a product always has a scale which is equal or greater this threshold.

Subclassed by Sophus::RxSO2< Scalar, Options >

Public Types

using Scalar = typename Eigen::internal::traits<Derived>::Scalar
using ComplexType = typename Eigen::internal::traits<Derived>::ComplexType
using ComplexTemporaryType = Sophus::Vector2<Scalar, Options>
using Transformation = Matrix<Scalar, N, N>
using Point = Vector2<Scalar>
using HomogeneousPoint = Vector3<Scalar>
using Line = ParametrizedLine2<Scalar>
using Hyperplane = Hyperplane2<Scalar>
using Tangent = Vector<Scalar, DoF>
using Adjoint = Matrix<Scalar, DoF, DoF>
template<typename OtherDerived>
using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<Scalar, typename OtherDerived::Scalar>::ReturnType

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 RxSO2 operations.

template<typename OtherDerived>
using RxSO2Product = RxSO2<ReturnScalar<OtherDerived>>
template<typename PointDerived>
using PointProduct = Vector2<ReturnScalar<PointDerived>>
template<typename HPointDerived>
using HomogeneousPointProduct = Vector3<ReturnScalar<HPointDerived>>

Public Functions

inline SOPHUS_FUNC Adjoint Adj () const

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.

For RxSO(2), it simply returns the identity matrix.

inline SOPHUS_FUNC Scalar angle () const

Returns rotation angle.

template<class NewScalarType> inline SOPHUS_FUNC RxSO2< NewScalarType > cast () const

Returns copy of instance casted to NewScalarType.

inline SOPHUS_FUNC Scalar * data ()

This provides unsafe read/write access to internal data. RxSO(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 is not set close to zero.

Note: The first parameter represents the real part, while the second parameter represent the imaginary part.

inline SOPHUS_FUNC Scalar const  * data () const

Const version of data() above.

inline SOPHUS_FUNC RxSO2< Scalar > inverse () const

Returns group inverse.

inline SOPHUS_FUNC Tangent log () const

Logarithmic map

Computes the logarithm, the inverse of the group exponential which maps element of the group (scaled rotation matrices) to elements of the tangent space (rotation-vector plus logarithm of scale factor).

To be specific, this function computes vee(logmat(.)) with logmat(.) being the matrix logarithm and vee(.) the vee-operator of RxSO2.

inline SOPHUS_FUNC Transformation matrix () const

Returns 2x2 matrix representation of the instance.

For RxSO2, the matrix representation is an scaled orthogonal matrix sR with det(R)=s^2, thus a scaled rotation matrix R with scale s.

template<class OtherDerived> inline SOPHUS_FUNC RxSO2Base< Derived > & operator= (RxSO2Base< OtherDerived > const &other)

Assignment-like operator from OtherDerived.

template<typename OtherDerived> inline SOPHUS_FUNC RxSO2Product< OtherDerived > operator* (RxSO2Base< OtherDerived > const &other) const

Group multiplication, which is rotation concatenation and scale multiplication.

Note: This function performs saturation for products close to zero in order to ensure the class invariant.

template<typename PointDerived, typename = typename std::enable_if<                IsFixedSizeVector<PointDerived, 2>::value>::type> inline SOPHUS_FUNC PointProduct< PointDerived > operator* (Eigen::MatrixBase< PointDerived > const &p) const

Group action on 2-points.

This function rotates a 2 dimensional point p by the SO2 element bar_R_foo (= rotation matrix) and scales it by the scale factor s:

p_bar = s * (bar_R_foo * p_foo).

template<typename HPointDerived, typename = typename std::enable_if<                IsFixedSizeVector<HPointDerived, 3>::value>::type> inline SOPHUS_FUNC HomogeneousPointProduct< HPointDerived > operator* (Eigen::MatrixBase< HPointDerived > const &p) const

Group action on homogeneous 2-points. See above for more details.

inline SOPHUS_FUNC Line operator* (Line const &l) const

Group action on lines.

This function rotates a parameterized line l(t) = o + t * d by the SO2 element and scales it by the scale factor

Origin o is rotated and scaled Direction d is rotated (preserving it’s norm)

inline SOPHUS_FUNC Hyperplane operator* (Hyperplane const &p) const

Group action on hyper-planes.

This function rotates a hyper-plane n.x + d = 0 by the SO2 element and scales offset by the scale factor

Normal vector n is rotated Offset d is scaled

Note that in 2d-case hyper-planes are just another parametrization of lines

template<typename OtherDerived, typename = typename std::enable_if<                std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type> inline SOPHUS_FUNC RxSO2Base< Derived > & operator*= (RxSO2Base< OtherDerived > const &other)

In-place group multiplication. This method is only valid if the return type of the multiplication is compatible with this SO2’s Scalar type.

Note: This function performs saturation for products close to zero in order to ensure the class invariant.

inline SOPHUS_FUNC Matrix< Scalar, num_parameters, DoF > Dx_this_mul_exp_x_at_0 () const

Returns derivative of this * RxSO2::exp(x) wrt. x at x=0

inline SOPHUS_FUNC Matrix< Scalar, DoF, num_parameters > Dx_log_this_inv_by_x_at_this () const

Returns derivative of log(this^{-1} * x) by x at x=this.

inline SOPHUS_FUNC Sophus::Vector< Scalar, num_parameters > params () const

Returns internal parameters of RxSO(2).

It returns (c[0], c[1]), with c being the complex number.

inline SOPHUS_FUNC void setComplex (Vector2< Scalar > const &z)

Sets non-zero complex

Precondition: z must not be close to either zero or infinity.

inline SOPHUS_FUNC ComplexType const  & complex () const

Accessor of complex.

inline SOPHUS_FUNC Transformation rotationMatrix () const

Returns rotation matrix.

inline SOPHUS_FUNC Scalar scale () const

Returns scale.

inline SOPHUS_FUNC void setAngle (Scalar const &theta)

Setter of rotation angle, leaves scale as is.

inline SOPHUS_FUNC void setRotationMatrix (Transformation const &R)

Setter of complex using rotation matrix R, leaves scale as is.

Precondition: R must be orthogonal with determinant of one.

inline SOPHUS_FUNC void setScale (Scalar const &scale)

Sets scale and leaves rotation as is.

inline SOPHUS_FUNC void setScaledRotationMatrix (Transformation const &sR)

Setter of complex number using scaled rotation matrix sR.

Precondition: The 2x2 matrix must be “scaled orthogonal” and have a positive determinant.

inline SOPHUS_FUNC void setSO2 (SO2< Scalar > const &so2)

Setter of SO(2) rotations, leaves scale as is.

inline SOPHUS_FUNC SO2< Scalar > so2 () const

Public Static Attributes

static constexpr int Options = Eigen::internal::traits<Derived>::Options
static constexpr int DoF = 2

Degrees of freedom of manifold, number of dimensions in tangent space (one for rotation and one for scaling).

static constexpr int num_parameters = 2

Number of internal parameters used (complex number is a tuple).

static constexpr int N = 2

Group transformations are 2x2 matrices.

static constexpr int Dim = 2

Points are 2-dimensional.