template<class Scalar_, int Options>
class Sophus::RxSO3< Scalar_, Options >
RxSO3 using storage; derived from RxSO3Base.
Definition at line 11 of file rxso3.hpp.
template<class Scalar_ , int Options>
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, thixs function computes expmat(hat(omega))
with expmat(.)
being the matrix exponential and hat(.)
being the hat()-operator of RSO3.
Definition at line 509 of file rxso3.hpp.
template<class Scalar_ , int Options>
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: i
must be 0, 1, 2 or 3.
Definition at line 557 of file rxso3.hpp.
template<class Scalar_ , int Options>
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_i
being the ith infinitesimal generator of RxSO3.
The corresponding inverse is the vee()-operator, see below.
Definition at line 579 of file rxso3.hpp.
template<class Scalar_ , int Options>
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-BA
being the matrix commutator, hat(.)
the hat()-operator and vee(.)
the vee()-operator of RxSO3.
Definition at line 598 of file rxso3.hpp.
template<class Scalar_ , int Options>
template<class UniformRandomBitGenerator >
static RxSO3 Sophus::RxSO3< Scalar_, Options >::sampleUniform |
( |
UniformRandomBitGenerator & |
generator | ) |
|
|
inlinestatic |
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].
Definition at line 613 of file rxso3.hpp.
template<class Scalar_ , int Options>
vee-operator
It takes the 3x3-matrix representation Omega
and maps it to the corresponding vector representation of Lie algebra.
This is the inverse of the hat()-operator, see above.
Precondition: Omega
must have the following structure:
| d -c b |
| c d -a |
| -b a d |
Definition at line 633 of file rxso3.hpp.