|
static SOPHUS_FUNC Sophus::Matrix< Scalar, num_parameters, DoF > | Dx_exp_x (Tangent const &upsilon_omega) |
|
static SOPHUS_FUNC Sophus::Matrix< Scalar, num_parameters, DoF > | Dx_exp_x_at_0 () |
|
static SOPHUS_FUNC Transformation | Dxi_exp_x_matrix_at_0 (int i) |
|
static SOPHUS_FUNC SE3< Scalar > | exp (Tangent const &a) |
|
template<class S = Scalar> |
static SOPHUS_FUNC enable_if_t< std::is_floating_point< S >::value, SE3 > | fitToSE3 (Matrix4< Scalar > const &T) |
|
static SOPHUS_FUNC Transformation | generator (int i) |
|
static SOPHUS_FUNC Transformation | hat (Tangent const &a) |
|
static SOPHUS_FUNC Tangent | lieBracket (Tangent const &a, Tangent const &b) |
|
static SOPHUS_FUNC SE3 | rotX (Scalar const &x) |
|
static SOPHUS_FUNC SE3 | rotY (Scalar const &y) |
|
static SOPHUS_FUNC SE3 | rotZ (Scalar const &z) |
|
template<class UniformRandomBitGenerator > |
static SE3 | sampleUniform (UniformRandomBitGenerator &generator) |
|
template<class T0 , class T1 , class T2 > |
static SOPHUS_FUNC SE3 | trans (T0 const &x, T1 const &y, T2 const &z) |
|
static SOPHUS_FUNC SE3 | trans (Vector3< Scalar > const &xyz) |
|
static SOPHUS_FUNC SE3 | transX (Scalar const &x) |
|
static SOPHUS_FUNC SE3 | transY (Scalar const &y) |
|
static SOPHUS_FUNC SE3 | transZ (Scalar const &z) |
|
static SOPHUS_FUNC Tangent | vee (Transformation const &Omega) |
|
template<class Scalar_, int Options>
class Sophus::SE3< Scalar_, Options >
SE3 using default storage; derived from SE3Base.
Definition at line 11 of file se3.hpp.
template<class Scalar_ , int Options>
Constructor from 4x4 matrix
Precondition: Rotation matrix needs to be orthogonal with determinant of 1. The last row must be (0, 0, 0, 1)
.
Definition at line 499 of file se3.hpp.
template<class Scalar_ , int Options>
Group exponential
This functions takes in an element of tangent space (= twist a
) and returns the corresponding element of the group SE(3).
The first three components of a
represent the translational part upsilon
in the tangent space of SE(3), while the last three components of a
represents the rotation vector omega
. To be more specific, this function computes expmat(hat(a))
with expmat(.)
being the matrix exponential and hat(.)
the hat-operator of SE(3), see below.
Note: That is an accurate expansion!
Definition at line 763 of file se3.hpp.
template<class Scalar_ , int Options>
Returns the ith infinitesimal generators of SE(3).
The infinitesimal generators of SE(3) are:
| 0 0 0 1 |
G_0 = | 0 0 0 0 |
| 0 0 0 0 |
| 0 0 0 0 |
| 0 0 0 0 |
G_1 = | 0 0 0 1 |
| 0 0 0 0 |
| 0 0 0 0 |
| 0 0 0 0 |
G_2 = | 0 0 0 0 |
| 0 0 0 1 |
| 0 0 0 0 |
| 0 0 0 0 |
G_3 = | 0 0 -1 0 |
| 0 1 0 0 |
| 0 0 0 0 |
| 0 0 1 0 |
G_4 = | 0 0 0 0 |
| -1 0 0 0 |
| 0 0 0 0 |
| 0 -1 0 0 |
G_5 = | 1 0 0 0 |
| 0 0 0 0 |
| 0 0 0 0 |
Precondition: i
must be in [0, 5].
Definition at line 833 of file se3.hpp.
template<class Scalar_ , int Options>
hat-operator
It takes in the 6-vector representation (= twist) and returns the corresponding matrix representation of Lie algebra element.
Formally, the hat()-operator of SE(3) is defined as
hat(.): R^6 -> R^{4x4}, hat(a) = sum_i a_i * G_i
(for i=0,...,5)
with G_i
being the ith infinitesimal generator of SE(3).
The corresponding inverse is the vee()-operator, see below.
Definition at line 854 of file se3.hpp.
template<class Scalar_ , int Options>
Lie bracket
It computes the Lie bracket of SE(3). To be more specific, it computes
[omega_1, omega_2]_se3 := 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 SE(3).
Definition at line 872 of file se3.hpp.
template<class Scalar_ , int Options>
template<class UniformRandomBitGenerator >
static SE3 Sophus::SE3< Scalar_, Options >::sampleUniform |
( |
UniformRandomBitGenerator & |
generator | ) |
|
|
inlinestatic |
Draw uniform sample from SE(3) manifold.
Translations are drawn component-wise from the range [-1, 1].
Definition at line 908 of file se3.hpp.
template<class Scalar_ , int Options>
vee-operator
It takes 4x4-matrix representation Omega
and maps it to the corresponding 6-vector representation of Lie algebra.
This is the inverse of the hat()-operator, see above.
Precondition: Omega
must have the following structure:
| 0 -f e a |
| f 0 -d b |
| -e d 0 c
| 0 0 0 0 | .
Definition at line 958 of file se3.hpp.