Skip to main content

SO3

Struct SO3 

Source
pub struct SO3 { /* private fields */ }
Expand description

SO(3) group element - 3×3 real orthogonal matrix with determinant 1

Represents a rotation in 3D space.

§Representation

We use Matrix3<f64> from nalgebra to represent the 3×3 rotation matrix.

§Constraints

  • Orthogonality: R^T R = I
  • Determinant: det(R) = 1

§Examples

use lie_groups::so3::SO3;
use lie_groups::traits::LieGroup;

// Rotation around Z-axis by π/2
let rot = SO3::rotation_z(std::f64::consts::FRAC_PI_2);

// Verify it's orthogonal
assert!(rot.verify_orthogonality(1e-10));

Implementations§

Source§

impl SO3

Source

pub fn matrix(&self) -> &Matrix3<f64>

Access the underlying 3×3 orthogonal matrix

Source

pub fn identity() -> Self

Identity element (no rotation)

Source

pub fn rotation_x(angle: f64) -> Self

Rotation around X-axis by angle θ (in radians)

R_x(θ) = [[1, 0, 0], [0, cos(θ), -sin(θ)], [0, sin(θ), cos(θ)]]
Source

pub fn rotation_y(angle: f64) -> Self

Rotation around Y-axis by angle θ (in radians)

R_y(θ) = [[cos(θ), 0, sin(θ)], [0, 1, 0], [-sin(θ), 0, cos(θ)]]
Source

pub fn rotation_z(angle: f64) -> Self

Rotation around Z-axis by angle θ (in radians)

R_z(θ) = [[cos(θ), -sin(θ), 0], [sin(θ), cos(θ), 0], [0, 0, 1]]
Source

pub fn rotation(axis: [f64; 3], angle: f64) -> Self

Rotation around arbitrary axis by angle

Uses Rodrigues’ rotation formula:

R(θ, n̂) = I + sin(θ)[n̂]_× + (1-cos(θ))[n̂]_ײ

where [n̂]_× is the skew-symmetric matrix for axis n̂.

Source

pub fn trace(&self) -> f64

Trace of the rotation matrix: Tr(R) = 1 + 2cos(θ)

Source

pub fn to_matrix(&self) -> [[f64; 3]; 3]

Convert to 3×3 array format

Source

pub fn from_matrix(arr: [[f64; 3]; 3]) -> Self

Create from 3×3 array format

§Panics

Does not verify orthogonality. Use verify_orthogonality() after construction.

Source

pub fn verify_orthogonality(&self, tolerance: f64) -> bool

Verify orthogonality: R^T R = I

Source

pub fn inverse(&self) -> Self

Matrix inverse (equals transpose for orthogonal matrices)

Source

pub fn distance_to_identity(&self) -> f64

Distance from identity (rotation angle)

For a rotation matrix R, the angle θ satisfies:

trace(R) = 1 + 2cos(θ)
Source

pub fn interpolate(&self, other: &Self, t: f64) -> Self

Interpolate between two SO(3) elements with proper orthogonalization

Uses linear interpolation of matrix elements followed by Gram-Schmidt orthogonalization to ensure the result stays on SO(3).

§Arguments
  • other - The target rotation
  • t - Interpolation parameter in [0, 1]
§Returns

An SO(3) element: self at t=0, other at t=1

§Note

This is NOT geodesic interpolation (SLERP). For true geodesic paths, convert to quaternions and use quaternion SLERP. However, this method guarantees the result is always a valid rotation matrix.

Source

pub fn gram_schmidt_orthogonalize(matrix: Matrix3<f64>) -> Self

Orthogonalize a matrix using Gram-Schmidt process

Takes a near-orthogonal matrix and projects it back onto SO(3). This is essential for numerical stability when matrices drift from orthogonality due to floating-point accumulation.

§Algorithm
  1. Normalize first column
  2. Orthogonalize and normalize second column
  3. Compute third column as cross product (ensures determinant = 1)
Source

pub fn renormalize(&self) -> Self

Re-normalize a rotation matrix that may have drifted

Use this periodically after many matrix multiplications to prevent numerical drift from accumulating.

Source

pub fn geodesic_distance(&self, other: &Self) -> f64

Geodesic distance between two SO(3) elements

d(R₁, R₂) = ||log(R₁ᵀ R₂)||

This is the rotation angle of the relative rotation R₁ᵀ R₂.

Trait Implementations§

Source§

impl Clone for SO3

Source§

fn clone(&self) -> SO3

Returns a duplicate of the value. Read more
1.0.0 · Source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
Source§

impl Debug for SO3

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
Source§

impl Display for SO3

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
Source§

impl LieGroup for SO3

Source§

const MATRIX_DIM: usize = 3

Matrix dimension in the fundamental representation. Read more
Source§

type Algebra = So3Algebra

Associated Lie algebra type. Read more
Source§

fn identity() -> Self

The identity element e ∈ G. Read more
Source§

fn compose(&self, other: &Self) -> Self

Group composition (multiplication): g₁ · g₂ Read more
Source§

fn inverse(&self) -> Self

Group inverse: g⁻¹ Read more
Source§

fn conjugate_transpose(&self) -> Self

Adjoint representation element (for matrix groups: conjugate transpose). Read more
Source§

fn adjoint_action(&self, algebra_element: &So3Algebra) -> So3Algebra

Adjoint representation: Ad_g: 𝔤 → 𝔤 Read more
Source§

fn distance_to_identity(&self) -> f64

Geodesic distance from identity: d(g, e) Read more
Source§

fn exp(tangent: &So3Algebra) -> Self

Exponential map: 𝔤 → G Read more
Source§

fn log(&self) -> LogResult<So3Algebra>

Logarithm map: G → 𝔤 (inverse of exponential) Read more
Source§

fn distance(&self, other: &Self) -> f64

Distance between two group elements: d(g, h) Read more
Source§

fn is_near_identity(&self, tolerance: f64) -> bool

Check if this element is approximately the identity. Read more
Source§

fn trace_identity() -> f64

Trace of the identity element Read more
Source§

fn reorthogonalize(&self) -> Self

Project element back onto the group manifold using Gram-Schmidt orthogonalization. Read more
Source§

fn geodesic(&self, other: &Self, t: f64) -> Option<Self>

Geodesic interpolation between two group elements. Read more
Source§

impl Mul<&SO3> for &SO3

Group multiplication: R₁ · R₂

Source§

type Output = SO3

The resulting type after applying the * operator.
Source§

fn mul(self, rhs: &SO3) -> SO3

Performs the * operation. Read more
Source§

impl Mul<&SO3> for SO3

Source§

type Output = SO3

The resulting type after applying the * operator.
Source§

fn mul(self, rhs: &SO3) -> SO3

Performs the * operation. Read more
Source§

impl MulAssign<&SO3> for SO3

Source§

fn mul_assign(&mut self, rhs: &SO3)

Performs the *= operation. Read more
Source§

impl PartialEq for SO3

Source§

fn eq(&self, other: &SO3) -> bool

Tests for self and other values to be equal, and is used by ==.
1.0.0 · Source§

fn ne(&self, other: &Rhs) -> bool

Tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
Source§

impl Compact for SO3

SO(3) is compact

The rotation group is diffeomorphic to ℝP³ (real projective 3-space). All rotations are bounded: ||R|| = 1.

Source§

impl SemiSimple for SO3

SO(3) is semi-simple

Source§

impl Simple for SO3

SO(3) is simple

It has no non-trivial normal subgroups (for dimension > 2).

Source§

impl StructuralPartialEq for SO3

Auto Trait Implementations§

§

impl Freeze for SO3

§

impl RefUnwindSafe for SO3

§

impl Send for SO3

§

impl Sync for SO3

§

impl Unpin for SO3

§

impl UnsafeUnpin for SO3

§

impl UnwindSafe for SO3

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dest: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T> Same for T

Source§

type Output = T

Should always be Self
Source§

impl<SS, SP> SupersetOf<SS> for SP
where SS: SubsetOf<SP>,

Source§

fn to_subset(&self) -> Option<SS>

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more
Source§

fn is_in_subset(&self) -> bool

Checks if self is actually part of its subset T (and can be converted to it).
Source§

fn to_subset_unchecked(&self) -> SS

Use with care! Same as self.to_subset but without any property checks. Always succeeds.
Source§

fn from_subset(element: &SS) -> SP

The inclusion map: converts self to the equivalent element of its superset.
Source§

impl<T> ToOwned for T
where T: Clone,

Source§

type Owned = T

The resulting type after obtaining ownership.
Source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
Source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
Source§

impl<T> ToString for T
where T: Display + ?Sized,

Source§

fn to_string(&self) -> String

Converts the given value to a String. Read more
Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
Source§

impl<V, T> VZip<V> for T
where V: MultiLane<T>,

Source§

fn vzip(self) -> V

Source§

impl<T, Right> ClosedMul<Right> for T
where T: Mul<Right, Output = T> + MulAssign<Right>,

Source§

impl<T, Right> ClosedMulAssign<Right> for T
where T: ClosedMul<Right> + MulAssign<Right>,

Source§

impl<T> Scalar for T
where T: 'static + Clone + PartialEq + Debug,