Similarity transformation in 3D (rotation + translation + scale).
More...
|
| | Sim3 () |
| | Default constructor.
|
| | Sim3 (const Matrix3< g_type > &R, const Vector3< g_type > &t, g_type s) |
| | Constructs from a rotation matrix, translation, and scale.
|
| | Sim3 (const Quaternion< g_type > &r, const Vector3< g_type > &t, g_type s) |
| | Constructs from a quaternion, translation, and scale.
|
| | Sim3 (const Vector7d &update, bool fix_scale) |
| | Constructs from a 7D tangent-space update vector.
|
| Sim3 | inverse () const |
| | Computes the inverse of this similarity transform.
|
| Vector7d | log () const |
| | Computes the logarithmic map (Sim3 -> 7D tangent vector).
|
| Vector3< g_type > | map (const Vector3< g_type > &xyz) const |
| | Applies the similarity transform to a 3D point: s * R * xyz + t.
|
| Sim3 | operator* (const Sim3 &other) const |
| | Composes two Sim3 transforms.
|
| Sim3 & | operator*= (const Sim3 &other) |
| | In-place composition with another Sim3 transform.
|
| g_type & | operator[] (int i) |
| | Mutable element access: indices 0-3 = quaternion, 4-6 = translation, 7 = scale.
|
| g_type | operator[] (int i) const |
| | Const element access: indices 0-3 = quaternion, 4-6 = translation, 7 = scale.
|
|
Quaternion< g_type > & | rotation () |
| | Returns a mutable reference to the rotation quaternion.
|
|
const Quaternion< g_type > & | rotation () const |
| | Returns a const reference to the rotation quaternion.
|
|
g_type & | scale () |
| | Returns a mutable reference to the scale factor.
|
|
const g_type & | scale () const |
| | Returns a const reference to the scale factor.
|
|
Vector3< g_type > & | translation () |
| | Returns a mutable reference to the translation.
|
|
const Vector3< g_type > & | translation () const |
| | Returns a const reference to the translation.
|
|
|
Quaternion< g_type > | r |
| | Rotation component as a unit quaternion.
|
|
g_type | s |
| | Scale factor.
|
|
Vector3< g_type > | t |
| | Translation component.
|
Similarity transformation in 3D (rotation + translation + scale).
Definition at line 12 of file sim3.h.
◆ Sim3() [1/4]
◆ Sim3() [2/4]
| Sim3::Sim3 |
( |
const Quaternion< g_type > & | r, |
|
|
const Vector3< g_type > & | t, |
|
|
g_type | s ) |
|
inline |
Constructs from a quaternion, translation, and scale.
- Parameters
-
| [in] | r | The rotation quaternion. |
| [in] | t | The translation vector. |
| [in] | s | The scale factor. |
Definition at line 35 of file sim3.h.
References r, s, and t.
◆ Sim3() [3/4]
| Sim3::Sim3 |
( |
const Matrix3< g_type > & | R, |
|
|
const Vector3< g_type > & | t, |
|
|
g_type | s ) |
|
inline |
Constructs from a rotation matrix, translation, and scale.
- Parameters
-
| [in] | R | The 3x3 rotation matrix. |
| [in] | t | The translation vector. |
| [in] | s | The scale factor. |
Definition at line 44 of file sim3.h.
References r, s, and t.
◆ Sim3() [4/4]
| Sim3::Sim3 |
( |
const Vector7d & | update, |
|
|
bool | fix_scale ) |
|
inline |
Constructs from a 7D tangent-space update vector.
- Parameters
-
| [in] | update | The update vector (omega, upsilon, sigma). |
| [in] | fix_scale | If true, the scale component is not updated. |
Definition at line 52 of file sim3.h.
References cast(), cos(), r, s, sin(), skew(), and t.
◆ inverse()
| Sim3 Sim3::inverse |
( |
| ) |
const |
|
inline |
Computes the inverse of this similarity transform.
- Returns
- The inverse Sim3.
Definition at line 218 of file sim3.h.
References Sim3(), r, s, and t.
◆ log()
◆ map()
| Vector3< g_type > Sim3::map |
( |
const Vector3< g_type > & | xyz | ) |
const |
|
inline |
Applies the similarity transform to a 3D point: s * R * xyz + t.
- Parameters
-
| [in] | xyz | The 3D point to transform. |
- Returns
- The transformed point.
Definition at line 129 of file sim3.h.
References r, s, and t.
◆ operator*()
| Sim3 Sim3::operator* |
( |
const Sim3 & | other | ) |
const |
|
inline |
Composes two Sim3 transforms.
- Parameters
-
| [in] | other | The right-hand side transform. |
Definition at line 257 of file sim3.h.
References Sim3(), r, s, and t.
◆ operator*=()
| Sim3 & Sim3::operator*= |
( |
const Sim3 & | other | ) |
|
|
inline |
In-place composition with another Sim3 transform.
- Parameters
-
| [in] | other | The right-hand side transform. |
Definition at line 267 of file sim3.h.
References Sim3().
◆ operator[]() [1/2]
| g_type & Sim3::operator[] |
( |
int | i | ) |
|
|
inline |
Mutable element access: indices 0-3 = quaternion, 4-6 = translation, 7 = scale.
- Parameters
-
| [in] | i | The element index (0-7). |
Definition at line 241 of file sim3.h.
References r, s, and t.
◆ operator[]() [2/2]
| g_type Sim3::operator[] |
( |
int | i | ) |
const |
|
inline |
Const element access: indices 0-3 = quaternion, 4-6 = translation, 7 = scale.
- Parameters
-
| [in] | i | The element index (0-7). |
Definition at line 226 of file sim3.h.
References r, s, and t.
The documentation for this struct was generated from the following file:
- GraphOptimization/Headers/sim3.h