Conversions and operations for rotations in SO(3)
More...
Conversions and operations for rotations in SO(3)
◆ ezyx_to_quat()
Convert intrinsic ZYX Euler-angles to unit quaternion.
- Parameters
-
ezyx | Euler angles in radians |
- Returns
- Quaternion
◆ quat_to_ezyx()
Convert unit quaternion to intrinsic ZYX Euler-angles.
- Parameters
-
- Returns
- Euler angles in radians
◆ quat_to_rot()
Convert unit quaternion to rotation matrix.
- Parameters
-
- Returns
- Rotation matrix
◆ quat_to_rotvec()
Convert unit quaternion to rotation vector.
- Parameters
-
- Returns
- Rotation vector
◆ rot_identity()
Mat3 fsb::rot_identity |
( |
| ) |
|
Identity rotation matrix.
\( \begin{bmatrix} 1 & 0 & 0 \\ 0 & 1 & 0 \\ 0 & 0 & 1 \end{bmatrix} \)
- Returns
- Identity rotation matrix
◆ rot_rx()
Mat3 fsb::rot_rx |
( |
real_t |
rx | ) |
|
Rotation matrix about x-axis.
- Parameters
-
rx | Rotation angle in radians |
- Returns
- Rotation matrix
◆ rot_ry()
Mat3 fsb::rot_ry |
( |
real_t |
ry | ) |
|
Rotation matrix about y-axis.
- Parameters
-
ry | Rotation angle in radians |
- Returns
- Rotation matrix
◆ rot_rz()
Mat3 fsb::rot_rz |
( |
real_t |
rz | ) |
|
Rotation matrix about z-axis.
- Parameters
-
rz | Rotation angle in radians |
- Returns
- Rotation matrix
◆ rot_to_quat()
Convert rotation matrix to unit quaternion.
- Parameters
-
- Returns
- Quaternion
◆ rotate_mat3()
Vec3 fsb::rotate_mat3 |
( |
const Mat3 & |
rot, |
|
|
const Vec3 & |
vec |
|
) |
| |
Matrix multiplication with rotation matrix.
- Parameters
-
rot | Rotation matrix |
vec | Vector |
- Returns
- Rotated vector
◆ rotate_mat3_transpose()
Vec3 fsb::rotate_mat3_transpose |
( |
const Mat3 & |
rot, |
|
|
const Vec3 & |
vec |
|
) |
| |
Transposed matrix multiplication with rotation matrix.
- Parameters
-
rot | Rotation matrix |
vec | Vector |
- Returns
- Rotated vector with transpose of rotation matrix
◆ rotvec_to_quat()
Convert rotation vector to unit quaternion.
- Parameters
-
- Returns
- Quaternion
◆ skew_symmetric()
Mat3 fsb::skew_symmetric |
( |
const Vec3 & |
vec | ) |
|
Skew-symmetric matrix from vector.
\( [v]^{\times} = \begin{bmatrix} 0 & -v_z & v_y \\ v_z & 0 & -v_x \\ -v_y & v_x & 0
\end{bmatrix} \)
- Parameters
-
- Returns
- Skew-symmetric matrix