Skip to main content

apex_manifolds/
so3.rs

1//! SO3 - Special Orthogonal Group in 3D
2//!
3//! This module implements the Special Orthogonal group SO(3), which represents
4//! rotations in 3D space.
5//!
6//! SO(3) elements are represented using nalgebra's UnitQuaternion internally.
7//! SO(3) tangent elements are represented as axis-angle vectors in R³,
8//! where the direction gives the axis of rotation and the magnitude gives the angle.
9//!
10//! The implementation follows the [manif](https://github.com/artivis/manif) C++ library
11//! conventions and provides all operations required by the LieGroup and Tangent traits.
12//!
13//! # Numerical Conditioning
14//!
15//! The Jacobian inverses (Jr⁻¹, Jl⁻¹) contain the term `(1 + cos θ) / (2θ sin θ)` which
16//! is poorly conditioned near θ = 0 (indeterminate 0/0) and θ = π (singularity).
17//! Expected precision for Jr * Jr⁻¹ ≈ I:
18//!
19//! | Angle range     | Precision |
20//! |-----------------|-----------|
21//! | θ < 0.1 rad     | ~1e-8     |
22//! | 0.1–0.5 rad     | ~1e-6     |
23//! | 0.5–π/2 rad     | ~1e-4     |
24//! | θ > π/2 rad     | ~0.01     |
25//!
26//! Composition chains accumulate drift multiplicatively — re-normalize quaternions
27//! periodically for long chains. These properties are consistent with production
28//! Lie group libraries (manif, Sophus, GTSAM).
29//!
30//! ## References
31//!
32//! - Nurlanov et al. (2021): "Exploring SO(3) logarithmic map: degeneracies and derivatives"
33//! - Sophus library: <https://github.com/strasdat/Sophus/issues/179>
34
35use crate::{LieGroup, Tangent};
36use nalgebra::{DVector, Matrix3, Matrix4, Quaternion, Unit, UnitQuaternion, Vector3};
37use std::{
38    fmt,
39    fmt::{Display, Formatter},
40};
41
42/// SO(3) group element representing rotations in 3D.
43///
44/// Internally represented using nalgebra's UnitQuaternion<f64> for efficient rotations.
45#[derive(Clone, PartialEq)]
46pub struct SO3 {
47    /// Internal representation as a unit quaternion
48    quaternion: UnitQuaternion<f64>,
49}
50
51impl Display for SO3 {
52    fn fmt(&self, f: &mut Formatter<'_>) -> fmt::Result {
53        let q = self.quaternion.quaternion();
54        write!(
55            f,
56            "SO3(quaternion: [w: {:.4}, x: {:.4}, y: {:.4}, z: {:.4}])",
57            q.w, q.i, q.j, q.k
58        )
59    }
60}
61
62impl SO3 {
63    /// Space dimension - dimension of the ambient space that the group acts on
64    pub const DIM: usize = 3;
65
66    /// Degrees of freedom - dimension of the tangent space
67    pub const DOF: usize = 3;
68
69    /// Representation size - size of the underlying data representation
70    pub const REP_SIZE: usize = 4;
71
72    /// Get the identity element of the group.
73    ///
74    /// Returns the neutral element e such that e ∘ g = g ∘ e = g for any group element g.
75    pub fn identity() -> Self {
76        SO3 {
77            quaternion: UnitQuaternion::identity(),
78        }
79    }
80
81    /// Get the identity matrix for Jacobians.
82    ///
83    /// Returns the identity matrix in the appropriate dimension for Jacobian computations.
84    pub fn jacobian_identity() -> Matrix3<f64> {
85        Matrix3::<f64>::identity()
86    }
87
88    /// Create a new SO(3) element from a unit quaternion.
89    ///
90    /// # Arguments
91    /// * `quaternion` - Unit quaternion representing rotation
92    #[inline]
93    pub fn new(quaternion: UnitQuaternion<f64>) -> Self {
94        SO3 { quaternion }
95    }
96
97    /// Create SO(3) from quaternion coefficients in G2O convention `[x, y, z, w]`.
98    ///
99    /// This parameter order matches the G2O file format where quaternion components
100    /// are stored as `(qx, qy, qz, qw)`. For nalgebra's `(w, x, y, z)` convention,
101    /// use [`from_quaternion_wxyz()`](Self::from_quaternion_wxyz).
102    ///
103    /// # Arguments
104    /// * `x` - i component of quaternion
105    /// * `y` - j component of quaternion
106    /// * `z` - k component of quaternion
107    /// * `w` - w (real) component of quaternion
108    pub fn from_quaternion_coeffs(x: f64, y: f64, z: f64, w: f64) -> Self {
109        let q = Quaternion::new(w, x, y, z);
110        SO3::new(UnitQuaternion::from_quaternion(q))
111    }
112
113    /// Create SO(3) from quaternion coefficients in nalgebra convention `[w, x, y, z]`.
114    ///
115    /// This parameter order matches nalgebra's `Quaternion::new(w, x, y, z)`.
116    /// For G2O file format order `(qx, qy, qz, qw)`, use
117    /// [`from_quaternion_coeffs()`](Self::from_quaternion_coeffs).
118    ///
119    /// # Arguments
120    /// * `w` - w (real) component of quaternion
121    /// * `x` - i component of quaternion
122    /// * `y` - j component of quaternion
123    /// * `z` - k component of quaternion
124    pub fn from_quaternion_wxyz(w: f64, x: f64, y: f64, z: f64) -> Self {
125        let q = Quaternion::new(w, x, y, z);
126        SO3::new(UnitQuaternion::from_quaternion(q))
127    }
128
129    /// Create SO(3) from Euler angles (roll, pitch, yaw).
130    pub fn from_euler_angles(roll: f64, pitch: f64, yaw: f64) -> Self {
131        let quaternion = UnitQuaternion::from_euler_angles(roll, pitch, yaw);
132        SO3::new(quaternion)
133    }
134
135    /// Create SO(3) from axis-angle representation.
136    pub fn from_axis_angle(axis: &Vector3<f64>, angle: f64) -> Self {
137        let unit_axis = Unit::new_normalize(*axis);
138        let quaternion = UnitQuaternion::from_axis_angle(&unit_axis, angle);
139        SO3::new(quaternion)
140    }
141
142    /// Create SO(3) from scaled axis (axis-angle vector).
143    pub fn from_scaled_axis(axis_angle: Vector3<f64>) -> Self {
144        let quaternion = UnitQuaternion::from_scaled_axis(axis_angle);
145        SO3::new(quaternion)
146    }
147
148    /// Get the quaternion representation.
149    pub fn quaternion(&self) -> UnitQuaternion<f64> {
150        self.quaternion
151    }
152
153    /// Create SO3 from quaternion (alias for new)
154    pub fn from_quaternion(quaternion: UnitQuaternion<f64>) -> Self {
155        Self::new(quaternion)
156    }
157
158    /// Get the quaternion representation (alias for quaternion)
159    pub fn to_quaternion(&self) -> UnitQuaternion<f64> {
160        self.quaternion
161    }
162
163    /// Get the raw quaternion coefficients.
164    pub fn quat(&self) -> Quaternion<f64> {
165        *self.quaternion.quaternion()
166    }
167
168    /// Get the x component of the quaternion.
169    #[inline]
170    pub fn x(&self) -> f64 {
171        self.quaternion.i
172    }
173
174    /// Get the y component of the quaternion.
175    #[inline]
176    pub fn y(&self) -> f64 {
177        self.quaternion.j
178    }
179
180    /// Get the z component of the quaternion.
181    #[inline]
182    pub fn z(&self) -> f64 {
183        self.quaternion.k
184    }
185
186    /// Get the w component of the quaternion.
187    #[inline]
188    pub fn w(&self) -> f64 {
189        self.quaternion.w
190    }
191
192    /// Get the rotation matrix (3x3).
193    pub fn rotation_matrix(&self) -> Matrix3<f64> {
194        self.quaternion.to_rotation_matrix().into_inner()
195    }
196
197    /// Get the homogeneous transformation matrix (4x4).
198    pub fn transform(&self) -> Matrix4<f64> {
199        self.quaternion.to_homogeneous()
200    }
201
202    /// Set the quaternion from coefficients array [w, x, y, z].
203    pub fn set_quaternion(&mut self, coeffs: &[f64; 4]) {
204        let q = Quaternion::new(coeffs[0], coeffs[1], coeffs[2], coeffs[3]);
205        self.quaternion = UnitQuaternion::from_quaternion(q);
206    }
207
208    /// Get coefficients as array [w, x, y, z].
209    #[inline]
210    pub fn coeffs(&self) -> [f64; 4] {
211        let q = self.quaternion.quaternion();
212        [q.w, q.i, q.j, q.k]
213    }
214
215    /// Calculate the distance between two SO3 elements
216    ///
217    /// Computes the geodesic distance, which is the norm of the log map
218    /// of the relative rotation between the two elements.
219    pub fn distance(&self, other: &Self) -> f64 {
220        self.between(other, None, None).log(None).angle()
221    }
222}
223
224// Conversion traits for integration with generic Problem
225impl From<DVector<f64>> for SO3 {
226    fn from(data: DVector<f64>) -> Self {
227        SO3::from_quaternion_wxyz(data[0], data[1], data[2], data[3])
228    }
229}
230
231impl From<SO3> for DVector<f64> {
232    fn from(so3: SO3) -> Self {
233        DVector::from_vec(so3.coeffs().to_vec())
234    }
235}
236
237// Implement basic trait requirements for LieGroup
238impl LieGroup for SO3 {
239    type TangentVector = SO3Tangent;
240    type JacobianMatrix = Matrix3<f64>;
241    type LieAlgebra = Matrix3<f64>;
242
243    /// SO3 inverse.
244    ///
245    /// # Arguments
246    /// * `jacobian` - Optional Jacobian matrix of the inverse wrt self.
247    ///
248    /// # Notes
249    /// R⁻¹ = Rᵀ, for quaternions: q⁻¹ = q*
250    ///
251    /// # Equation 140: Jacobian of Inverse for SO(3)
252    /// J_R⁻¹_R = -Adj(R) = -R
253    ///
254    fn inverse(&self, jacobian: Option<&mut Self::JacobianMatrix>) -> Self {
255        let inverse_quat = self.quaternion.inverse();
256
257        if let Some(jac) = jacobian {
258            *jac = -self.adjoint();
259        }
260
261        SO3 {
262            quaternion: inverse_quat,
263        }
264    }
265
266    /// SO3 composition.
267    ///
268    /// # Arguments
269    /// * `other` - Another SO3 element.
270    /// * `jacobian_self` - Optional Jacobian matrix of the composition wrt self.
271    /// * `jacobian_other` - Optional Jacobian matrix of the composition wrt other.
272    ///
273    /// # Notes
274    /// # Equation 141: Jacobian of the composition wrt self.
275    /// J_QR_R = Adj(R⁻¹) = Rᵀ
276    ///
277    /// # Equation 142: Jacobian of the composition wrt other.
278    /// J_QR_Q = I
279    ///
280    fn compose(
281        &self,
282        other: &Self,
283        jacobian_self: Option<&mut Self::JacobianMatrix>,
284        jacobian_other: Option<&mut Self::JacobianMatrix>,
285    ) -> Self {
286        let result = SO3 {
287            quaternion: self.quaternion * other.quaternion,
288        };
289
290        if let Some(jac_self) = jacobian_self {
291            *jac_self = other.inverse(None).adjoint();
292        }
293
294        if let Some(jac_other) = jacobian_other {
295            *jac_other = Matrix3::identity();
296        }
297
298        result
299    }
300
301    /// Get the SO3 corresponding Lie algebra element in vector form.
302    ///
303    /// # Arguments
304    /// * `jacobian` - Optional Jacobian matrix of the tangent wrt to self.
305    ///
306    /// # Notes
307    /// # Equation 133: Logarithmic map for unit quaternions (S³)
308    /// θu = Log(q) = (2 / ||v||) * v * arctan(||v||, w) ∈ R³
309    ///
310    /// # Equation 144: Inverse of Right Jacobian for SO(3) Exp map
311    /// J_R⁻¹(θ) = I + (1/2) [θ]ₓ + (1/θ² - (1 + cos θ)/(2θ sin θ)) [θ]ₓ²
312    ///
313    fn log(&self, jacobian: Option<&mut Self::JacobianMatrix>) -> Self::TangentVector {
314        debug_assert!(
315            (self.quaternion.norm() - 1.0).abs() < 1e-6,
316            "SO3::log() requires normalized quaternion, norm = {}",
317            self.quaternion.norm()
318        );
319
320        let q = self.quaternion.quaternion();
321        let sin_angle_squared = q.i * q.i + q.j * q.j + q.k * q.k;
322
323        let log_coeff = if sin_angle_squared > crate::SMALL_ANGLE_THRESHOLD {
324            let sin_angle = sin_angle_squared.sqrt();
325            let cos_angle = q.w;
326
327            // When cos_angle < 0, the rotation angle θ > π/2.
328            // Using atan2(sin, cos) directly would give θ/2 in (π/4, π/2].
329            // By negating both arguments: atan2(-sin, -cos), we get θ/2 in
330            // (-3π/4, -π/2], which when doubled gives the rotation angle in the
331            // correct range [-π, π]. This avoids discontinuities and matches the
332            // manif C++ library convention. The key insight is that atan2(-y, -x)
333            // = atan2(y, x) - π (or + π), shifting the result by π.
334            let two_angle = 2.0
335                * if cos_angle < 0.0 {
336                    f64::atan2(-sin_angle, -cos_angle)
337                } else {
338                    f64::atan2(sin_angle, cos_angle)
339                };
340
341            two_angle / sin_angle
342        } else {
343            2.0
344        };
345
346        let axis_angle = SO3Tangent::new(Vector3::new(
347            q.i * log_coeff,
348            q.j * log_coeff,
349            q.k * log_coeff,
350        ));
351
352        if let Some(jac) = jacobian {
353            *jac = axis_angle.right_jacobian_inv();
354        }
355
356        axis_angle
357    }
358
359    fn act(
360        &self,
361        vector: &Vector3<f64>,
362        jacobian_self: Option<&mut Self::JacobianMatrix>,
363        jacobian_vector: Option<&mut Matrix3<f64>>,
364    ) -> Vector3<f64> {
365        let result = self.quaternion * vector;
366
367        if let Some(jac_self) = jacobian_self {
368            // -R * [v]×
369            let vector_hat = SO3Tangent::new(*vector).hat();
370            *jac_self = -self.rotation_matrix() * vector_hat;
371        }
372
373        if let Some(jac_vector) = jacobian_vector {
374            *jac_vector = self.rotation_matrix();
375        }
376
377        result
378    }
379
380    fn adjoint(&self) -> Self::JacobianMatrix {
381        self.rotation_matrix()
382    }
383
384    fn random() -> Self {
385        SO3 {
386            quaternion: UnitQuaternion::from_scaled_axis(Vector3::new(
387                rand::random::<f64>() * 2.0 - 1.0,
388                rand::random::<f64>() * 2.0 - 1.0,
389                rand::random::<f64>() * 2.0 - 1.0,
390            )),
391        }
392    }
393
394    fn jacobian_identity() -> Self::JacobianMatrix {
395        Matrix3::<f64>::identity()
396    }
397
398    fn zero_jacobian() -> Self::JacobianMatrix {
399        Matrix3::<f64>::zeros()
400    }
401
402    fn normalize(&mut self) {
403        let q = self.quaternion.into_inner().normalize();
404        self.quaternion = UnitQuaternion::from_quaternion(q);
405    }
406
407    fn is_valid(&self, tolerance: f64) -> bool {
408        // Check if the quaternion is normalized
409        let norm_diff = (self.quaternion.norm() - 1.0).abs();
410        norm_diff < tolerance
411    }
412
413    /// Vee operator: log(g)^∨.
414    ///
415    /// Maps a group element g ∈ G to its tangent vector log(g)^∨ ∈ 𝔤.
416    /// For SO(3), this is the same as log().
417    fn vee(&self) -> Self::TangentVector {
418        self.log(None)
419    }
420
421    /// Check if the element is approximately equal to another element.
422    ///
423    /// # Arguments
424    /// * `other` - The other element to compare with
425    /// * `tolerance` - The tolerance for the comparison
426    fn is_approx(&self, other: &Self, tolerance: f64) -> bool {
427        let difference = self.right_minus(other, None, None);
428        difference.is_zero(tolerance)
429    }
430}
431
432/// SO(3) tangent space element representing elements in the Lie algebra so(3).
433///
434/// Internally represented as axis-angle vectors in R³ where:
435/// - Direction: axis of rotation (unit vector)
436/// - Magnitude: angle of rotation (radians)
437#[derive(Clone, PartialEq)]
438pub struct SO3Tangent {
439    /// Internal data: axis-angle vector [θx, θy, θz]
440    data: Vector3<f64>,
441}
442
443impl fmt::Display for SO3Tangent {
444    fn fmt(&self, f: &mut fmt::Formatter<'_>) -> fmt::Result {
445        write!(
446            f,
447            "so3(axis-angle: [{:.4}, {:.4}, {:.4}])",
448            self.data.x, self.data.y, self.data.z
449        )
450    }
451}
452
453// Conversion traits for integration with generic Problem
454impl From<DVector<f64>> for SO3Tangent {
455    fn from(data_vector: DVector<f64>) -> Self {
456        SO3Tangent {
457            data: Vector3::new(data_vector[0], data_vector[1], data_vector[2]),
458        }
459    }
460}
461
462impl From<SO3Tangent> for DVector<f64> {
463    fn from(so3_tangent: SO3Tangent) -> Self {
464        DVector::from_vec(vec![
465            so3_tangent.data.x,
466            so3_tangent.data.y,
467            so3_tangent.data.z,
468        ])
469    }
470}
471
472impl SO3Tangent {
473    /// Create a new SO3Tangent from axis-angle vector.
474    ///
475    /// # Arguments
476    /// * `axis_angle` - Axis-angle vector [θx, θy, θz]
477    #[inline]
478    pub fn new(axis_angle: Vector3<f64>) -> Self {
479        SO3Tangent { data: axis_angle }
480    }
481
482    /// Create SO3Tangent from individual components.
483    pub fn from_components(x: f64, y: f64, z: f64) -> Self {
484        SO3Tangent::new(Vector3::new(x, y, z))
485    }
486
487    /// Get the axis-angle vector.
488    #[inline]
489    pub fn axis_angle(&self) -> Vector3<f64> {
490        self.data
491    }
492
493    /// Get the angle of rotation.
494    #[inline]
495    pub fn angle(&self) -> f64 {
496        self.data.norm()
497    }
498
499    /// Get the axis of rotation (normalized).
500    #[inline]
501    pub fn axis(&self) -> Vector3<f64> {
502        let norm = self.data.norm();
503        if norm < f64::EPSILON {
504            Vector3::identity()
505        } else {
506            self.data / norm
507        }
508    }
509
510    /// Get the x component.
511    #[inline]
512    pub fn x(&self) -> f64 {
513        self.data.x
514    }
515
516    /// Get the y component.
517    #[inline]
518    pub fn y(&self) -> f64 {
519        self.data.y
520    }
521
522    /// Get the z component.
523    #[inline]
524    pub fn z(&self) -> f64 {
525        self.data.z
526    }
527
528    /// Get the coefficients as a vector.
529    #[inline]
530    pub fn coeffs(&self) -> Vector3<f64> {
531        self.data
532    }
533
534    /// Get angular velocity representation (alias for axis_angle).
535    pub fn ang(&self) -> Vector3<f64> {
536        self.data
537    }
538}
539
540// Implement LieAlgebra trait for SO3Tangent
541impl Tangent<SO3> for SO3Tangent {
542    /// Dimension of the tangent space
543    const DIM: usize = 3;
544
545    /// SO3 exponential map.
546    ///
547    /// # Arguments
548    /// * `tangent` - Tangent vector [θx, θy, θz]
549    /// * `jacobian` - Optional Jacobian matrix of the SO3 element wrt self.
550    ///
551    /// # Notes
552    /// # Equation 132: Exponential map for unit quaternions (S³)
553    /// q = Exp(θu) = cos(θ/2) + u sin(θ/2) ∈ H
554    ///
555    /// # Equation 143: Right Jacobian for SO(3) Exp map
556    /// J_R(θ) = I - (1 - cos θ)/θ² [θ]ₓ + (θ - sin θ)/θ³ [θ]ₓ²
557    ///
558    fn exp(&self, jacobian: Option<&mut <SO3 as LieGroup>::JacobianMatrix>) -> SO3 {
559        let theta_squared = self.data.norm_squared();
560
561        let quaternion = if theta_squared > crate::SMALL_ANGLE_THRESHOLD {
562            UnitQuaternion::from_scaled_axis(self.data)
563        } else {
564            UnitQuaternion::from_quaternion(Quaternion::new(
565                1.0,
566                self.data.x / 2.0,
567                self.data.y / 2.0,
568                self.data.z / 2.0,
569            ))
570        };
571
572        if let Some(jac) = jacobian {
573            *jac = self.right_jacobian();
574        }
575
576        SO3 { quaternion }
577    }
578
579    /// Right Jacobian for SO(3)
580    ///
581    /// # Notes
582    /// # Equation 143: Right Jacobian for SO(3) Exp map
583    /// J_R(θ) = I - (1 - cos θ)/θ² [θ]ₓ + (θ - sin θ)/θ³ [θ]ₓ²
584    ///
585    fn right_jacobian(&self) -> <SO3 as LieGroup>::JacobianMatrix {
586        self.left_jacobian().transpose()
587    }
588
589    /// Left Jacobian for SO(3)
590    ///
591    /// # Notes
592    /// # Equation 144: Left Jacobian for SO(3) Exp map
593    /// J_R⁻¹(θ) = I + (1 - cos θ)/θ² [θ]ₓ + (θ - sin θ)/θ³ [θ]ₓ²
594    ///
595    fn left_jacobian(&self) -> <SO3 as LieGroup>::JacobianMatrix {
596        let angle = self.data.norm_squared();
597        let tangent_skew = self.hat();
598
599        if angle <= crate::SMALL_ANGLE_THRESHOLD {
600            Matrix3::identity() + 0.5 * tangent_skew
601        } else {
602            let theta = angle.sqrt();
603            let sin_theta = theta.sin();
604            let cos_theta = theta.cos();
605
606            Matrix3::identity()
607                + (1.0 - cos_theta) / angle * tangent_skew
608                + (theta - sin_theta) / (angle * theta) * tangent_skew * tangent_skew
609        }
610    }
611
612    /// Right Jacobian inverse for SO(3)
613    ///
614    /// Computed as transpose of left Jacobian inverse: Jr⁻¹ = (Jl⁻¹)ᵀ
615    ///
616    /// Has numerical conditioning issues near θ → π (sin θ → 0).
617    ///
618    fn right_jacobian_inv(&self) -> <SO3 as LieGroup>::JacobianMatrix {
619        self.left_jacobian_inv().transpose()
620    }
621
622    /// Left Jacobian inverse for SO(3)
623    ///
624    /// J_L⁻¹(θ) = I - (1/2) [θ]ₓ + (1/θ² - (1 + cos θ)/(2θ sin θ)) [θ]ₓ²
625    ///
626    /// Has numerical conditioning issues near θ → π (sin θ → 0).
627    ///
628    fn left_jacobian_inv(&self) -> <SO3 as LieGroup>::JacobianMatrix {
629        let angle = self.data.norm_squared();
630        let tangent_skew = self.hat();
631
632        if angle <= crate::SMALL_ANGLE_THRESHOLD {
633            Matrix3::identity() - 0.5 * tangent_skew
634        } else {
635            let theta = angle.sqrt();
636            let sin_theta = theta.sin();
637            let cos_theta = theta.cos();
638
639            Matrix3::identity() - (0.5 * tangent_skew)
640                + (1.0 / angle - (1.0 + cos_theta) / (2.0 * theta * sin_theta))
641                    * tangent_skew
642                    * tangent_skew
643        }
644    }
645
646    /// Hat map for SO(3)
647    ///
648    /// # Notes
649    /// [θ]ₓ = [0 -θz θy; θz 0 -θx; -θy θx 0]
650    ///
651    fn hat(&self) -> <SO3 as LieGroup>::LieAlgebra {
652        Matrix3::new(
653            0.0,
654            -self.data.z,
655            self.data.y,
656            self.data.z,
657            0.0,
658            -self.data.x,
659            -self.data.y,
660            self.data.x,
661            0.0,
662        )
663    }
664
665    fn zero() -> <SO3 as LieGroup>::TangentVector {
666        Self::new(Vector3::zeros())
667    }
668
669    fn random() -> <SO3 as LieGroup>::TangentVector {
670        Self::new(Vector3::new(
671            rand::random::<f64>() * 0.2 - 0.1,
672            rand::random::<f64>() * 0.2 - 0.1,
673            rand::random::<f64>() * 0.2 - 0.1,
674        ))
675    }
676
677    fn is_zero(&self, tolerance: f64) -> bool {
678        self.data.norm() < tolerance
679    }
680
681    fn normalize(&mut self) {
682        let norm = self.data.norm();
683        if norm > f64::EPSILON {
684            self.data /= norm;
685        }
686    }
687
688    fn normalized(&self) -> <SO3 as LieGroup>::TangentVector {
689        let norm = self.data.norm();
690        if norm > f64::EPSILON {
691            SO3Tangent::new(self.data / norm)
692        } else {
693            Self::zero()
694        }
695    }
696
697    /// Small adjoint matrix for SO(3).
698    ///
699    /// For SO(3), the small adjoint is the skew-symmetric matrix (hat operator).
700    fn small_adj(&self) -> <SO3 as LieGroup>::JacobianMatrix {
701        self.hat()
702    }
703
704    /// Lie bracket for SO(3).
705    ///
706    /// Computes the Lie bracket [this, other] = this.small_adj() * other.
707    fn lie_bracket(&self, other: &Self) -> <SO3 as LieGroup>::TangentVector {
708        let bracket_result = self.small_adj() * other.data;
709        SO3Tangent::new(bracket_result)
710    }
711
712    /// Check if this tangent vector is approximately equal to another.
713    ///
714    /// # Arguments
715    /// * `other` - The other tangent vector to compare with
716    /// * `tolerance` - The tolerance for the comparison
717    fn is_approx(&self, other: &Self, tolerance: f64) -> bool {
718        (self.data - other.data).norm() < tolerance
719    }
720
721    /// Get the ith generator of the SO(3) Lie algebra.
722    ///
723    /// # Arguments
724    /// * `i` - Index of the generator (0, 1, or 2 for SO(3))
725    ///
726    /// # Returns
727    /// The generator matrix
728    fn generator(&self, i: usize) -> <SO3 as LieGroup>::LieAlgebra {
729        assert!(i < 3, "SO(3) only has generators for indices 0, 1, 2");
730
731        match i {
732            0 => {
733                // Generator E1 for x-axis rotation
734                Matrix3::new(0.0, 0.0, 0.0, 0.0, 0.0, -1.0, 0.0, 1.0, 0.0)
735            }
736            1 => {
737                // Generator E2 for y-axis rotation
738                Matrix3::new(0.0, 0.0, 1.0, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0)
739            }
740            2 => {
741                // Generator E3 for z-axis rotation
742                Matrix3::new(0.0, -1.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0)
743            }
744            _ => unreachable!(),
745        }
746    }
747}
748
749#[cfg(test)]
750mod tests {
751    use super::*;
752    use core::f64;
753    use std::f64::consts::PI;
754
755    const TOLERANCE: f64 = 1e-12;
756
757    #[test]
758    fn test_so3_constructor_datatype() {
759        let so3 = SO3::from_quaternion_coeffs(0.0, 0.0, 0.0, 1.0);
760        assert_eq!(0.0, so3.x());
761        assert_eq!(0.0, so3.y());
762        assert_eq!(0.0, so3.z());
763        assert_eq!(1.0, so3.w());
764    }
765
766    #[test]
767    fn test_so3_constructor_quat() {
768        let quat = UnitQuaternion::identity();
769        let so3 = SO3::new(quat);
770        assert_eq!(0.0, so3.x());
771        assert_eq!(0.0, so3.y());
772        assert_eq!(0.0, so3.z());
773        assert_eq!(1.0, so3.w());
774    }
775
776    #[test]
777    fn test_so3_constructor_euler() {
778        let so3 = SO3::from_euler_angles(0.0, 0.0, 0.0);
779        assert_eq!(0.0, so3.x());
780        assert_eq!(0.0, so3.y());
781        assert_eq!(0.0, so3.z());
782        assert_eq!(1.0, so3.w());
783    }
784
785    #[test]
786    fn test_so3_identity() {
787        let so3 = SO3::identity();
788        assert_eq!(0.0, so3.x());
789        assert_eq!(0.0, so3.y());
790        assert_eq!(0.0, so3.z());
791        assert_eq!(1.0, so3.w());
792    }
793
794    #[test]
795    fn test_so3_coeffs() {
796        // Create from normalized coefficients
797        let so3 = SO3::from_quaternion_coeffs(0.0, 0.0, 0.0, 1.0);
798        let coeffs = so3.coeffs();
799        assert!((coeffs[0] - 1.0).abs() < TOLERANCE); // w
800        assert!((coeffs[1] - 0.0).abs() < TOLERANCE); // x
801        assert!((coeffs[2] - 0.0).abs() < TOLERANCE); // y
802        assert!((coeffs[3] - 0.0).abs() < TOLERANCE); // z
803
804        // Test with non-normalized input - should get normalized output
805        let so3 = SO3::from_quaternion_coeffs(0.1, 0.2, 0.3, 0.4);
806        let coeffs = so3.coeffs();
807        let original_quat = Quaternion::new(0.4, 0.1, 0.2, 0.3);
808        let normalized_quat = original_quat.normalize();
809        assert!((coeffs[0] - normalized_quat.w).abs() < TOLERANCE);
810        assert!((coeffs[1] - normalized_quat.i).abs() < TOLERANCE);
811        assert!((coeffs[2] - normalized_quat.j).abs() < TOLERANCE);
812        assert!((coeffs[3] - normalized_quat.k).abs() < TOLERANCE);
813    }
814
815    #[test]
816    fn test_so3_random() {
817        let so3 = SO3::random();
818        assert!((so3.quaternion().norm() - 1.0).abs() < TOLERANCE);
819    }
820
821    #[test]
822    fn test_so3_transform() {
823        let so3 = SO3::identity();
824        let transform = so3.transform();
825
826        assert_eq!(4, transform.nrows());
827        assert_eq!(4, transform.ncols());
828
829        // Check identity transform
830        for i in 0..4 {
831            for j in 0..4 {
832                if i == j {
833                    assert!((transform[(i, j)] - 1.0).abs() < TOLERANCE);
834                } else {
835                    assert!(transform[(i, j)].abs() < TOLERANCE);
836                }
837            }
838        }
839    }
840
841    #[test]
842    fn test_so3_rotation() {
843        let so3 = SO3::identity();
844        let rotation = so3.rotation_matrix();
845
846        assert_eq!(3, rotation.nrows());
847        assert_eq!(3, rotation.ncols());
848
849        // Check identity rotation
850        for i in 0..3 {
851            for j in 0..3 {
852                if i == j {
853                    assert!((rotation[(i, j)] - 1.0).abs() < TOLERANCE);
854                } else {
855                    assert!(rotation[(i, j)].abs() < TOLERANCE);
856                }
857            }
858        }
859    }
860
861    #[test]
862    fn test_so3_inverse() {
863        // inverse of identity is identity
864        let so3 = SO3::identity();
865        let so3_inv = so3.inverse(None);
866        assert_eq!(0.0, so3_inv.x());
867        assert_eq!(0.0, so3_inv.y());
868        assert_eq!(0.0, so3_inv.z());
869        assert_eq!(1.0, so3_inv.w());
870
871        // inverse of random in quaternion form is conjugate
872        let so3 = SO3::random();
873        let so3_inv = so3.inverse(None);
874        assert!((so3.x() + so3_inv.x()).abs() < TOLERANCE);
875        assert!((so3.y() + so3_inv.y()).abs() < TOLERANCE);
876        assert!((so3.z() + so3_inv.z()).abs() < TOLERANCE);
877        assert!((so3.w() - so3_inv.w()).abs() < TOLERANCE);
878    }
879
880    #[test]
881    fn test_so3_inverse_jacobian() {
882        let so3 = SO3::identity();
883        let mut jacobian = Matrix3::zeros();
884        let so3_inv = so3.inverse(Some(&mut jacobian));
885
886        // Check result
887        assert_eq!(0.0, so3_inv.x());
888        assert_eq!(0.0, so3_inv.y());
889        assert_eq!(0.0, so3_inv.z());
890        assert_eq!(1.0, so3_inv.w());
891
892        // Check Jacobian is negative identity
893        let expected_jac = -Matrix3::identity();
894        assert!((jacobian - expected_jac).norm() < TOLERANCE);
895    }
896
897    #[test]
898    fn test_so3_rplus() {
899        // Adding zero to identity
900        let so3a = SO3::identity();
901        let so3b = SO3Tangent::new(Vector3::zeros());
902        let so3c = so3a.right_plus(&so3b, None, None);
903        assert_eq!(0.0, so3c.x());
904        assert_eq!(0.0, so3c.y());
905        assert_eq!(0.0, so3c.z());
906        assert_eq!(1.0, so3c.w());
907
908        // Adding zero to random
909        let so3a = SO3::random();
910        let so3c = so3a.right_plus(&so3b, None, None);
911        assert!((so3a.x() - so3c.x()).abs() < TOLERANCE);
912        assert!((so3a.y() - so3c.y()).abs() < TOLERANCE);
913        assert!((so3a.z() - so3c.z()).abs() < TOLERANCE);
914        assert!((so3a.w() - so3c.w()).abs() < TOLERANCE);
915    }
916
917    #[test]
918    fn test_so3_lplus() {
919        // Adding zero to identity
920        let so3a = SO3::identity();
921        let so3t = SO3Tangent::new(Vector3::zeros());
922        let so3c = so3a.left_plus(&so3t, None, None);
923        assert_eq!(0.0, so3c.x());
924        assert_eq!(0.0, so3c.y());
925        assert_eq!(0.0, so3c.z());
926        assert_eq!(1.0, so3c.w());
927
928        // Adding zero to random
929        let so3a = SO3::random();
930        let so3c = so3a.left_plus(&so3t, None, None);
931        assert!((so3a.x() - so3c.x()).abs() < TOLERANCE);
932        assert!((so3a.y() - so3c.y()).abs() < TOLERANCE);
933        assert!((so3a.z() - so3c.z()).abs() < TOLERANCE);
934        assert!((so3a.w() - so3c.w()).abs() < TOLERANCE);
935    }
936
937    #[test]
938    fn test_so3_rminus() {
939        // identity minus identity is zero
940        let so3a = SO3::identity();
941        let so3b = SO3::identity();
942        let so3c = so3a.right_minus(&so3b, None, None);
943        assert!(so3c.x().abs() < TOLERANCE);
944        assert!(so3c.y().abs() < TOLERANCE);
945        assert!(so3c.z().abs() < TOLERANCE);
946
947        // random minus the same is zero
948        let so3a = SO3::random();
949        let so3b = so3a.clone();
950        let so3c = so3a.right_minus(&so3b, None, None);
951        assert!(so3c.data.norm() < TOLERANCE);
952    }
953
954    #[test]
955    fn test_so3_minus() {
956        // minus is the same as right_minus
957        let so3a = SO3::random();
958        let so3b = SO3::random();
959        let so3c = so3a.minus(&so3b, None, None);
960        let so3d = so3a.right_minus(&so3b, None, None);
961        assert!((so3c.data - so3d.data).norm() < TOLERANCE);
962    }
963
964    #[test]
965    fn test_so3_exp_log() {
966        // exp of zero is identity
967        let so3t = SO3Tangent::new(Vector3::zeros());
968        let so3 = so3t.exp(None);
969        assert_eq!(0.0, so3.x());
970        assert_eq!(0.0, so3.y());
971        assert_eq!(0.0, so3.z());
972        assert_eq!(1.0, so3.w());
973
974        // exp of negative is inverse of exp
975        let so3t = SO3Tangent::new(Vector3::new(0.1, 0.2, 0.3));
976        let so3 = so3t.exp(None);
977        let so3n = SO3Tangent::new(Vector3::new(-0.1, -0.2, -0.3));
978        let so3_inv = so3n.exp(None);
979        assert!((so3_inv.x() + so3.x()).abs() < TOLERANCE);
980        assert!((so3_inv.y() + so3.y()).abs() < TOLERANCE);
981        assert!((so3_inv.z() + so3.z()).abs() < TOLERANCE);
982        assert!((so3_inv.w() - so3.w()).abs() < TOLERANCE);
983    }
984
985    #[test]
986    fn test_so3_log() {
987        // log of identity is zero
988        let so3 = SO3::identity();
989        let so3_log = so3.log(None);
990        assert!(so3_log.x().abs() < TOLERANCE);
991        assert!(so3_log.y().abs() < TOLERANCE);
992        assert!(so3_log.z().abs() < TOLERANCE);
993
994        // log of inverse is negative log
995        let so3 = SO3::random();
996        let so3_log = so3.log(None);
997        let so3_inv_log = so3.inverse(None).log(None);
998        assert!((so3_inv_log.x() + so3_log.x()).abs() < TOLERANCE);
999        assert!((so3_inv_log.y() + so3_log.y()).abs() < TOLERANCE);
1000        assert!((so3_inv_log.z() + so3_log.z()).abs() < TOLERANCE);
1001    }
1002
1003    #[test]
1004    fn test_so3_tangent_hat() {
1005        let so3_tan = SO3Tangent::new(Vector3::new(1.0, 2.0, 3.0));
1006        let so3_lie = so3_tan.hat();
1007
1008        assert!((so3_lie[(0, 0)] - 0.0).abs() < TOLERANCE);
1009        assert!((so3_lie[(0, 1)] + 3.0).abs() < TOLERANCE);
1010        assert!((so3_lie[(0, 2)] - 2.0).abs() < TOLERANCE);
1011        assert!((so3_lie[(1, 0)] - 3.0).abs() < TOLERANCE);
1012        assert!((so3_lie[(1, 1)] - 0.0).abs() < TOLERANCE);
1013        assert!((so3_lie[(1, 2)] + 1.0).abs() < TOLERANCE);
1014        assert!((so3_lie[(2, 0)] + 2.0).abs() < TOLERANCE);
1015        assert!((so3_lie[(2, 1)] - 1.0).abs() < TOLERANCE);
1016        assert!((so3_lie[(2, 2)] - 0.0).abs() < TOLERANCE);
1017    }
1018
1019    #[test]
1020    fn test_so3_act() {
1021        let so3 = SO3::identity();
1022        let transformed_point = so3.act(&Vector3::new(1.0, 1.0, 1.0), None, None);
1023        assert!((transformed_point.x - 1.0).abs() < TOLERANCE);
1024        assert!((transformed_point.y - 1.0).abs() < TOLERANCE);
1025        assert!((transformed_point.z - 1.0).abs() < TOLERANCE);
1026
1027        let so3 = SO3::from_euler_angles(PI, PI / 2.0, PI / 4.0);
1028        let transformed_point = so3.act(&Vector3::new(1.0, 1.0, 1.0), None, None);
1029        assert!((transformed_point.x - 0.0).abs() < TOLERANCE);
1030        assert!((transformed_point.y + f64::consts::SQRT_2).abs() < 1e-10);
1031        assert!((transformed_point.z + 1.0).abs() < TOLERANCE);
1032    }
1033
1034    #[test]
1035    fn test_so3_tangent_angular_velocity() {
1036        let so3tan = SO3Tangent::new(Vector3::new(1.0, 2.0, 3.0));
1037        let ang_vel = so3tan.ang();
1038        assert!((ang_vel - Vector3::new(1.0, 2.0, 3.0)).norm() < TOLERANCE);
1039    }
1040
1041    #[test]
1042    fn test_so3_compose() {
1043        let so3_1 = SO3::random();
1044        let so3_2 = SO3::random();
1045        let composed = so3_1.compose(&so3_2, None, None);
1046        assert!(composed.is_valid(TOLERANCE));
1047
1048        // Test composition with identity
1049        let identity = SO3::identity();
1050        let composed_with_identity = so3_1.compose(&identity, None, None);
1051        assert!((composed_with_identity.distance(&so3_1)).abs() < TOLERANCE);
1052    }
1053
1054    #[test]
1055    fn test_so3_exp_log_consistency() {
1056        let tangent = SO3Tangent::new(Vector3::new(0.1, 0.2, 0.3));
1057        let so3 = tangent.exp(None);
1058        let recovered_tangent = so3.log(None);
1059        assert!((tangent.data - recovered_tangent.data).norm() < TOLERANCE);
1060    }
1061
1062    #[test]
1063    fn test_so3_right_left_jacobian_relationship() {
1064        // For zero tangent, left and right Jacobians should be equal (both identity)
1065        let tangent = SO3Tangent::new(Vector3::zeros());
1066        let ljac = tangent.left_jacobian();
1067        let rjac = tangent.right_jacobian();
1068        assert!((ljac - rjac).norm() < TOLERANCE);
1069        assert!((ljac - Matrix3::identity()).norm() < TOLERANCE);
1070
1071        // For non-zero tangent, test the general relationship
1072        let tangent = SO3Tangent::new(Vector3::new(0.1, 0.2, 0.3));
1073        let ljac = tangent.left_jacobian();
1074        let rjac = tangent.right_jacobian();
1075
1076        // The correct relationship for SO(3) should be that both are transposes
1077        // when the tangent is small enough
1078        assert!((ljac - rjac.transpose()).norm() < TOLERANCE);
1079        assert!((rjac - ljac.transpose()).norm() < TOLERANCE);
1080    }
1081
1082    #[test]
1083    fn test_so3_manifold_properties() {
1084        assert_eq!(SO3::DIM, 3);
1085        assert_eq!(SO3::DOF, 3);
1086        assert_eq!(SO3::REP_SIZE, 4);
1087    }
1088
1089    #[test]
1090    fn test_so3_normalize() {
1091        let mut so3 = SO3::from_quaternion_coeffs(0.5, 0.5, 0.5, 0.5);
1092        so3.normalize();
1093        assert!(so3.is_valid(TOLERANCE));
1094    }
1095
1096    #[test]
1097    fn test_so3_tangent_norms() {
1098        let tangent = SO3Tangent::new(Vector3::new(3.0, 4.0, 0.0));
1099        let norm = tangent.data.norm();
1100        assert!((norm - 5.0).abs() < TOLERANCE);
1101
1102        let squared_norm = tangent.data.norm_squared();
1103        assert!((squared_norm - 25.0).abs() < TOLERANCE);
1104    }
1105
1106    #[test]
1107    fn test_so3_tangent_zero() {
1108        let zero = SO3Tangent::zero();
1109        assert!(zero.data.norm() < TOLERANCE);
1110
1111        let tangent = SO3Tangent::new(Vector3::zeros());
1112        assert!(tangent.is_zero(TOLERANCE));
1113    }
1114
1115    #[test]
1116    fn test_so3_tangent_normalize() {
1117        let mut tangent = SO3Tangent::new(Vector3::new(3.0, 4.0, 0.0));
1118        tangent.normalize();
1119        assert!((tangent.data.norm() - 1.0).abs() < TOLERANCE);
1120    }
1121
1122    #[test]
1123    fn test_so3_adjoint() {
1124        let so3 = SO3::random();
1125        let adj = so3.adjoint();
1126        assert_eq!(adj.nrows(), 3);
1127        assert_eq!(adj.ncols(), 3);
1128
1129        // For SO(3), adjoint is the rotation matrix, so det should be 1
1130        let det = adj.determinant();
1131        assert!((det - 1.0).abs() < TOLERANCE);
1132    }
1133
1134    #[test]
1135    fn test_so3_small_angle_approximations() {
1136        let small_tangent = SO3Tangent::new(Vector3::new(1e-8, 2e-8, 3e-8));
1137        let so3 = small_tangent.exp(None);
1138        let recovered = so3.log(None);
1139        assert!((small_tangent.data - recovered.data).norm() < TOLERANCE);
1140    }
1141
1142    #[test]
1143    fn test_so3_specific_rotations() {
1144        // Test rotation around X axis
1145        let so3_x = SO3::from_axis_angle(&Vector3::x(), PI / 2.0);
1146        let point_y = Vector3::y();
1147        let rotated = so3_x.act(&point_y, None, None);
1148        assert!((rotated - Vector3::z()).norm() < TOLERANCE);
1149
1150        // Test rotation around Z axis
1151        let so3_z = SO3::from_axis_angle(&Vector3::z(), PI / 2.0);
1152        let point_x = Vector3::x();
1153        let rotated = so3_z.act(&point_x, None, None);
1154        assert!((rotated - Vector3::y()).norm() < TOLERANCE);
1155    }
1156
1157    #[test]
1158    fn test_so3_from_components() {
1159        let so3 = SO3::from_quaternion_coeffs(0.0, 0.0, 0.0, 1.0);
1160        assert_eq!(so3.x(), 0.0);
1161        assert_eq!(so3.y(), 0.0);
1162        assert_eq!(so3.z(), 0.0);
1163        assert_eq!(so3.w(), 1.0);
1164    }
1165
1166    #[test]
1167    fn test_so3_tangent_from_components() {
1168        let tangent = SO3Tangent::from_components(1.0, 2.0, 3.0);
1169        assert_eq!(tangent.x(), 1.0);
1170        assert_eq!(tangent.y(), 2.0);
1171        assert_eq!(tangent.z(), 3.0);
1172    }
1173
1174    #[test]
1175    fn test_so3_consistency_with_manif() {
1176        // Test that operations are consistent with manif library expectations
1177        let so3_1 = SO3::random();
1178        let so3_2 = SO3::random();
1179
1180        // Test associativity: (R1 * R2) * R3 = R1 * (R2 * R3)
1181        let so3_3 = SO3::random();
1182        let left_assoc = so3_1
1183            .compose(&so3_2, None, None)
1184            .compose(&so3_3, None, None);
1185        let right_assoc = so3_1.compose(&so3_2.compose(&so3_3, None, None), None, None);
1186
1187        assert!(left_assoc.distance(&right_assoc) < 1e-10);
1188    }
1189
1190    #[test]
1191    fn test_so3_tangent_accessors() {
1192        let tangent = SO3Tangent::new(Vector3::new(1.0, 2.0, 3.0));
1193        assert_eq!(tangent.x(), 1.0);
1194        assert_eq!(tangent.y(), 2.0);
1195        assert_eq!(tangent.z(), 3.0);
1196
1197        let coeffs = tangent.coeffs();
1198        assert_eq!(coeffs, Vector3::new(1.0, 2.0, 3.0));
1199    }
1200
1201    #[test]
1202    fn test_so3_between() {
1203        let so3_1 = SO3::random();
1204        let so3_2 = SO3::random();
1205        let between = so3_1.between(&so3_2, None, None);
1206
1207        // Check that so3_1 * between = so3_2
1208        let result = so3_1.compose(&between, None, None);
1209        assert!(result.distance(&so3_2) < TOLERANCE);
1210    }
1211
1212    #[test]
1213    fn test_so3_distance() {
1214        let so3_1 = SO3::random();
1215        let so3_2 = SO3::random();
1216        let distance = so3_1.distance(&so3_2);
1217        assert!(distance >= 0.0);
1218        assert!(so3_1.distance(&so3_1) < TOLERANCE);
1219    }
1220
1221    // New tests for the additional functions
1222
1223    #[test]
1224    fn test_so3_vee() {
1225        let so3 = SO3::random();
1226        let tangent_log = so3.log(None);
1227        let tangent_vee = so3.vee();
1228
1229        assert!((tangent_log.data - tangent_vee.data).norm() < 1e-10);
1230    }
1231
1232    #[test]
1233    fn test_so3_is_approx() {
1234        let so3_1 = SO3::random();
1235        let so3_2 = so3_1.clone();
1236
1237        assert!(so3_1.is_approx(&so3_1, 1e-10));
1238        assert!(so3_1.is_approx(&so3_2, 1e-10));
1239
1240        // Test with small perturbation
1241        let small_tangent = SO3Tangent::new(Vector3::new(1e-12, 1e-12, 1e-12));
1242        let so3_perturbed = so3_1.right_plus(&small_tangent, None, None);
1243        assert!(so3_1.is_approx(&so3_perturbed, 1e-10));
1244    }
1245
1246    #[test]
1247    fn test_so3_tangent_small_adj() {
1248        let axis_angle = Vector3::new(0.1, 0.2, 0.3);
1249        let tangent = SO3Tangent::new(axis_angle);
1250        let small_adj = tangent.small_adj();
1251        let hat_matrix = tangent.hat();
1252
1253        // For SO(3), small adjoint equals hat matrix
1254        assert!((small_adj - hat_matrix).norm() < 1e-10);
1255    }
1256
1257    #[test]
1258    fn test_so3_tangent_lie_bracket() {
1259        let tangent_a = SO3Tangent::new(Vector3::new(0.1, 0.0, 0.0));
1260        let tangent_b = SO3Tangent::new(Vector3::new(0.0, 0.2, 0.0));
1261
1262        let bracket_ab = tangent_a.lie_bracket(&tangent_b);
1263        let bracket_ba = tangent_b.lie_bracket(&tangent_a);
1264
1265        // Anti-symmetry test: [a,b] = -[b,a]
1266        assert!((bracket_ab.data + bracket_ba.data).norm() < 1e-10);
1267
1268        // [a,a] = 0
1269        let bracket_aa = tangent_a.lie_bracket(&tangent_a);
1270        assert!(bracket_aa.is_zero(1e-10));
1271
1272        // Verify bracket relationship with hat operator
1273        let bracket_hat = bracket_ab.hat();
1274        let expected = tangent_a.hat() * tangent_b.hat() - tangent_b.hat() * tangent_a.hat();
1275        assert!((bracket_hat - expected).norm() < 1e-10);
1276    }
1277
1278    #[test]
1279    fn test_so3_tangent_is_approx() {
1280        let tangent_1 = SO3Tangent::new(Vector3::new(0.1, 0.2, 0.3));
1281        let tangent_2 = SO3Tangent::new(Vector3::new(0.1 + 1e-12, 0.2, 0.3));
1282        let tangent_3 = SO3Tangent::new(Vector3::new(0.5, 0.6, 0.7));
1283
1284        assert!(tangent_1.is_approx(&tangent_1, 1e-10));
1285        assert!(tangent_1.is_approx(&tangent_2, 1e-10));
1286        assert!(!tangent_1.is_approx(&tangent_3, 1e-10));
1287    }
1288
1289    #[test]
1290    fn test_so3_generators() {
1291        let tangent = SO3Tangent::new(Vector3::new(1.0, 1.0, 1.0));
1292
1293        // Test all three generators
1294        for i in 0..3 {
1295            let generator = tangent.generator(i);
1296
1297            // Generator should be skew-symmetric
1298            assert!((generator + generator.transpose()).norm() < 1e-10);
1299
1300            // Generator should have trace zero
1301            assert!(generator.trace().abs() < 1e-10);
1302        }
1303
1304        // Test specific values for the generators
1305        let e1 = tangent.generator(0);
1306        let e2 = tangent.generator(1);
1307        let e3 = tangent.generator(2);
1308
1309        // Expected generators based on C++ manif implementation
1310        let expected_e1 = Matrix3::new(0.0, 0.0, 0.0, 0.0, 0.0, -1.0, 0.0, 1.0, 0.0);
1311        let expected_e2 = Matrix3::new(0.0, 0.0, 1.0, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0);
1312        let expected_e3 = Matrix3::new(0.0, -1.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0);
1313
1314        assert!((e1 - expected_e1).norm() < 1e-10);
1315        assert!((e2 - expected_e2).norm() < 1e-10);
1316        assert!((e3 - expected_e3).norm() < 1e-10);
1317    }
1318
1319    #[test]
1320    #[should_panic]
1321    fn test_so3_generator_invalid_index() {
1322        let tangent = SO3Tangent::new(Vector3::new(1.0, 1.0, 1.0));
1323        let _generator = tangent.generator(3); // Should panic for SO(3)
1324    }
1325
1326    #[test]
1327    fn test_so3_jacobi_identity() {
1328        // Test Jacobi identity: [x,[y,z]]+[y,[z,x]]+[z,[x,y]]=0
1329        let x = SO3Tangent::new(Vector3::new(0.1, 0.0, 0.0));
1330        let y = SO3Tangent::new(Vector3::new(0.0, 0.2, 0.0));
1331        let z = SO3Tangent::new(Vector3::new(0.0, 0.0, 0.3));
1332
1333        let term1 = x.lie_bracket(&y.lie_bracket(&z));
1334        let term2 = y.lie_bracket(&z.lie_bracket(&x));
1335        let term3 = z.lie_bracket(&x.lie_bracket(&y));
1336
1337        let jacobi_sum = SO3Tangent::new(term1.data + term2.data + term3.data);
1338        assert!(jacobi_sum.is_zero(1e-10));
1339    }
1340
1341    // T1: Numerical Jacobian Verification Tests
1342
1343    #[test]
1344    fn test_so3_right_jacobian_numerical() {
1345        // The right Jacobian Jr relates tangent space perturbations to group elements:
1346        // exp(ξ + δξ) ≈ exp(ξ) ∘ exp(Jr(ξ)·δξ)
1347        // Equivalently: Jr(ξ)·δξ ≈ log(exp(ξ)^{-1} ∘ exp(ξ + δξ))
1348
1349        let xi = Vector3::new(0.1, 0.2, 0.3);
1350        let tangent = SO3Tangent::new(xi);
1351        let jr_analytical = tangent.right_jacobian();
1352
1353        // Test with small perturbations in each direction
1354        let delta_size = 1e-6;
1355        let test_deltas = vec![
1356            Vector3::new(delta_size, 0.0, 0.0),
1357            Vector3::new(0.0, delta_size, 0.0),
1358            Vector3::new(0.0, 0.0, delta_size),
1359        ];
1360
1361        for delta in test_deltas {
1362            // Analytical: Jr * δξ
1363            let analytical_result = jr_analytical * delta;
1364
1365            // Numerical: log(exp(ξ)^{-1} * exp(ξ + δξ))
1366            let base = SO3Tangent::new(xi).exp(None);
1367            let perturbed = SO3Tangent::new(xi + delta).exp(None);
1368            let base_inv = base.inverse(None);
1369            let diff_element = base_inv.compose(&perturbed, None, None);
1370            let diff_log = diff_element.log(None);
1371            let numerical_result = Vector3::new(diff_log.x(), diff_log.y(), diff_log.z());
1372
1373            let error = (analytical_result - numerical_result).norm();
1374            assert!(
1375                error < 1e-7,
1376                "Right Jacobian verification failed: error = {}, delta = {:?}",
1377                error,
1378                delta
1379            );
1380        }
1381    }
1382
1383    #[test]
1384    fn test_so3_left_jacobian_numerical() {
1385        // The left Jacobian Jl relates tangent space perturbations to group elements:
1386        // exp(ξ + δξ) ≈ exp(Jl(ξ)·δξ) ∘ exp(ξ)
1387        // Equivalently: Jl(ξ)·δξ ≈ log(exp(ξ + δξ) ∘ exp(ξ)^{-1})
1388
1389        let xi = Vector3::new(0.1, 0.2, 0.3);
1390        let tangent = SO3Tangent::new(xi);
1391        let jl_analytical = tangent.left_jacobian();
1392
1393        // Test with small perturbations in each direction
1394        let delta_size = 1e-6;
1395        let test_deltas = vec![
1396            Vector3::new(delta_size, 0.0, 0.0),
1397            Vector3::new(0.0, delta_size, 0.0),
1398            Vector3::new(0.0, 0.0, delta_size),
1399        ];
1400
1401        for delta in test_deltas {
1402            // Analytical: Jl * δξ
1403            let analytical_result = jl_analytical * delta;
1404
1405            // Numerical: log(exp(ξ + δξ) * exp(ξ)^{-1})
1406            let base = SO3Tangent::new(xi).exp(None);
1407            let perturbed = SO3Tangent::new(xi + delta).exp(None);
1408            let base_inv = base.inverse(None);
1409            let diff_element = perturbed.compose(&base_inv, None, None);
1410            let diff_log = diff_element.log(None);
1411            let numerical_result = Vector3::new(diff_log.x(), diff_log.y(), diff_log.z());
1412
1413            let error = (analytical_result - numerical_result).norm();
1414            assert!(
1415                error < 1e-7,
1416                "Left Jacobian verification failed: error = {}, delta = {:?}",
1417                error,
1418                delta
1419            );
1420        }
1421    }
1422
1423    #[test]
1424    fn test_so3_accumulated_error_small_rotations() {
1425        // Compose 1000 small rotations, verify final result
1426        let small_rotation = SO3::from_scaled_axis(Vector3::new(0.001, 0.002, -0.001));
1427        let mut accumulated = SO3::identity();
1428
1429        for _ in 0..1000 {
1430            accumulated = accumulated.compose(&small_rotation, None, None);
1431        }
1432
1433        // Expected: 1000 * small rotation
1434        let expected_tangent = SO3Tangent::new(Vector3::new(1.0, 2.0, -1.0));
1435        let expected = expected_tangent.exp(None);
1436
1437        // Tolerance reflects accumulated rounding error over 1000 compositions (expected)
1438        assert!(accumulated.is_approx(&expected, 1e-6));
1439    }
1440
1441    #[test]
1442    fn test_so3_inverse_composition_chain() {
1443        // g * g^{-1} * g * g^{-1} ... should stay near identity
1444        let rotation = SO3::from_euler_angles(0.1, 0.2, 0.3);
1445        let inverse = rotation.inverse(None);
1446        let mut accumulated = SO3::identity();
1447
1448        for _ in 0..500 {
1449            accumulated = accumulated.compose(&rotation, None, None);
1450            accumulated = accumulated.compose(&inverse, None, None);
1451        }
1452
1453        // Should still be identity (within numerical error)
1454        assert!(accumulated.is_approx(&SO3::identity(), 1e-9));
1455    }
1456
1457    // T2: Edge Case Tests
1458
1459    #[test]
1460    fn test_so3_antipodal_quaternions() {
1461        // q and -q represent the same rotation
1462        let q = UnitQuaternion::from_euler_angles(0.5, 0.3, 0.2);
1463        let so3_pos = SO3::new(q);
1464        let so3_neg = SO3::new(UnitQuaternion::from_quaternion(-q.quaternion()));
1465
1466        // Should represent the same rotation (up to numerical tolerance)
1467        let log_pos = so3_pos.log(None);
1468        let log_neg = so3_neg.log(None);
1469
1470        // One of these should be true: either logs are equal, or they're π apart
1471        let diff_norm = (log_pos.data - log_neg.data).norm();
1472        let sum_norm = (log_pos.data + log_neg.data).norm();
1473        assert!(diff_norm < 1e-10 || sum_norm < 1e-10);
1474    }
1475
1476    #[test]
1477    fn test_so3_near_pi_rotation() {
1478        // Test rotation very close to π (edge case in log())
1479        let axis = Vector3::new(1.0, 0.0, 0.0).normalize();
1480        let angle = std::f64::consts::PI - 1e-8;
1481        let so3 = SO3::from_axis_angle(&axis, angle);
1482
1483        let tangent = so3.log(None);
1484        let recovered = tangent.exp(None);
1485
1486        assert!(so3.is_approx(&recovered, 1e-6));
1487    }
1488
1489    #[test]
1490    fn test_so3_right_jacobian_inverse_identity() {
1491        let tangent = SO3Tangent::new(Vector3::new(0.001, 0.002, 0.003));
1492        let jr = tangent.right_jacobian();
1493        let jr_inv = tangent.right_jacobian_inv();
1494        let product = jr * jr_inv;
1495        let identity = Matrix3::identity();
1496
1497        assert!(
1498            (product - identity).norm() < 1e-10,
1499            "Jr * Jr_inv should be identity, got error: {}",
1500            (product - identity).norm()
1501        );
1502    }
1503
1504    #[test]
1505    fn test_so3_left_jacobian_inverse_identity() {
1506        let tangent = SO3Tangent::new(Vector3::new(0.001, 0.002, 0.003));
1507        let jl = tangent.left_jacobian();
1508        let jl_inv = tangent.left_jacobian_inv();
1509        let product = jl * jl_inv;
1510        let identity = Matrix3::identity();
1511
1512        assert!(
1513            (product - identity).norm() < 1e-10,
1514            "Jl * Jl_inv should be identity, got error: {}",
1515            (product - identity).norm()
1516        );
1517    }
1518
1519    #[test]
1520    fn test_so3_from_quaternion_wxyz() {
1521        // Identity quaternion: w=1, x=y=z=0
1522        let so3_wxyz = SO3::from_quaternion_wxyz(1.0, 0.0, 0.0, 0.0);
1523        let so3_xyzw = SO3::from_quaternion_coeffs(0.0, 0.0, 0.0, 1.0);
1524        assert!(so3_wxyz.is_approx(&so3_xyzw, 1e-12));
1525
1526        // Non-trivial quaternion: verify swapped argument order gives same result
1527        let so3_wxyz = SO3::from_quaternion_wxyz(0.4, 0.1, 0.2, 0.3);
1528        let so3_xyzw = SO3::from_quaternion_coeffs(0.1, 0.2, 0.3, 0.4);
1529        assert!(so3_wxyz.is_approx(&so3_xyzw, 1e-12));
1530    }
1531
1532    #[test]
1533    fn test_so3_tangent_is_not_dynamic() {
1534        assert!(!SO3Tangent::is_dynamic());
1535        assert_eq!(SO3Tangent::DIM, 3);
1536    }
1537
1538    #[test]
1539    fn test_so3_small_angle_threshold_exp_log() {
1540        // Test angles near the SMALL_ANGLE_THRESHOLD boundary round-trip correctly
1541        // sqrt(1e-10) ≈ 1e-5 is the effective angle threshold
1542        let near_threshold_angles = [1e-6, 1e-5, 1e-4, 1e-3];
1543
1544        for &angle in &near_threshold_angles {
1545            let tangent = SO3Tangent::new(Vector3::new(angle, 0.0, 0.0));
1546            let so3 = tangent.exp(None);
1547            let recovered = so3.log(None);
1548            assert!(
1549                (tangent.data - recovered.data).norm() < 1e-10,
1550                "SO3 exp-log round-trip failed for angle = {angle}"
1551            );
1552        }
1553    }
1554
1555    #[test]
1556    fn test_so3_display() {
1557        let r = SO3::identity();
1558        let s = format!("{r}");
1559        assert!(!s.is_empty(), "Display should produce output");
1560    }
1561
1562    #[test]
1563    fn test_so3_accessors_xyzw() {
1564        let r = SO3::from_axis_angle(&Vector3::z(), std::f64::consts::FRAC_PI_2);
1565        let _ = r.x();
1566        let _ = r.y();
1567        let _ = r.z();
1568        let _ = r.w();
1569        let q = r.to_quaternion();
1570        let q2 = r.quat();
1571        assert!((q.w - q2.w).abs() < 1e-10);
1572    }
1573
1574    #[test]
1575    fn test_so3_set_quaternion_and_coeffs() {
1576        // coeffs() returns [w, x, y, z] and set_quaternion takes [w, x, y, z]
1577        let r_orig = SO3::from_euler_angles(0.1, 0.2, 0.3);
1578        let orig_coeffs = r_orig.coeffs();
1579        assert_eq!(orig_coeffs.len(), 4);
1580
1581        // Round-trip: read coeffs, set them back, read again
1582        let mut r2 = SO3::identity();
1583        r2.set_quaternion(&orig_coeffs);
1584        let c2 = r2.coeffs();
1585        for i in 0..4 {
1586            assert!(
1587                (c2[i] - orig_coeffs[i]).abs() < 1e-9,
1588                "coeffs[{i}] mismatch"
1589            );
1590        }
1591    }
1592
1593    #[test]
1594    fn test_so3_from_scaled_axis_constructor() {
1595        let v = Vector3::new(0.1, 0.2, 0.3);
1596        let r = SO3::from_scaled_axis(v);
1597        assert!(r.is_valid(1e-6));
1598    }
1599
1600    #[test]
1601    fn test_so3_from_axis_angle_constructor() {
1602        let axis = Vector3::x();
1603        let r = SO3::from_axis_angle(&axis, std::f64::consts::FRAC_PI_4);
1604        assert!(r.is_valid(1e-6));
1605    }
1606
1607    #[test]
1608    fn test_so3_tangent_axis_angle_accessors() {
1609        let t = SO3Tangent::new(Vector3::new(0.1, 0.2, 0.3));
1610
1611        // axis_angle() returns Vector3<f64>
1612        let av = t.axis_angle();
1613        assert!((av.norm() - t.angle()).abs() < 1e-10);
1614
1615        // axis() returns normalized Vector3
1616        let ax = t.axis();
1617        assert!((ax.norm() - 1.0).abs() < 1e-9);
1618
1619        // let _ = t.x();
1620        // let _ = t.y();
1621        // let _ = t.z();
1622
1623        let c = t.coeffs();
1624        assert_eq!(c.len(), 3);
1625
1626        // ang() returns Vector3<f64>
1627        let ang = t.ang();
1628        assert!((ang.norm() - t.angle()).abs() < 1e-10);
1629    }
1630
1631    #[test]
1632    fn test_so3_right_jacobian_inv() {
1633        use crate::Tangent;
1634        let t = SO3Tangent::new(Vector3::new(0.1, 0.2, 0.3));
1635        let jr_inv = t.right_jacobian_inv();
1636        assert_eq!(jr_inv.nrows(), 3);
1637        assert_eq!(jr_inv.ncols(), 3);
1638
1639        let jr = t.right_jacobian();
1640        let product = jr_inv * jr;
1641        for i in 0..3 {
1642            for j in 0..3 {
1643                let expected = if i == j { 1.0 } else { 0.0 };
1644                assert!(
1645                    (product[(i, j)] - expected).abs() < 1e-4,
1646                    "product[{i},{j}] = {} != {expected}",
1647                    product[(i, j)]
1648                );
1649            }
1650        }
1651    }
1652
1653    #[test]
1654    fn test_so3_left_jacobian_inv() {
1655        use crate::Tangent;
1656        let t = SO3Tangent::new(Vector3::new(0.1, 0.2, 0.3));
1657        let jl_inv = t.left_jacobian_inv();
1658        assert_eq!(jl_inv.nrows(), 3);
1659
1660        let jl = t.left_jacobian();
1661        let product = jl_inv * jl;
1662        for i in 0..3 {
1663            for j in 0..3 {
1664                let expected = if i == j { 1.0 } else { 0.0 };
1665                assert!(
1666                    (product[(i, j)] - expected).abs() < 1e-4,
1667                    "product[{i},{j}] = {} != {expected}",
1668                    product[(i, j)]
1669                );
1670            }
1671        }
1672    }
1673
1674    #[test]
1675    fn test_so3_tangent_normalized() {
1676        use crate::Tangent;
1677        let t = SO3Tangent::new(Vector3::new(0.0, 0.0, 3.0));
1678        let tn = t.normalized();
1679        assert!((tn.angle() - 1.0).abs() < 1e-9);
1680    }
1681
1682    #[test]
1683    fn test_so3_tangent_is_zero() {
1684        use crate::Tangent;
1685        let zero = SO3Tangent::new(Vector3::zeros());
1686        assert!(zero.is_zero(1e-9));
1687        let nonzero = SO3Tangent::new(Vector3::new(0.1, 0.0, 0.0));
1688        assert!(!nonzero.is_zero(1e-9));
1689    }
1690
1691    #[test]
1692    fn test_so3_inverse_with_jacobian() {
1693        use crate::LieGroup;
1694        let r = SO3::from_euler_angles(0.1, 0.2, 0.3);
1695        let mut jac = Matrix3::zeros();
1696        let inv = r.inverse(Some(&mut jac));
1697        assert!(inv.is_valid(1e-6));
1698        assert!(jac[(0, 0)].is_finite());
1699    }
1700
1701    #[test]
1702    fn test_so3_compose_with_jacobians() {
1703        use crate::LieGroup;
1704        let r1 = SO3::from_euler_angles(0.1, 0.2, 0.3);
1705        let r2 = SO3::from_euler_angles(0.4, 0.1, 0.2);
1706        let mut j_self = Matrix3::zeros();
1707        let mut j_other = Matrix3::zeros();
1708        let result = r1.compose(&r2, Some(&mut j_self), Some(&mut j_other));
1709        assert!(result.is_valid(1e-6));
1710        assert!(j_self[(0, 0)].is_finite());
1711        assert!(j_other[(0, 0)].is_finite());
1712    }
1713
1714    #[test]
1715    fn test_so3_zero_jacobian() {
1716        use crate::LieGroup;
1717        let zj = SO3::zero_jacobian();
1718        for i in 0..3 {
1719            for j in 0..3 {
1720                assert!(zj[(i, j)].abs() < 1e-10);
1721            }
1722        }
1723    }
1724
1725    #[test]
1726    fn test_so3_act_with_jacobians() {
1727        use crate::LieGroup;
1728        let r = SO3::from_euler_angles(0.1, 0.2, 0.3);
1729        let v = Vector3::new(1.0, 0.0, 0.0);
1730        let mut j_self = Matrix3::zeros();
1731        let mut j_vec = Matrix3::zeros();
1732        let result = r.act(&v, Some(&mut j_self), Some(&mut j_vec));
1733        assert!(result.norm() > 0.0);
1734        assert!(j_self[(0, 0)].is_finite());
1735        assert!(j_vec[(0, 0)].is_finite());
1736    }
1737
1738    #[test]
1739    fn test_from_dvector_wxyz() {
1740        let dv = ::nalgebra::dvector![144., 96., 72., 83.] / 205.; // norm 1
1741        let so3 = SO3::from(dv.clone());
1742        assert_eq!(144. / 205., so3.w());
1743        assert_eq!(96. / 205., so3.x());
1744        assert_eq!(72. / 205., so3.y());
1745        assert_eq!(83. / 205., so3.z());
1746    }
1747
1748    #[test]
1749    fn test_from_s03_wxyz() {
1750        let so3 = SO3::from_quaternion_wxyz(144. / 205., 96. / 205., 72. / 205., 83. / 205.); // norm 1
1751        let dv = DVector::<f64>::from(so3.clone());
1752        assert_eq!(144. / 205., dv[0]);
1753        assert_eq!(96. / 205., dv[1]);
1754        assert_eq!(72. / 205., dv[2]);
1755        assert_eq!(83. / 205., dv[3]);
1756    }
1757
1758    #[test]
1759    fn test_bijective_from_dvector() {
1760        let dv_expected = ::nalgebra::dvector![144., 96., 72., 83.] / 205.; // norm 1
1761        let so3_expected = SO3::from(dv_expected.clone());
1762        let dv_actual = DVector::<f64>::from(so3_expected.clone());
1763        let so3_actual = SO3::from(dv_actual.clone());
1764        assert_eq!(dv_expected, dv_actual);
1765        assert!(so3_expected == so3_actual);
1766    }
1767}