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