Template Class RxSO3
Defined in File rxso3.hpp
Inheritance Relationships
Base Type
public Sophus::RxSO3Base< RxSO3< Scalar_, Options > >(Template Class RxSO3Base)
Class Documentation
-
template<class Scalar_, int Options>
class RxSO3 : public Sophus::RxSO3Base<RxSO3<Scalar_, Options>> RxSO3 using storage; derived from RxSO3Base.
Public Types
Public Functions
- SOPHUS_FUNC RxSO3 & operator= (RxSO3 const &other)=default
Define copy-assignment operator explicitly. The definition of implicit copy assignment operator is deprecated in presence of a user-declared copy constructor (-Wdeprecated-copy in clang >= 13).
- inline EIGEN_MAKE_ALIGNED_OPERATOR_NEW SOPHUS_FUNC RxSO3 ()
Default constructor initializes quaternion to identity rotation and scale to 1.
-
template<class OtherDerived>
inline SOPHUS_FUNC RxSO3(RxSO3Base<OtherDerived> const &other) Copy-like constructor from OtherDerived
-
inline explicit SOPHUS_FUNC RxSO3(Transformation const &sR)
Constructor from scaled rotation matrix
Precondition: rotation matrix need to be scaled orthogonal with determinant of
s^3.
-
inline SOPHUS_FUNC RxSO3(Scalar const &scale, Transformation const &R)
Constructor from scale factor and rotation matrix
R.Precondition: Rotation matrix
Rmust to be orthogonal with determinant of 1 andscalemust not be close to either zero or infinity.
-
inline SOPHUS_FUNC RxSO3(Scalar const &scale, SO3<Scalar> const &so3)
Constructor from scale factor and SO3
Precondition:
scalemust not to be close to either zero or infinity.
-
template<class D>
inline explicit SOPHUS_FUNC RxSO3(Eigen::QuaternionBase<D> const &quat) Constructor from quaternion
Precondition: quaternion must not be close to either zero or infinity.
-
template<class D>
inline explicit SOPHUS_FUNC RxSO3(Scalar const &scale, Eigen::QuaternionBase<D> const &unit_quat) Constructor from scale factor and unit quaternion
Precondition: quaternion must not be close to zero.
- inline SOPHUS_FUNC QuaternionMember const & quaternion () const
Accessor of quaternion.
Public Static Functions
- static inline SOPHUS_FUNC Sophus::Matrix< Scalar, num_parameters, DoF > Dx_exp_x_at_0 ()
Returns derivative of exp(x) wrt. x_i at x=0.
- static inline SOPHUS_FUNC Sophus::Matrix< Scalar, num_parameters, DoF > Dx_exp_x (const Tangent &a)
Returns derivative of exp(x) wrt. x.
- static inline SOPHUS_FUNC Sophus::Matrix< Scalar, 3, DoF > Dx_exp_x_times_point_at_0 (Point const &point)
Returns derivative of exp(x) * p wrt. x_i at x=0.
- static inline SOPHUS_FUNC Transformation Dxi_exp_x_matrix_at_0 (int i)
Returns derivative of exp(x).matrix() wrt.
x_i at x=0.
- static inline SOPHUS_FUNC RxSO3< Scalar > exp (Tangent const &a)
Group exponential
This functions takes in an element of tangent space (= rotation 3-vector plus logarithm of scale) and returns the corresponding element of the group RxSO3.
To be more specific, this function computes
expmat(hat(omega))withexpmat(.)being the matrix exponential andhat(.)being the hat()-operator of RSO3.
- static inline SOPHUS_FUNC RxSO3< Scalar > expAndTheta (Tangent const &a, Scalar *theta)
As above, but also returns
theta = |omega|as out-parameter.Precondition:
thetamust not benullptr.
- static inline SOPHUS_FUNC Transformation generator (int i)
Returns the ith infinitesimal generators of
R+ x SO(3).The infinitesimal generators of RxSO3 are:
| 0 0 0 | G_0 = | 0 0 -1 | | 0 1 0 | | 0 0 1 | G_1 = | 0 0 0 | | -1 0 0 | | 0 -1 0 | G_2 = | 1 0 0 | | 0 0 0 | | 1 0 0 | G_2 = | 0 1 0 | | 0 0 1 |
Precondition:
imust be 0, 1, 2 or 3.
- static inline SOPHUS_FUNC Transformation hat (Tangent const &a)
hat-operator
It takes in the 4-vector representation
a(= rotation vector plus logarithm of scale) and returns the corresponding matrix representation of Lie algebra element.Formally, the hat()-operator of RxSO3 is defined as
hat(.): R^4 -> R^{3x3}, hat(a) = sum_i a_i * G_i(for i=0,1,2,3)with
G_ibeing the ith infinitesimal generator of RxSO3.The corresponding inverse is the vee()-operator, see below.
- static inline SOPHUS_FUNC Tangent lieBracket (Tangent const &a, Tangent const &b)
Lie bracket
It computes the Lie bracket of RxSO(3). To be more specific, it computes
[omega_1, omega_2]_rxso3 := vee([hat(omega_1), hat(omega_2)])with
[A,B] := AB-BAbeing the matrix commutator,hat(.)the hat()-operator andvee(.)the vee()-operator of RxSO3.
-
template<class UniformRandomBitGenerator>
static inline RxSO3 sampleUniform(UniformRandomBitGenerator &generator) Draw uniform sample from RxSO(3) manifold.
The scale factor is drawn uniformly in log2-space from [-1, 1], hence the scale is in [0.5, 2].
- static inline SOPHUS_FUNC Tangent vee (Transformation const &Omega)
vee-operator
It takes the 3x3-matrix representation
Omegaand maps it to the corresponding vector representation of Lie algebra.This is the inverse of the hat()-operator, see above.
Precondition:
Omegamust have the following structure:| d -c b | | c d -a | | -b a d |
Public Static Attributes
Protected Functions
- inline SOPHUS_FUNC QuaternionMember & quaternion_nonconst ()
Protected Attributes
-
QuaternionMember quaternion_
Friends
- friend class RxSO3Base< RxSO3< Scalar_, Options > >