#include <rxso2.hpp>

| Public Types | |
| using | Adjoint = Matrix< Scalar, DoF, DoF > | 
| using | ComplexType = 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 | 
| template<typename OtherDerived > | |
| using | RxSO2Product = RxSO2< ReturnScalar< OtherDerived > > | 
| using | Scalar = typename Eigen::internal::traits< Derived >::Scalar | 
| using | Tangent = Vector< Scalar, DoF > | 
| using | Transformation = Matrix< Scalar, N, N > | 
| Public Member Functions | |
| SOPHUS_FUNC Adjoint | Adj () const | 
| SOPHUS_FUNC Scalar | angle () const | 
| template<class NewScalarType > | |
| SOPHUS_FUNC RxSO2< NewScalarType > | cast () const | 
| SOPHUS_FUNC ComplexType const & | complex () const | 
| SOPHUS_FUNC Scalar * | data () | 
| SOPHUS_FUNC Scalar const * | data () const | 
| SOPHUS_FUNC RxSO2< Scalar > | inverse () const | 
| SOPHUS_FUNC Tangent | log () const | 
| SOPHUS_FUNC Transformation | matrix () const | 
| 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 RxSO2Product< OtherDerived > | operator* (RxSO2Base< OtherDerived > const &other) const | 
| template<typename OtherDerived , typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type> | |
| SOPHUS_FUNC RxSO2Base< Derived > & | operator*= (RxSO2Base< OtherDerived > const &other) | 
| SOPHUS_FUNC RxSO2Base & | operator= (RxSO2Base const &other)=default | 
| template<class OtherDerived > | |
| SOPHUS_FUNC RxSO2Base< Derived > & | operator= (RxSO2Base< OtherDerived > const &other) | 
| SOPHUS_FUNC Sophus::Vector< Scalar, num_parameters > | params () const | 
| SOPHUS_FUNC Transformation | rotationMatrix () const | 
| SOPHUS_FUNC Scalar | scale () const | 
| SOPHUS_FUNC void | setAngle (Scalar const &theta) | 
| SOPHUS_FUNC void | setComplex (Vector2< Scalar > const &z) | 
| SOPHUS_FUNC void | setRotationMatrix (Transformation const &R) | 
| SOPHUS_FUNC void | setScale (Scalar const &scale) | 
| SOPHUS_FUNC void | setScaledRotationMatrix (Transformation const &sR) | 
| SOPHUS_FUNC void | setSO2 (SO2< Scalar > const &so2) | 
| SOPHUS_FUNC SO2< Scalar > | so2 () const | 
| Static Public Attributes | |
| static constexpr int | DoF = 2 | 
| static constexpr int | N = 2 | 
| Group transformations are 2x2 matrices.  More... | |
| static constexpr int | num_parameters = 2 | 
| Number of internal parameters used (complex number is a tuple).  More... | |
| Protected Member Functions | |
| SOPHUS_FUNC ComplexType & | complex_nonconst () | 
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 zero. Strictly speaking, it must hold that:
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.
| using Sophus::RxSO2Base< Derived >::ComplexType = typename Eigen::internal::traits<Derived>::ComplexType | 
| using Sophus::RxSO2Base< Derived >::HomogeneousPoint = Vector3<Scalar> | 
| using Sophus::RxSO2Base< Derived >::HomogeneousPointProduct = Vector3<ReturnScalar<HPointDerived> > | 
| using Sophus::RxSO2Base< Derived >::Line = ParametrizedLine2<Scalar> | 
| using Sophus::RxSO2Base< Derived >::Point = Vector2<Scalar> | 
| using Sophus::RxSO2Base< Derived >::PointProduct = Vector2<ReturnScalar<PointDerived> > | 
| using Sophus::RxSO2Base< Derived >::ReturnScalar = typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar>::ReturnType | 
| using Sophus::RxSO2Base< Derived >::RxSO2Product = RxSO2<ReturnScalar<OtherDerived> > | 
| using Sophus::RxSO2Base< Derived >::Scalar = typename Eigen::internal::traits<Derived>::Scalar | 
| using Sophus::RxSO2Base< Derived >::Tangent = Vector<Scalar, DoF> | 
| using Sophus::RxSO2Base< Derived >::Transformation = Matrix<Scalar, N, N> | 
| 
 | inline | 
| 
 | inline | 
| 
 | inline | 
| 
 | inline | 
| 
 | inlineprotected | 
| 
 | inline | 
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 | 
| 
 | inline | 
| 
 | inline | 
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 | 
| 
 | inline | 
| 
 | inline | 
| 
 | inline | 
| 
 | inline | 
| 
 | inline | 
| 
 | default | 
Assignment operator.
| 
 | inline | 
| 
 | inline | 
| 
 | inline | 
| 
 | inline | 
| 
 | inline | 
| 
 | inline | 
| 
 | inline | 
| 
 | inline | 
| 
 | inline | 
| 
 | inline | 
| 
 | inline | 
| 
 | staticconstexpr | 
| 
 | staticconstexpr | 
| 
 | staticconstexpr |