Template Class SO2Base
Defined in File so2.hpp
Inheritance Relationships
Derived Type
public Sophus::SO2< Scalar, Options >
(Template Class SO2)
Class Documentation
-
template<class Derived>
class SO2Base SO2 base type - implements SO2 class but is storage agnostic.
SO(2) is the group of rotations in 2d. As a matrix group, it is the set of matrices which are orthogonal such that
R * R' = I
(withR'
being the transpose ofR
) and have a positive determinant. In particular, the determinant is 1. Lettheta
be the rotation angle, the rotation matrix can be written in close form:As a matter of fact, the first column of those matrices is isomorph to the set of unit complex numbers U(1). Thus, internally, SO2 is represented as complex number with length 1.| cos(theta) -sin(theta) | | sin(theta) cos(theta) |
SO(2) is a compact and commutative group. First it is compact since the set of rotation matrices is a closed and bounded set. Second it is commutative since
R(alpha) * R(beta) = R(beta) * R(alpha)
, simply becausealpha + beta = beta + alpha
withalpha
andbeta
being rotation angles (about the same axis).Class invariant: The 2-norm of
unit_complex
must be close to 1. Technically speaking, it must hold that:|unit_complex().squaredNorm() - 1| <= Constants::epsilon()
.Subclassed by Sophus::SO2< Scalar, Options >
Public Types
-
using Line = ParametrizedLine2<Scalar>
-
using Hyperplane = Hyperplane2<Scalar>
-
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 SO2 operations.
-
template<typename OtherDerived>
using SO2Product = SO2<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 elementA
such that for allx
it holds thathat(Ad_A * x) = A * hat(x) A^{-1}
. See hat-operator below.It simply
1
, sinceSO(2)
is a commutative group.
- template<class NewScalarType> inline SOPHUS_FUNC SO2< NewScalarType > cast () const
Returns copy of instance casted to NewScalarType.
- inline SOPHUS_FUNC Scalar * data ()
This provides unsafe read/write access to internal data. SO(2) is represented by a unit complex number (two parameters). When using direct write access, the user needs to take care of that the complex number stays normalized.
- inline SOPHUS_FUNC Scalar const * data () const
Const version of data() above.
- inline SOPHUS_FUNC SO2< Scalar > inverse () const
Returns group inverse.
- inline SOPHUS_FUNC Scalar log () const
Logarithmic map
Computes the logarithm, the inverse of the group exponential which maps element of the group (rotation matrices) to elements of the tangent space (rotation angles).
To be specific, this function computes
vee(logmat(.))
withlogmat(.)
being the matrix logarithm andvee(.)
the vee-operator of SO(2).
- inline SOPHUS_FUNC void normalize ()
It re-normalizes
unit_complex
to unit length.Note: Because of the class invariant, there is typically no need to call this function directly.
- inline SOPHUS_FUNC Transformation matrix () const
Returns 2x2 matrix representation of the instance.
For SO(2), the matrix representation is an orthogonal matrix
R
withdet(R)=1
, thus the so-called “rotation matrix”.
- template<class OtherDerived> inline SOPHUS_FUNC SO2Base< Derived > & operator= (SO2Base< OtherDerived > const &other)
Assignment-like operator from OtherDerived.
- template<typename OtherDerived> inline SOPHUS_FUNC SO2Product< OtherDerived > operator* (SO2Base< OtherDerived > const &other) const
Group multiplication, which is rotation concatenation.
- 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 elementbar_R_foo
(= rotation matrix):p_bar = 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.
This function rotates a homogeneous 2 dimensional point
p
by the SO2 elementbar_R_foo
(= rotation matrix):p_bar = bar_R_foo * p_foo
.
- inline SOPHUS_FUNC Line operator* (Line const &l) const
Group action on lines.
This function rotates a parametrized line
l(t) = o + t * d
by the SO2 element:Both direction
d
and origino
are rotated as a 2 dimensional point
- 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:Normal vector
n
is rotated Offsetd
is left unchangedNote 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 SO2Base< Derived > operator*= (SO2Base< 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.
- inline SOPHUS_FUNC Matrix< Scalar, num_parameters, DoF > Dx_this_mul_exp_x_at_0 () const
Returns derivative of this * SO2::exp(x) wrt. x at x=0.
- inline SOPHUS_FUNC Sophus::Vector< Scalar, num_parameters > params () const
Returns internal parameters of SO(2).
It returns (c[0], c[1]), with c being the unit complex number.
- 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 void setComplex (Point const &complex)
Takes in complex number / tuple and normalizes it.
Precondition: The complex number must not be close to zero.
- inline SOPHUS_FUNC ComplexT const & unit_complex () const
Accessor of unit quaternion.
Public Static Attributes
-
static constexpr int DoF = 1
Degrees of freedom of manifold, number of dimensions in tangent space (one since we only have in-plane rotations).
-
static constexpr int num_parameters = 2
Number of internal parameters used (complex numbers are a tuples).
-
static constexpr int N = 2
Group transformations are 2x2 matrices.
-
static constexpr int Dim = 2
Points are 3-dimensional.
-
using Line = ParametrizedLine2<Scalar>