so3
SO(3) Lie group operations for rotation matrices.
This module provides exponential and logarithm maps for the SO(3) rotation group, enabling axis-angle to rotation matrix conversions and vice versa.
Requires jaxlie: pip install openscvx[lie]
SO3Exp
¶
Bases: Expr
Exponential map from so(3) to SO(3) rotation matrix.
Maps a 3D rotation vector (axis-angle representation) to a 3×3 rotation matrix using the Rodrigues formula. Uses jaxlie for numerically robust implementation with proper handling of small angles.
The rotation vector ω has direction equal to the rotation axis and magnitude equal to the rotation angle in radians.
Attributes:
| Name | Type | Description |
|---|---|---|
omega |
3D rotation vector with shape (3,) |
Example
Create a rotation about the z-axis::
import openscvx as ox
import numpy as np
# 90 degree rotation about z
omega = ox.Constant(np.array([0, 0, np.pi/2]))
R = ox.lie.SO3Exp(omega) # 3×3 rotation matrix
Parameterized rotation for optimization::
theta = ox.State("theta", shape=(1,))
axis = ox.Constant(np.array([0, 0, 1])) # z-axis
R = ox.lie.SO3Exp(axis * theta)
See Also
- SO3Log: Inverse operation (rotation matrix to rotation vector)
- SE3Exp: Full rigid body transformation including translation
Source code in openscvx/symbolic/expr/lie/so3.py
__init__(omega: Union[Expr, float, int, np.ndarray])
¶
Initialize SO3 exponential map.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
omega
|
Union[Expr, float, int, ndarray]
|
3D rotation vector (axis × angle) with shape (3,) |
required |
check_shape() -> Tuple[int, ...]
¶
Check that input is a 3D vector and return output shape.
Returns:
| Name | Type | Description |
|---|---|---|
tuple |
Tuple[int, ...]
|
Shape (3, 3) for the rotation matrix |
Raises:
| Type | Description |
|---|---|
ValueError
|
If omega does not have shape (3,) |
Source code in openscvx/symbolic/expr/lie/so3.py
SO3Log
¶
Bases: Expr
Logarithm map from SO(3) rotation matrix to so(3) rotation vector.
Maps a 3×3 rotation matrix to a 3D rotation vector (axis-angle representation). Uses jaxlie for numerically robust implementation.
The output rotation vector ω has direction equal to the rotation axis and magnitude equal to the rotation angle in radians.
Attributes:
| Name | Type | Description |
|---|---|---|
rotation |
3×3 rotation matrix with shape (3, 3) |
Example
Extract rotation vector from a rotation matrix::
import openscvx as ox
R = ox.State("R", shape=(3, 3)) # Rotation matrix state
omega = ox.lie.SO3Log(R) # 3D rotation vector
See Also
- SO3Exp: Inverse operation (rotation vector to rotation matrix)
- SE3Log: Full rigid body transformation logarithm
Source code in openscvx/symbolic/expr/lie/so3.py
__init__(rotation: Union[Expr, float, int, np.ndarray])
¶
Initialize SO3 logarithm map.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
rotation
|
Union[Expr, float, int, ndarray]
|
3×3 rotation matrix with shape (3, 3) |
required |
check_shape() -> Tuple[int, ...]
¶
Check that input is a 3×3 matrix and return output shape.
Returns:
| Name | Type | Description |
|---|---|---|
tuple |
Tuple[int, ...]
|
Shape (3,) for the rotation vector |
Raises:
| Type | Description |
|---|---|
ValueError
|
If rotation does not have shape (3, 3) |