Skip to main content

apex_manifolds/
rn.rs

1//! Rn - n-dimensional Euclidean Space
2//!
3//! This module implements the n-dimensional Euclidean space Rⁿ with vector addition
4//! as the group operation.
5//!
6//! Rⁿ elements are represented using nalgebra's DVector<f64> for dynamic sizing.
7//! Rⁿ tangent elements are also represented as DVector<f64> since the tangent space
8//! is isomorphic to the manifold itself.
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
13use crate::{Interpolatable, LieGroup, Tangent};
14use nalgebra::{DMatrix, DVector, Matrix3, Vector3};
15use std::{
16    fmt,
17    fmt::{Display, Formatter},
18};
19
20/// Rⁿ group element representing n-dimensional Euclidean vectors.
21///
22/// Internally represented using nalgebra's DVector<f64> for dynamic sizing.
23#[derive(Clone, PartialEq)]
24pub struct Rn {
25    /// Internal representation as a dynamic vector
26    data: DVector<f64>,
27}
28
29impl Display for Rn {
30    fn fmt(&self, f: &mut Formatter<'_>) -> fmt::Result {
31        write!(f, "Rn(dim: {}, data: [", self.data.len())?;
32        for (i, val) in self.data.iter().enumerate() {
33            if i > 0 {
34                write!(f, ", ")?;
35            }
36            write!(f, "{:.4}", val)?;
37        }
38        write!(f, "])")
39    }
40}
41
42// Conversion traits for integration with generic Problem
43impl From<DVector<f64>> for Rn {
44    fn from(data: DVector<f64>) -> Self {
45        Rn::new(data)
46    }
47}
48
49impl From<Rn> for DVector<f64> {
50    fn from(rn: Rn) -> Self {
51        rn.data
52    }
53}
54
55/// Rⁿ tangent space element representing elements in the Lie algebra rⁿ.
56///
57/// For Euclidean space, the tangent space is isomorphic to the manifold itself,
58/// so this is also represented as a DVector<f64>.
59#[derive(Clone, PartialEq)]
60pub struct RnTangent {
61    /// Internal data: n-dimensional vector
62    data: DVector<f64>,
63}
64
65impl Display for RnTangent {
66    fn fmt(&self, f: &mut Formatter<'_>) -> fmt::Result {
67        write!(f, "rn(dim: {}, data: [", self.data.len())?;
68        for (i, val) in self.data.iter().enumerate() {
69            if i > 0 {
70                write!(f, ", ")?;
71            }
72            write!(f, "{:.4}", val)?;
73        }
74        write!(f, "])")
75    }
76}
77
78impl Rn {
79    /// Space dimension - dimension of the ambient space that the group acts on
80    /// Note: For Rⁿ this is dynamic and determined at runtime
81    pub const DIM: usize = 0;
82
83    /// Degrees of freedom - dimension of the tangent space
84    /// Note: For Rⁿ this is dynamic and determined at runtime
85    pub const DOF: usize = 0;
86
87    /// Representation size - size of the underlying data representation
88    /// Note: For Rⁿ this is dynamic and determined at runtime
89    pub const REP_SIZE: usize = 0;
90
91    /// Get the identity element of the group.
92    ///
93    /// Returns the neutral element e such that e ∘ g = g ∘ e = g for any group element g.
94    /// Note: Default to 3D identity for compatibility, but this should be created with specific dimension
95    pub fn identity() -> Self {
96        Rn::new(DVector::zeros(3))
97    }
98
99    /// Get the identity matrix for Jacobians.
100    ///
101    /// Returns the identity matrix in the appropriate dimension for Jacobian computations.
102    /// Note: Default to 3x3 identity, but this should be created with specific dimension
103    pub fn jacobian_identity() -> DMatrix<f64> {
104        DMatrix::identity(3, 3)
105    }
106
107    /// Create a new Rⁿ element from a vector.
108    ///
109    /// # Arguments
110    /// * `data` - Vector data
111    #[inline]
112    pub fn new(data: DVector<f64>) -> Self {
113        Rn { data }
114    }
115
116    /// Create Rⁿ from a slice.
117    ///
118    /// # Arguments
119    /// * `slice` - Data slice
120    pub fn from_slice(slice: &[f64]) -> Self {
121        Rn::new(DVector::from_row_slice(slice))
122    }
123
124    /// Create Rⁿ from individual components (up to 6D for convenience).
125    pub fn from_vec(components: Vec<f64>) -> Self {
126        Rn::new(DVector::from_vec(components))
127    }
128
129    /// Get the underlying vector.
130    #[inline]
131    pub fn data(&self) -> &DVector<f64> {
132        &self.data
133    }
134
135    /// Get the dimension of the space.
136    #[inline]
137    pub fn dim(&self) -> usize {
138        self.data.len()
139    }
140
141    /// Get a specific component.
142    #[inline]
143    pub fn component(&self, index: usize) -> f64 {
144        self.data[index]
145    }
146
147    /// Set a specific component.
148    pub fn set_component(&mut self, index: usize, value: f64) {
149        self.data[index] = value;
150    }
151
152    /// Get the norm (Euclidean length) of the vector.
153    #[inline]
154    pub fn norm(&self) -> f64 {
155        self.data.norm()
156    }
157
158    /// Get the squared norm of the vector.
159    #[inline]
160    pub fn norm_squared(&self) -> f64 {
161        self.data.norm_squared()
162    }
163
164    /// Convert Rn to a DVector
165    #[inline]
166    pub fn to_vector(&self) -> DVector<f64> {
167        self.data.clone()
168    }
169}
170
171impl LieGroup for Rn {
172    type TangentVector = RnTangent;
173    type JacobianMatrix = DMatrix<f64>;
174    type LieAlgebra = DMatrix<f64>;
175
176    /// Rⁿ inverse (negation for additive group).
177    ///
178    /// # Arguments
179    /// * `jacobian` - Optional Jacobian matrix of the inverse wrt self.
180    ///
181    /// # Notes
182    /// For Euclidean space with addition: -v
183    /// Jacobian of inverse: d(-v)/dv = -I
184    fn inverse(&self, jacobian: Option<&mut Self::JacobianMatrix>) -> Self {
185        let dim = self.data.len();
186        if let Some(jac) = jacobian {
187            *jac = -DMatrix::identity(dim, dim);
188        }
189        Rn::new(-&self.data)
190    }
191
192    /// Rⁿ composition (vector addition).
193    ///
194    /// # Arguments
195    /// * `other` - Another Rⁿ element.
196    /// * `jacobian_self` - Optional Jacobian matrix of the composition wrt self.
197    /// * `jacobian_other` - Optional Jacobian matrix of the composition wrt other.
198    ///
199    /// # Notes
200    /// For Euclidean space: v₁ + v₂
201    /// Jacobians: d(v₁ + v₂)/dv₁ = I, d(v₁ + v₂)/dv₂ = I
202    fn compose(
203        &self,
204        other: &Self,
205        jacobian_self: Option<&mut Self::JacobianMatrix>,
206        jacobian_other: Option<&mut Self::JacobianMatrix>,
207    ) -> Self {
208        assert_eq!(
209            self.data.len(),
210            other.data.len(),
211            "Rn elements must have the same dimension for composition"
212        );
213
214        let dim = self.data.len();
215        if let Some(jac_self) = jacobian_self {
216            *jac_self = DMatrix::identity(dim, dim);
217        }
218        if let Some(jac_other) = jacobian_other {
219            *jac_other = DMatrix::identity(dim, dim);
220        }
221
222        Rn::new(&self.data + &other.data)
223    }
224
225    /// Logarithmic map from manifold to tangent space.
226    ///
227    /// # Arguments
228    /// * `jacobian` - Optional Jacobian matrix of the tangent wrt to self.
229    ///
230    /// # Notes
231    /// For Euclidean space, log is identity: log(v) = v
232    /// Jacobian: dlog(v)/dv = I
233    fn log(&self, jacobian: Option<&mut Self::JacobianMatrix>) -> Self::TangentVector {
234        let dim = self.data.len();
235        if let Some(jac) = jacobian {
236            *jac = DMatrix::identity(dim, dim);
237        }
238        RnTangent::new(self.data.clone())
239    }
240
241    /// Vee operator: log(g)^∨.
242    ///
243    /// For Euclidean space, this is the same as log().
244    fn vee(&self) -> Self::TangentVector {
245        self.log(None)
246    }
247
248    /// Action on a 3-vector (for compatibility with the trait).
249    ///
250    /// # Arguments
251    /// * `vector` - A 3-vector.
252    /// * `jacobian_self` - Optional Jacobian of the new object wrt this.
253    /// * `jacobian_vector` - Optional Jacobian of the new object wrt input object.
254    ///
255    /// # Returns
256    /// The transformed 3-vector.
257    ///
258    /// # Notes
259    /// For Euclidean space, the action is translation: v + x
260    /// This only works if this Rⁿ element is 3-dimensional.
261    fn act(
262        &self,
263        vector: &Vector3<f64>,
264        jacobian_self: Option<&mut Self::JacobianMatrix>,
265        jacobian_vector: Option<&mut Matrix3<f64>>,
266    ) -> Vector3<f64> {
267        if let Some(jac_self) = jacobian_self {
268            *jac_self = DMatrix::identity(3, 3);
269        }
270        if let Some(jac_vector) = jacobian_vector {
271            *jac_vector = Matrix3::identity();
272        }
273
274        Vector3::new(
275            self.data[0] + vector.x,
276            self.data[1] + vector.y,
277            self.data[2] + vector.z,
278        )
279    }
280
281    /// Get the adjoint matrix of Rⁿ.
282    ///
283    /// # Notes
284    /// For Euclidean space (abelian group), adjoint is identity.
285    fn adjoint(&self) -> Self::JacobianMatrix {
286        let dim = self.data.len();
287        DMatrix::identity(dim, dim)
288    }
289
290    /// Generate a random element.
291    fn random() -> Self {
292        // Default to 3D random vector
293        let data = DVector::from_fn(3, |_, _| rand::random::<f64>() * 10.0 - 5.0);
294        Rn::new(data)
295    }
296
297    fn jacobian_identity() -> Self::JacobianMatrix {
298        // Default to 3D identity for compatibility
299        DMatrix::identity(3, 3)
300    }
301
302    fn zero_jacobian() -> Self::JacobianMatrix {
303        // Default to 3D zero matrix for compatibility
304        DMatrix::zeros(3, 3)
305    }
306
307    fn normalize(&mut self) {
308        let norm = self.data.norm();
309        if norm > 1e-12 {
310            self.data /= norm;
311        }
312    }
313
314    fn is_valid(&self, _tolerance: f64) -> bool {
315        self.data.iter().all(|x| x.is_finite())
316    }
317
318    /// Check if the element is approximately equal to another element.
319    ///
320    /// # Arguments
321    /// * `other` - The other element to compare with
322    /// * `tolerance` - The tolerance for the comparison
323    fn is_approx(&self, other: &Self, tolerance: f64) -> bool {
324        if self.data.len() != other.data.len() {
325            return false;
326        }
327        let difference = self.right_minus(other, None, None);
328        difference.is_zero(tolerance)
329    }
330
331    // Explicit implementations of plus/minus operations for optimal performance
332    // These override the default LieGroup implementations to provide correct
333    // Jacobians for Euclidean space (simple identity matrices)
334
335    /// Right plus operation: v ⊞ δ = v + δ.
336    ///
337    /// For Euclidean space, this is simple vector addition.
338    ///
339    /// # Arguments
340    /// * `tangent` - Tangent vector perturbation
341    /// * `jacobian_self` - Optional Jacobian ∂(v ⊞ δ)/∂v = I
342    /// * `jacobian_tangent` - Optional Jacobian ∂(v ⊞ δ)/∂δ = I
343    ///
344    /// # Notes
345    /// For Euclidean space: v ⊞ δ = v + δ
346    /// Jacobians: ∂(v + δ)/∂v = I, ∂(v + δ)/∂δ = I
347    fn right_plus(
348        &self,
349        tangent: &Self::TangentVector,
350        jacobian_self: Option<&mut Self::JacobianMatrix>,
351        jacobian_tangent: Option<&mut Self::JacobianMatrix>,
352    ) -> Self {
353        assert_eq!(
354            self.data.len(),
355            tangent.data.len(),
356            "Rn element and tangent must have the same dimension"
357        );
358
359        let dim = self.data.len();
360
361        if let Some(jac_self) = jacobian_self {
362            *jac_self = DMatrix::identity(dim, dim);
363        }
364
365        if let Some(jac_tangent) = jacobian_tangent {
366            *jac_tangent = DMatrix::identity(dim, dim);
367        }
368
369        Rn::new(&self.data + &tangent.data)
370    }
371
372    /// Right minus operation: v₁ ⊟ v₂ = v₁ - v₂.
373    ///
374    /// For Euclidean space, this is simple vector subtraction.
375    ///
376    /// # Arguments
377    /// * `other` - The reference element v₂
378    /// * `jacobian_self` - Optional Jacobian ∂(v₁ ⊟ v₂)/∂v₁ = I
379    /// * `jacobian_other` - Optional Jacobian ∂(v₁ ⊟ v₂)/∂v₂ = -I
380    ///
381    /// # Notes
382    /// For Euclidean space: v₁ ⊟ v₂ = v₁ - v₂
383    /// Jacobians: ∂(v₁ - v₂)/∂v₁ = I, ∂(v₁ - v₂)/∂v₂ = -I
384    fn right_minus(
385        &self,
386        other: &Self,
387        jacobian_self: Option<&mut Self::JacobianMatrix>,
388        jacobian_other: Option<&mut Self::JacobianMatrix>,
389    ) -> Self::TangentVector {
390        assert_eq!(
391            self.data.len(),
392            other.data.len(),
393            "Rn elements must have the same dimension"
394        );
395
396        let dim = self.data.len();
397
398        if let Some(jac_self) = jacobian_self {
399            *jac_self = DMatrix::identity(dim, dim);
400        }
401
402        if let Some(jac_other) = jacobian_other {
403            *jac_other = -DMatrix::identity(dim, dim);
404        }
405
406        RnTangent::new(&self.data - &other.data)
407    }
408
409    /// Left plus operation: δ ⊞ v = δ + v.
410    ///
411    /// For Euclidean space (abelian group), left plus is the same as right plus.
412    ///
413    /// # Arguments
414    /// * `tangent` - Tangent vector perturbation
415    /// * `jacobian_tangent` - Optional Jacobian ∂(δ ⊞ v)/∂δ = I
416    /// * `jacobian_self` - Optional Jacobian ∂(δ ⊞ v)/∂v = I
417    ///
418    /// # Notes
419    /// For abelian groups: δ ⊞ v = v ⊞ δ = δ + v
420    fn left_plus(
421        &self,
422        tangent: &Self::TangentVector,
423        jacobian_tangent: Option<&mut Self::JacobianMatrix>,
424        jacobian_self: Option<&mut Self::JacobianMatrix>,
425    ) -> Self {
426        assert_eq!(
427            self.data.len(),
428            tangent.data.len(),
429            "Rn element and tangent must have the same dimension"
430        );
431
432        let dim = self.data.len();
433
434        if let Some(jac_tangent) = jacobian_tangent {
435            *jac_tangent = DMatrix::identity(dim, dim);
436        }
437
438        if let Some(jac_self) = jacobian_self {
439            *jac_self = DMatrix::identity(dim, dim);
440        }
441
442        // For abelian groups, left plus is the same as right plus
443        Rn::new(&tangent.data + &self.data)
444    }
445
446    /// Left minus operation: v₁ ⊟ v₂ = v₁ - v₂.
447    ///
448    /// For Euclidean space (abelian group), left minus is the same as right minus.
449    ///
450    /// # Arguments
451    /// * `other` - The reference element v₂
452    /// * `jacobian_self` - Optional Jacobian ∂(v₁ ⊟ v₂)/∂v₁ = I
453    /// * `jacobian_other` - Optional Jacobian ∂(v₁ ⊟ v₂)/∂v₂ = -I
454    ///
455    /// # Notes
456    /// For abelian groups: left minus = right minus
457    fn left_minus(
458        &self,
459        other: &Self,
460        jacobian_self: Option<&mut Self::JacobianMatrix>,
461        jacobian_other: Option<&mut Self::JacobianMatrix>,
462    ) -> Self::TangentVector {
463        // For abelian groups, left minus is the same as right minus
464        self.right_minus(other, jacobian_self, jacobian_other)
465    }
466
467    /// Get the dimension of the tangent space for this Rⁿ element.
468    ///
469    /// # Returns
470    /// The actual runtime dimension of this Rⁿ element.
471    ///
472    /// # Notes
473    /// Overrides the default implementation to return the dynamic size
474    /// based on the actual data vector length, since Rⁿ has variable dimension.
475    fn tangent_dim(&self) -> usize {
476        self.data.len()
477    }
478}
479
480impl RnTangent {
481    /// Create a new RnTangent from a vector.
482    ///
483    /// # Arguments
484    /// * `data` - Vector data
485    #[inline]
486    pub fn new(data: DVector<f64>) -> Self {
487        RnTangent { data }
488    }
489
490    /// Create RnTangent from a slice.
491    ///
492    /// # Arguments
493    /// * `slice` - Data slice
494    pub fn from_slice(slice: &[f64]) -> Self {
495        RnTangent::new(DVector::from_row_slice(slice))
496    }
497
498    /// Create RnTangent from individual components.
499    pub fn from_vec(components: Vec<f64>) -> Self {
500        RnTangent::new(DVector::from_vec(components))
501    }
502
503    /// Get the underlying vector.
504    #[inline]
505    pub fn data(&self) -> &DVector<f64> {
506        &self.data
507    }
508
509    /// Get the dimension of the tangent space.
510    #[inline]
511    pub fn dim(&self) -> usize {
512        self.data.len()
513    }
514
515    /// Get a specific component.
516    #[inline]
517    pub fn component(&self, index: usize) -> f64 {
518        self.data[index]
519    }
520
521    /// Set a specific component.
522    pub fn set_component(&mut self, index: usize, value: f64) {
523        self.data[index] = value;
524    }
525
526    /// Get the norm (Euclidean length) of the tangent vector.
527    #[inline]
528    pub fn norm(&self) -> f64 {
529        self.data.norm()
530    }
531
532    /// Get the squared norm of the tangent vector.
533    #[inline]
534    pub fn norm_squared(&self) -> f64 {
535        self.data.norm_squared()
536    }
537
538    /// Convert RnTangent to a DVector
539    #[inline]
540    pub fn to_vector(&self) -> DVector<f64> {
541        self.data.clone()
542    }
543
544    /// Create RnTangent from a DVector
545    pub fn from_vector(data: DVector<f64>) -> Self {
546        RnTangent::new(data)
547    }
548}
549
550impl Tangent<Rn> for RnTangent {
551    /// Dimension of the tangent space
552    /// Note: For Rⁿ this is dynamic and determined at runtime
553    const DIM: usize = 0;
554
555    /// Exponential map for Euclidean space (identity).
556    ///
557    /// # Arguments
558    /// * `jacobian` - Optional Jacobian matrix of the Rn element wrt this.
559    ///
560    /// # Notes
561    /// For Euclidean space: exp(v) = v
562    /// Jacobian: dexp(v)/dv = I
563    fn exp(&self, jacobian: Option<&mut <Rn as LieGroup>::JacobianMatrix>) -> Rn {
564        let dim = self.data.len();
565        if let Some(jac) = jacobian {
566            *jac = DMatrix::identity(dim, dim);
567        }
568        Rn::new(self.data.clone())
569    }
570
571    fn right_jacobian(&self) -> <Rn as LieGroup>::JacobianMatrix {
572        let dim = self.data.len();
573        DMatrix::identity(dim, dim)
574    }
575
576    fn left_jacobian(&self) -> <Rn as LieGroup>::JacobianMatrix {
577        let dim = self.data.len();
578        DMatrix::identity(dim, dim)
579    }
580
581    fn right_jacobian_inv(&self) -> <Rn as LieGroup>::JacobianMatrix {
582        let dim = self.data.len();
583        DMatrix::identity(dim, dim)
584    }
585
586    fn left_jacobian_inv(&self) -> <Rn as LieGroup>::JacobianMatrix {
587        let dim = self.data.len();
588        DMatrix::identity(dim, dim)
589    }
590
591    /// Hat operator: v^∧ (vector to matrix).
592    ///
593    /// For Euclidean space, this could be interpreted as a diagonal matrix
594    /// or simply return the vector as a column matrix.
595    fn hat(&self) -> <Rn as LieGroup>::LieAlgebra {
596        DMatrix::from_diagonal(&self.data)
597    }
598
599    /// Small adjoint (zero for abelian group).
600    fn small_adj(&self) -> <Rn as LieGroup>::JacobianMatrix {
601        let dim = self.data.len();
602        DMatrix::zeros(dim, dim)
603    }
604
605    /// Lie bracket for Euclidean space.
606    ///
607    /// For abelian groups: [v, w] = 0
608    fn lie_bracket(&self, _other: &Self) -> <Rn as LieGroup>::TangentVector {
609        RnTangent::new(DVector::zeros(self.data.len()))
610    }
611
612    /// Check if the tangent vector is approximately equal to another tangent vector.
613    ///
614    /// # Arguments
615    /// * `other` - The other tangent vector to compare with
616    /// * `tolerance` - The tolerance for the comparison
617    fn is_approx(&self, other: &Self, tolerance: f64) -> bool {
618        if self.data.len() != other.data.len() {
619            return false;
620        }
621        (&self.data - &other.data).norm() < tolerance
622    }
623
624    /// Get the i-th generator of the Lie algebra.
625    ///
626    /// For Euclidean space, generators are standard basis vectors.
627    fn generator(&self, i: usize) -> <Rn as LieGroup>::LieAlgebra {
628        let dim = self.data.len();
629        let mut generator_matrix = DMatrix::zeros(dim, dim);
630        generator_matrix[(i, i)] = 1.0;
631        generator_matrix
632    }
633
634    /// Zero tangent vector.
635    fn zero() -> <Rn as LieGroup>::TangentVector {
636        // Default to 3D zero vector for compatibility
637        RnTangent::new(DVector::zeros(3))
638    }
639
640    /// Random tangent vector.
641    fn random() -> <Rn as LieGroup>::TangentVector {
642        // Default to 3D random vector
643        let data = DVector::from_fn(3, |_, _| rand::random::<f64>() * 10.0 - 5.0);
644        RnTangent::new(data)
645    }
646
647    /// Check if the tangent vector is approximately zero.
648    fn is_zero(&self, tolerance: f64) -> bool {
649        self.data.norm() < tolerance
650    }
651
652    /// Normalize the tangent vector to unit norm.
653    fn normalize(&mut self) {
654        let norm = self.data.norm();
655        if norm > 1e-12 {
656            self.data /= norm;
657        }
658    }
659
660    /// Return a unit tangent vector in the same direction.
661    fn normalized(&self) -> <Rn as LieGroup>::TangentVector {
662        let mut result = self.clone();
663        result.normalize();
664        result
665    }
666}
667
668// Implement Interpolatable trait for Rn
669impl Interpolatable for Rn {
670    /// Linear interpolation in Euclidean space.
671    ///
672    /// For parameter t ∈ [0,1]: interp(v₁, v₂, 0) = v₁, interp(v₁, v₂, 1) = v₂.
673    ///
674    /// # Arguments
675    /// * `other` - Target element for interpolation
676    /// * `t` - Interpolation parameter in [0,1]
677    fn interp(&self, other: &Self, t: f64) -> Self {
678        assert_eq!(
679            self.data.len(),
680            other.data.len(),
681            "Rn elements must have the same dimension for interpolation"
682        );
683
684        let interpolated = &self.data * (1.0 - t) + &other.data * t;
685        Rn::new(interpolated)
686    }
687
688    /// Spherical linear interpolation (same as linear for Euclidean space).
689    fn slerp(&self, other: &Self, t: f64) -> Self {
690        self.interp(other, t)
691    }
692}
693
694// Additional convenience implementations
695impl Rn {
696    /// Create identity element with specific dimension.
697    ///
698    /// For Euclidean space, the identity (additive neutral element) is the zero vector.
699    /// The default `identity()` returns a 3D zero vector for compatibility.
700    /// Use this method when you need a specific dimension.
701    pub fn identity_with_dim(dim: usize) -> Self {
702        Rn::new(DVector::zeros(dim))
703    }
704
705    /// Create Rn with specific dimension filled with zeros.
706    pub fn zeros(dim: usize) -> Self {
707        Rn::new(DVector::zeros(dim))
708    }
709
710    /// Create Rn with specific dimension filled with ones.
711    pub fn ones(dim: usize) -> Self {
712        Rn::new(DVector::from_element(dim, 1.0))
713    }
714
715    /// Create Rn with specific dimension and random values.
716    pub fn random_with_dim(dim: usize) -> Self {
717        let data = DVector::from_fn(dim, |_, _| rand::random::<f64>() * 10.0 - 5.0);
718        Rn::new(data)
719    }
720
721    /// Create identity matrix for Jacobians with specific dimension.
722    pub fn jacobian_identity_with_dim(dim: usize) -> DMatrix<f64> {
723        DMatrix::identity(dim, dim)
724    }
725}
726
727impl RnTangent {
728    /// Create zero tangent vector with specific dimension.
729    pub fn zero_with_dim(dim: usize) -> Self {
730        RnTangent::new(DVector::zeros(dim))
731    }
732
733    /// Create RnTangent with specific dimension filled with zeros.
734    pub fn zeros(dim: usize) -> Self {
735        RnTangent::new(DVector::zeros(dim))
736    }
737
738    /// Create RnTangent with specific dimension filled with ones.
739    pub fn ones(dim: usize) -> Self {
740        RnTangent::new(DVector::from_element(dim, 1.0))
741    }
742
743    /// Create RnTangent with specific dimension and random values.
744    pub fn random_with_dim(dim: usize) -> Self {
745        let data = DVector::from_fn(dim, |_, _| rand::random::<f64>() * 2.0 - 1.0);
746        RnTangent::new(data)
747    }
748}
749
750#[cfg(test)]
751mod tests {
752    use super::*;
753    use crate::{Interpolatable, LieGroup, Tangent};
754
755    #[test]
756    fn test_rn_basic_operations() {
757        // Test 3D Euclidean space
758        let v1 = Rn::from_vec(vec![1.0, 2.0, 3.0]);
759        let v2 = Rn::from_vec(vec![4.0, 5.0, 6.0]);
760
761        // Test composition (addition)
762        let sum = v1.compose(&v2, None, None);
763        assert_eq!(sum.component(0), 5.0);
764        assert_eq!(sum.component(1), 7.0);
765        assert_eq!(sum.component(2), 9.0);
766
767        // Test identity
768        let identity = Rn::zeros(3);
769        let result = v1.compose(&identity, None, None);
770        assert_eq!(result.component(0), v1.component(0));
771        assert_eq!(result.component(1), v1.component(1));
772        assert_eq!(result.component(2), v1.component(2));
773
774        // Test inverse
775        let v1_inv = v1.inverse(None);
776        assert_eq!(v1_inv.component(0), -1.0);
777        assert_eq!(v1_inv.component(1), -2.0);
778        assert_eq!(v1_inv.component(2), -3.0);
779
780        // Test log/exp (should be identity for Euclidean space)
781        let tangent = v1.log(None);
782        let recovered = tangent.exp(None);
783        assert!((recovered.component(0) - v1.component(0)).abs() < 1e-10);
784        assert!((recovered.component(1) - v1.component(1)).abs() < 1e-10);
785        assert!((recovered.component(2) - v1.component(2)).abs() < 1e-10);
786    }
787
788    #[test]
789    fn test_rn_tangent_operations() {
790        let t1 = RnTangent::from_vec(vec![1.0, 2.0, 3.0]);
791        let t2 = RnTangent::from_vec(vec![4.0, 5.0, 6.0]);
792
793        // Test Lie bracket (should be zero for abelian group)
794        let bracket = t1.lie_bracket(&t2);
795        assert!(bracket.is_zero(1e-10));
796
797        // Test zero tangent
798        let zero = RnTangent::zeros(3);
799        assert!(zero.is_zero(1e-10));
800
801        // Test normalization
802        let mut t = RnTangent::from_vec(vec![3.0, 4.0, 0.0]);
803        t.normalize();
804        assert!((t.norm() - 1.0).abs() < 1e-10);
805    }
806
807    #[test]
808    fn test_rn_interpolation() {
809        let v1 = Rn::from_vec(vec![0.0, 0.0, 0.0]);
810        let v2 = Rn::from_vec(vec![10.0, 20.0, 30.0]);
811
812        // Test interpolation at t=0.5
813        let mid = v1.interp(&v2, 0.5);
814        assert_eq!(mid.component(0), 5.0);
815        assert_eq!(mid.component(1), 10.0);
816        assert_eq!(mid.component(2), 15.0);
817
818        // Test interpolation at endpoints
819        let start = v1.interp(&v2, 0.0);
820        let end = v1.interp(&v2, 1.0);
821        assert!(v1.is_approx(&start, 1e-10));
822        assert!(v2.is_approx(&end, 1e-10));
823    }
824
825    #[test]
826    fn test_rn_different_dimensions() {
827        // Test 2D
828        let v2d = Rn::from_vec(vec![1.0, 2.0]);
829        assert_eq!(v2d.dim(), 2);
830
831        // Test 1D
832        let v1d = Rn::from_vec(vec![5.0]);
833        assert_eq!(v1d.dim(), 1);
834
835        // Test higher dimensions
836        let v5d = Rn::from_vec(vec![1.0, 2.0, 3.0, 4.0, 5.0]);
837        assert_eq!(v5d.dim(), 5);
838        assert_eq!(v5d.component(4), 5.0);
839    }
840
841    #[test]
842    fn test_rn_action() {
843        // Test action on 3D vector (translation)
844        let translation = Rn::from_vec(vec![1.0, 2.0, 3.0]);
845        let point = Vector3::new(4.0, 5.0, 6.0);
846        let transformed = translation.act(&point, None, None);
847
848        assert_eq!(transformed.x, 5.0);
849        assert_eq!(transformed.y, 7.0);
850        assert_eq!(transformed.z, 9.0);
851    }
852
853    #[test]
854    fn test_rn_right_plus_operations() {
855        let v = Rn::from_vec(vec![1.0, 2.0, 3.0]);
856        let delta = RnTangent::from_vec(vec![0.1, 0.2, 0.3]);
857
858        // Test right plus without Jacobians
859        let result = v.right_plus(&delta, None, None);
860        assert!((result.component(0) - 1.1).abs() < 1e-10);
861        assert!((result.component(1) - 2.2).abs() < 1e-10);
862        assert!((result.component(2) - 3.3).abs() < 1e-10);
863
864        // Test right plus with Jacobians
865        let mut jac_self = DMatrix::zeros(3, 3);
866        let mut jac_tangent = DMatrix::zeros(3, 3);
867        let result_jac = v.right_plus(&delta, Some(&mut jac_self), Some(&mut jac_tangent));
868
869        // Verify result is the same
870        assert!((result_jac.component(0) - result.component(0)).abs() < 1e-10);
871        assert!((result_jac.component(1) - result.component(1)).abs() < 1e-10);
872        assert!((result_jac.component(2) - result.component(2)).abs() < 1e-10);
873
874        // Verify Jacobians are identity matrices
875        let identity = DMatrix::identity(3, 3);
876        assert!((jac_self - &identity).norm() < 1e-10);
877        assert!((jac_tangent - &identity).norm() < 1e-10);
878    }
879
880    #[test]
881    fn test_rn_right_minus_operations() {
882        let v1 = Rn::from_vec(vec![5.0, 7.0, 9.0]);
883        let v2 = Rn::from_vec(vec![1.0, 2.0, 3.0]);
884
885        // Test right minus without Jacobians
886        let result = v1.right_minus(&v2, None, None);
887        assert!((result.component(0) - 4.0).abs() < 1e-10);
888        assert!((result.component(1) - 5.0).abs() < 1e-10);
889        assert!((result.component(2) - 6.0).abs() < 1e-10);
890
891        // Test right minus with Jacobians
892        let mut jac_self = DMatrix::zeros(3, 3);
893        let mut jac_other = DMatrix::zeros(3, 3);
894        let result_jac = v1.right_minus(&v2, Some(&mut jac_self), Some(&mut jac_other));
895
896        // Verify result is the same
897        assert!((result_jac.component(0) - result.component(0)).abs() < 1e-10);
898        assert!((result_jac.component(1) - result.component(1)).abs() < 1e-10);
899        assert!((result_jac.component(2) - result.component(2)).abs() < 1e-10);
900
901        // Verify Jacobians
902        let identity = DMatrix::identity(3, 3);
903        let neg_identity = -&identity;
904        assert!((jac_self - &identity).norm() < 1e-10);
905        assert!((jac_other - &neg_identity).norm() < 1e-10);
906    }
907
908    #[test]
909    fn test_rn_left_plus_operations() {
910        let v = Rn::from_vec(vec![1.0, 2.0, 3.0]);
911        let delta = RnTangent::from_vec(vec![0.1, 0.2, 0.3]);
912
913        // Test left plus without Jacobians
914        let result = v.left_plus(&delta, None, None);
915        assert!((result.component(0) - 1.1).abs() < 1e-10);
916        assert!((result.component(1) - 2.2).abs() < 1e-10);
917        assert!((result.component(2) - 3.3).abs() < 1e-10);
918
919        // Test left plus with Jacobians
920        let mut jac_tangent = DMatrix::zeros(3, 3);
921        let mut jac_self = DMatrix::zeros(3, 3);
922        let result_jac = v.left_plus(&delta, Some(&mut jac_tangent), Some(&mut jac_self));
923
924        // Verify result is the same
925        assert!((result_jac.component(0) - result.component(0)).abs() < 1e-10);
926        assert!((result_jac.component(1) - result.component(1)).abs() < 1e-10);
927        assert!((result_jac.component(2) - result.component(2)).abs() < 1e-10);
928
929        // Verify Jacobians are identity matrices
930        let identity = DMatrix::identity(3, 3);
931        assert!((jac_tangent - &identity).norm() < 1e-10);
932        assert!((jac_self - &identity).norm() < 1e-10);
933    }
934
935    #[test]
936    fn test_rn_left_minus_operations() {
937        let v1 = Rn::from_vec(vec![5.0, 7.0, 9.0]);
938        let v2 = Rn::from_vec(vec![1.0, 2.0, 3.0]);
939
940        // Test left minus without Jacobians
941        let result = v1.left_minus(&v2, None, None);
942        assert!((result.component(0) - 4.0).abs() < 1e-10);
943        assert!((result.component(1) - 5.0).abs() < 1e-10);
944        assert!((result.component(2) - 6.0).abs() < 1e-10);
945
946        // Test left minus with Jacobians
947        let mut jac_self = DMatrix::zeros(3, 3);
948        let mut jac_other = DMatrix::zeros(3, 3);
949        let result_jac = v1.left_minus(&v2, Some(&mut jac_self), Some(&mut jac_other));
950
951        // Verify result is the same
952        assert!((result_jac.component(0) - result.component(0)).abs() < 1e-10);
953        assert!((result_jac.component(1) - result.component(1)).abs() < 1e-10);
954        assert!((result_jac.component(2) - result.component(2)).abs() < 1e-10);
955
956        // Verify Jacobians
957        let identity = DMatrix::identity(3, 3);
958        let neg_identity = -&identity;
959        assert!((jac_self - &identity).norm() < 1e-10);
960        assert!((jac_other - &neg_identity).norm() < 1e-10);
961    }
962
963    #[test]
964    fn test_rn_left_right_equivalence() {
965        // For abelian groups, left and right operations should be equivalent
966        let v1 = Rn::from_vec(vec![1.0, 2.0, 3.0]);
967        let v2 = Rn::from_vec(vec![4.0, 5.0, 6.0]);
968        let delta = RnTangent::from_vec(vec![0.1, 0.2, 0.3]);
969
970        // Test plus operations equivalence
971        let right_plus = v1.right_plus(&delta, None, None);
972        let left_plus = v1.left_plus(&delta, None, None);
973        assert!(right_plus.is_approx(&left_plus, 1e-10));
974
975        // Test minus operations equivalence
976        let right_minus = v1.right_minus(&v2, None, None);
977        let left_minus = v1.left_minus(&v2, None, None);
978        assert!(right_minus.is_approx(&left_minus, 1e-10));
979    }
980
981    #[test]
982    fn test_rn_plus_minus_different_dimensions() {
983        // Test 2D operations
984        let v2d = Rn::from_vec(vec![1.0, 2.0]);
985        let delta2d = RnTangent::from_vec(vec![0.5, 1.0]);
986        let result2d = v2d.right_plus(&delta2d, None, None);
987        assert_eq!(result2d.dim(), 2);
988        assert!((result2d.component(0) - 1.5).abs() < 1e-10);
989        assert!((result2d.component(1) - 3.0).abs() < 1e-10);
990
991        // Test 5D operations
992        let v5d = Rn::from_vec(vec![1.0, 2.0, 3.0, 4.0, 5.0]);
993        let delta5d = RnTangent::from_vec(vec![0.1, 0.2, 0.3, 0.4, 0.5]);
994        let result5d = v5d.right_plus(&delta5d, None, None);
995        assert_eq!(result5d.dim(), 5);
996        for i in 0..5 {
997            assert!(
998                (result5d.component(i) - (i as f64 + 1.0 + (i as f64 + 1.0) * 0.1)).abs() < 1e-10
999            );
1000        }
1001    }
1002
1003    #[test]
1004    fn test_rn_plus_minus_edge_cases() {
1005        let v = Rn::from_vec(vec![1.0, 2.0, 3.0]);
1006
1007        // Test with zero tangent vector
1008        let zero_tangent = RnTangent::zeros(3);
1009        let result_zero = v.right_plus(&zero_tangent, None, None);
1010        assert!(v.is_approx(&result_zero, 1e-10));
1011
1012        // Test minus with itself (should give zero)
1013        let self_minus = v.right_minus(&v, None, None);
1014        assert!(self_minus.is_zero(1e-10));
1015
1016        // Test plus then minus (should recover original)
1017        let delta = RnTangent::from_vec(vec![0.5, 1.0, 1.5]);
1018        let plus_result = v.right_plus(&delta, None, None);
1019        let recovered_delta = plus_result.right_minus(&v, None, None);
1020        assert!(delta.is_approx(&recovered_delta, 1e-10));
1021    }
1022
1023    #[test]
1024    fn test_rn_jacobian_dimensions() {
1025        // Test that Jacobians have correct dimensions for different vector sizes
1026        let v1d = Rn::from_vec(vec![1.0]);
1027        let delta1d = RnTangent::from_vec(vec![0.1]);
1028        let mut jac1d = DMatrix::zeros(1, 1);
1029        v1d.right_plus(&delta1d, Some(&mut jac1d), None);
1030        assert_eq!(jac1d.nrows(), 1);
1031        assert_eq!(jac1d.ncols(), 1);
1032
1033        let v4d = Rn::from_vec(vec![1.0, 2.0, 3.0, 4.0]);
1034        let delta4d = RnTangent::from_vec(vec![0.1, 0.2, 0.3, 0.4]);
1035        let mut jac4d = DMatrix::zeros(4, 4);
1036        v4d.right_plus(&delta4d, Some(&mut jac4d), None);
1037        assert_eq!(jac4d.nrows(), 4);
1038        assert_eq!(jac4d.ncols(), 4);
1039
1040        // Verify they are identity matrices
1041        assert!((jac1d - DMatrix::identity(1, 1)).norm() < 1e-10);
1042        assert!((jac4d - DMatrix::identity(4, 4)).norm() < 1e-10);
1043    }
1044
1045    // T3: Accumulated Error Tests
1046
1047    #[test]
1048    fn test_rn_addition_chain() {
1049        // Add same vector 1000 times
1050        let increment = Rn::new(DVector::from_vec(vec![0.001, -0.002, 0.003]));
1051        let mut accumulated = Rn::new(DVector::zeros(3));
1052
1053        for _ in 0..1000 {
1054            accumulated = accumulated.compose(&increment, None, None);
1055        }
1056
1057        let expected = Rn::new(DVector::from_vec(vec![1.0, -2.0, 3.0]));
1058        assert!((accumulated.to_vector() - expected.to_vector()).norm() < 1e-10);
1059    }
1060
1061    // T2: Edge Case Tests
1062
1063    #[test]
1064    #[should_panic(expected = "Rn elements must have the same dimension")]
1065    fn test_rn_dimension_mismatch_compose() {
1066        let rn_2d = Rn::new(DVector::from_vec(vec![1.0, 2.0]));
1067        let rn_3d = Rn::new(DVector::from_vec(vec![3.0, 4.0, 5.0]));
1068
1069        let _ = rn_2d.compose(&rn_3d, None, None); // Should panic
1070    }
1071
1072    #[test]
1073    fn test_rn_zero_dimension() {
1074        let rn_0d = Rn::new(DVector::zeros(0));
1075        assert_eq!(rn_0d.dim(), 0);
1076
1077        let identity = Rn::new(DVector::zeros(0));
1078        let composed = rn_0d.compose(&identity, None, None);
1079        assert_eq!(composed.dim(), 0);
1080    }
1081
1082    #[test]
1083    fn test_rn_identity_with_dim() {
1084        for dim in [1, 2, 3, 5, 10] {
1085            let id = Rn::identity_with_dim(dim);
1086            assert_eq!(id.dim(), dim);
1087            assert!(id.norm() < 1e-15);
1088
1089            // Composing with identity should be no-op
1090            let v = Rn::random_with_dim(dim);
1091            let result = v.compose(&id, None, None);
1092            assert!(v.is_approx(&result, 1e-10));
1093        }
1094    }
1095
1096    #[test]
1097    fn test_rn_tangent_zero_with_dim() {
1098        for dim in [1, 2, 3, 5, 10] {
1099            let z = RnTangent::zero_with_dim(dim);
1100            assert_eq!(z.dim(), dim);
1101            assert!(z.is_zero(1e-15));
1102        }
1103    }
1104
1105    #[test]
1106    fn test_rn_tangent_is_dynamic() {
1107        assert!(RnTangent::is_dynamic());
1108    }
1109}