#include <so2.hpp>
Public Types | |
using | Adjoint = Scalar |
using | ComplexT = typename Eigen::internal::traits< Derived >::ComplexType |
using | HomogeneousPoint = Vector3< Scalar > |
template<typename HPointDerived > | |
using | HomogeneousPointProduct = Vector3< ReturnScalar< HPointDerived > > |
using | Line = ParametrizedLine2< Scalar > |
using | Point = Vector2< Scalar > |
template<typename PointDerived > | |
using | PointProduct = Vector2< ReturnScalar< PointDerived > > |
template<typename OtherDerived > | |
using | ReturnScalar = typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar >::ReturnType |
using | Scalar = typename Eigen::internal::traits< Derived >::Scalar |
template<typename OtherDerived > | |
using | SO2Product = SO2< ReturnScalar< OtherDerived > > |
using | Tangent = Scalar |
using | Transformation = Matrix< Scalar, N, N > |
Public Member Functions | |
SOPHUS_FUNC Adjoint | Adj () const |
template<class NewScalarType > | |
SOPHUS_FUNC SO2< NewScalarType > | cast () const |
SOPHUS_FUNC Scalar * | data () |
SOPHUS_FUNC Scalar const * | data () const |
SOPHUS_FUNC Matrix< Scalar, num_parameters, DoF > | Dx_this_mul_exp_x_at_0 () const |
SOPHUS_FUNC SO2< Scalar > | inverse () const |
SOPHUS_FUNC Scalar | log () const |
SOPHUS_FUNC Transformation | matrix () const |
SOPHUS_FUNC void | normalize () |
template<typename HPointDerived , typename = typename std::enable_if< IsFixedSizeVector<HPointDerived, 3>::value>::type> | |
SOPHUS_FUNC HomogeneousPointProduct< HPointDerived > | operator* (Eigen::MatrixBase< HPointDerived > const &p) const |
template<typename PointDerived , typename = typename std::enable_if< IsFixedSizeVector<PointDerived, 2>::value>::type> | |
SOPHUS_FUNC PointProduct< PointDerived > | operator* (Eigen::MatrixBase< PointDerived > const &p) const |
SOPHUS_FUNC Line | operator* (Line const &l) const |
template<typename OtherDerived > | |
SOPHUS_FUNC SO2Product< OtherDerived > | operator* (SO2Base< OtherDerived > const &other) const |
template<typename OtherDerived , typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type> | |
SOPHUS_FUNC SO2Base< Derived > | operator*= (SO2Base< OtherDerived > const &other) |
SOPHUS_FUNC SO2Base & | operator= (SO2Base const &other)=default |
template<class OtherDerived > | |
SOPHUS_FUNC SO2Base< Derived > & | operator= (SO2Base< OtherDerived > const &other) |
SOPHUS_FUNC Sophus::Vector< Scalar, num_parameters > | params () const |
SOPHUS_FUNC void | setComplex (Point const &complex) |
SOPHUS_FUNC ComplexT const & | unit_complex () const |
Static Public Attributes | |
static constexpr int | DoF = 1 |
static constexpr int | N = 2 |
Group transformations are 2x2 matrices. More... | |
static constexpr int | num_parameters = 2 |
Number of internal parameters used (complex numbers are a tuples). More... | |
Private Member Functions | |
SOPHUS_FUNC ComplexT & | unit_complex_nonconst () |
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
(with R'
being the transpose of R
) and have a positive determinant. In particular, the determinant is 1. Let theta
be the rotation angle, the rotation matrix can be written in close form:
| cos(theta) -sin(theta) | | sin(theta) cos(theta) |
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.
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 because alpha + beta = beta + alpha
with alpha
and beta
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()
.
using Sophus::SO2Base< Derived >::Adjoint = Scalar |
using Sophus::SO2Base< Derived >::ComplexT = typename Eigen::internal::traits<Derived>::ComplexType |
using Sophus::SO2Base< Derived >::HomogeneousPoint = Vector3<Scalar> |
using Sophus::SO2Base< Derived >::HomogeneousPointProduct = Vector3<ReturnScalar<HPointDerived> > |
using Sophus::SO2Base< Derived >::Line = ParametrizedLine2<Scalar> |
using Sophus::SO2Base< Derived >::Point = Vector2<Scalar> |
using Sophus::SO2Base< Derived >::PointProduct = Vector2<ReturnScalar<PointDerived> > |
using Sophus::SO2Base< Derived >::ReturnScalar = typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar>::ReturnType |
using Sophus::SO2Base< Derived >::Scalar = typename Eigen::internal::traits<Derived>::Scalar |
using Sophus::SO2Base< Derived >::SO2Product = SO2<ReturnScalar<OtherDerived> > |
using Sophus::SO2Base< Derived >::Tangent = Scalar |
using Sophus::SO2Base< Derived >::Transformation = Matrix<Scalar, N, N> |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
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(.))
with logmat(.)
being the matrix logarithm and vee(.)
the vee-operator of SO(2).
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
default |
Assignment operator
|
inline |
|
inline |
|
inline |
|
inline |
|
inlineprivate |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |