1use crate::{LieGroup, Tangent};
13use nalgebra::{DVector, Matrix1, Matrix2, Matrix3, UnitComplex, Vector2, Vector3};
14use std::{
15 fmt,
16 fmt::{Display, Formatter},
17};
18
19#[derive(Clone, PartialEq)]
23pub struct SO2 {
24 complex: UnitComplex<f64>,
26}
27
28impl Display for SO2 {
29 fn fmt(&self, f: &mut Formatter<'_>) -> fmt::Result {
30 write!(f, "SO2(angle: {:.4})", self.complex.angle())
31 }
32}
33
34impl From<DVector<f64>> for SO2 {
36 fn from(data: DVector<f64>) -> Self {
37 SO2::from_angle(data[0])
38 }
39}
40
41impl From<SO2> for DVector<f64> {
42 fn from(so2: SO2) -> Self {
43 DVector::from_vec(vec![so2.complex.angle()])
44 }
45}
46
47impl SO2 {
48 pub const DIM: usize = 2;
50
51 pub const DOF: usize = 1;
53
54 pub const REP_SIZE: usize = 2;
56
57 pub fn identity() -> Self {
61 SO2 {
62 complex: UnitComplex::identity(),
63 }
64 }
65
66 pub fn jacobian_identity() -> Matrix1<f64> {
70 Matrix1::<f64>::identity()
71 }
72
73 #[inline]
78 pub fn new(complex: UnitComplex<f64>) -> Self {
79 SO2 { complex }
80 }
81
82 pub fn from_angle(angle: f64) -> Self {
87 SO2::new(UnitComplex::from_angle(angle))
88 }
89
90 pub fn complex(&self) -> UnitComplex<f64> {
92 self.complex
93 }
94
95 #[inline]
97 pub fn angle(&self) -> f64 {
98 self.complex.angle()
99 }
100
101 pub fn rotation_matrix(&self) -> Matrix2<f64> {
103 self.complex.to_rotation_matrix().into_inner()
104 }
105}
106
107impl LieGroup for SO2 {
108 type TangentVector = SO2Tangent;
109 type JacobianMatrix = Matrix1<f64>;
110 type LieAlgebra = Matrix2<f64>;
111
112 fn inverse(&self, jacobian: Option<&mut Self::JacobianMatrix>) -> Self {
124 if let Some(jac) = jacobian {
125 *jac = -self.adjoint();
126 }
127 SO2 {
128 complex: self.complex.inverse(),
129 }
130 }
131
132 fn compose(
144 &self,
145 other: &Self,
146 jacobian_self: Option<&mut Self::JacobianMatrix>,
147 jacobian_other: Option<&mut Self::JacobianMatrix>,
148 ) -> Self {
149 if let Some(jac_self) = jacobian_self {
150 *jac_self = other.inverse(None).adjoint();
151 }
152 if let Some(jac_other) = jacobian_other {
153 *jac_other = Matrix1::identity();
154 }
155 SO2 {
156 complex: self.complex * other.complex,
157 }
158 }
159
160 fn log(&self, jacobian: Option<&mut Self::JacobianMatrix>) -> Self::TangentVector {
172 if let Some(jac) = jacobian {
173 *jac = Matrix1::identity();
174 }
175 SO2Tangent {
176 data: self.complex.angle(),
177 }
178 }
179
180 fn act(
193 &self,
194 vector: &Vector3<f64>,
195 _jacobian_self: Option<&mut Self::JacobianMatrix>,
196 _jacobian_vector: Option<&mut Matrix3<f64>>,
197 ) -> Vector3<f64> {
198 let point2d = Vector2::new(vector.x, vector.y);
199 let rotated_point = self.complex * point2d;
200 Vector3::new(rotated_point.x, rotated_point.y, vector.z)
201 }
202
203 fn adjoint(&self) -> Self::JacobianMatrix {
208 Matrix1::identity()
209 }
210
211 fn random() -> Self {
213 SO2::from_angle(rand::random::<f64>() * 2.0 * std::f64::consts::PI)
214 }
215
216 fn jacobian_identity() -> Self::JacobianMatrix {
217 Matrix1::<f64>::identity()
218 }
219
220 fn zero_jacobian() -> Self::JacobianMatrix {
221 Matrix1::<f64>::zeros()
222 }
223
224 fn normalize(&mut self) {
226 self.complex.renormalize();
227 }
228
229 fn is_valid(&self, tolerance: f64) -> bool {
231 let norm_diff = (self.complex.norm() - 1.0).abs();
232 norm_diff < tolerance
233 }
234
235 fn vee(&self) -> Self::TangentVector {
240 self.log(None)
241 }
242
243 fn is_approx(&self, other: &Self, tolerance: f64) -> bool {
249 let difference = self.right_minus(other, None, None);
250 difference.is_zero(tolerance)
251 }
252}
253
254#[derive(Clone, PartialEq)]
258pub struct SO2Tangent {
259 data: f64,
261}
262
263impl fmt::Display for SO2Tangent {
264 fn fmt(&self, f: &mut fmt::Formatter<'_>) -> fmt::Result {
265 write!(f, "so2(angle: {:.4})", self.data)
266 }
267}
268
269impl From<DVector<f64>> for SO2Tangent {
271 fn from(data_vector: DVector<f64>) -> Self {
272 SO2Tangent {
273 data: data_vector[0],
274 }
275 }
276}
277
278impl From<SO2Tangent> for DVector<f64> {
279 fn from(so2_tangent: SO2Tangent) -> Self {
280 DVector::from_vec(vec![so2_tangent.data])
281 }
282}
283
284impl SO2Tangent {
285 #[inline]
290 pub fn new(angle: f64) -> Self {
291 SO2Tangent { data: angle }
292 }
293
294 #[inline]
296 pub fn angle(&self) -> f64 {
297 self.data
298 }
299}
300
301impl Tangent<SO2> for SO2Tangent {
302 const DIM: usize = 1;
304
305 fn exp(&self, jacobian: Option<&mut <SO2 as LieGroup>::JacobianMatrix>) -> SO2 {
311 let angle = self.angle();
312 let complex = UnitComplex::new(angle);
313
314 if let Some(jac) = jacobian {
315 *jac = Matrix1::identity();
316 }
317
318 SO2::new(complex)
319 }
320
321 fn right_jacobian(&self) -> <SO2 as LieGroup>::JacobianMatrix {
323 Matrix1::identity()
324 }
325
326 fn left_jacobian(&self) -> <SO2 as LieGroup>::JacobianMatrix {
328 Matrix1::identity()
329 }
330
331 fn right_jacobian_inv(&self) -> <SO2 as LieGroup>::JacobianMatrix {
333 Matrix1::identity()
334 }
335
336 fn left_jacobian_inv(&self) -> <SO2 as LieGroup>::JacobianMatrix {
338 Matrix1::identity()
339 }
340
341 fn hat(&self) -> <SO2 as LieGroup>::LieAlgebra {
343 let theta = self.data;
344 Matrix2::new(0.0, -theta, theta, 0.0)
345 }
346
347 fn zero() -> Self {
349 SO2Tangent { data: 0.0 }
350 }
351
352 fn random() -> Self {
354 SO2Tangent {
355 data: rand::random::<f64>() * 0.2 - 0.1,
356 }
357 }
358
359 fn is_zero(&self, tolerance: f64) -> bool {
361 self.data.abs() < tolerance
362 }
363
364 fn normalize(&mut self) {
366 }
369
370 fn normalized(&self) -> Self {
372 if self.data.abs() > f64::EPSILON {
373 SO2Tangent::new(self.data.signum())
374 } else {
375 SO2Tangent::new(0.0)
376 }
377 }
378
379 fn small_adj(&self) -> <SO2 as LieGroup>::JacobianMatrix {
383 Matrix1::zeros()
384 }
385
386 fn lie_bracket(&self, _other: &Self) -> <SO2 as LieGroup>::TangentVector {
390 SO2Tangent::zero()
391 }
392
393 fn is_approx(&self, other: &Self, tolerance: f64) -> bool {
399 (self.data - other.data).abs() < tolerance
400 }
401
402 fn generator(&self, i: usize) -> <SO2 as LieGroup>::LieAlgebra {
410 assert_eq!(i, 0, "SO(2) only has one generator (index 0)");
411 Matrix2::new(0.0, -1.0, 1.0, 0.0)
412 }
413}
414
415#[cfg(test)]
416mod tests {
417 use super::*;
418 use nalgebra::{DMatrix, DVector};
419 use std::f64::consts::PI;
420
421 const TOLERANCE: f64 = 1e-12;
422
423 fn numerical_jacobian<F>(
425 func: F,
426 point: &DVector<f64>,
427 output_dim: usize,
428 epsilon: f64,
429 ) -> DMatrix<f64>
430 where
431 F: Fn(&DVector<f64>) -> DVector<f64>,
432 {
433 let input_dim = point.len();
434 let mut jacobian = DMatrix::zeros(output_dim, input_dim);
435
436 for i in 0..input_dim {
437 let mut point_plus = point.clone();
438 let mut point_minus = point.clone();
439 point_plus[i] += epsilon;
440 point_minus[i] -= epsilon;
441
442 let output_plus = func(&point_plus);
443 let output_minus = func(&point_minus);
444 let derivative = (output_plus - output_minus) / (2.0 * epsilon);
445
446 jacobian.set_column(i, &derivative);
447 }
448
449 jacobian
450 }
451
452 #[test]
453 fn test_so2_identity() {
454 let so2 = SO2::identity();
455 assert!((so2.angle() - 0.0).abs() < TOLERANCE);
456 }
457
458 #[test]
459 fn test_so2_inverse() {
460 let so2 = SO2::from_angle(PI / 4.0);
461 let so2_inv = so2.inverse(None);
462 assert!((so2_inv.angle() + PI / 4.0).abs() < TOLERANCE);
463 }
464
465 #[test]
466 fn test_so2_compose() {
467 let so2_a = SO2::from_angle(PI / 4.0);
468 let so2_b = SO2::from_angle(PI / 2.0);
469 let composed = so2_a.compose(&so2_b, None, None);
470 assert!((composed.angle() - (3.0 * PI / 4.0)).abs() < TOLERANCE);
471 }
472
473 #[test]
474 fn test_so2_exp_log_consistency() {
475 let angle = PI / 4.0;
476 let tangent = SO2Tangent::new(angle);
477 let so2 = tangent.exp(None);
478 let recovered_tangent = so2.log(None);
479
480 assert!((tangent.angle() - recovered_tangent.angle()).abs() < 1e-10);
481 }
482
483 #[test]
486 fn test_so2_vee() {
487 let so2 = SO2::from_angle(PI / 3.0);
488 let tangent_log = so2.log(None);
489 let tangent_vee = so2.vee();
490
491 assert!((tangent_log.angle() - tangent_vee.angle()).abs() < 1e-10);
492 }
493
494 #[test]
495 fn test_so2_is_approx() {
496 let so2_1 = SO2::from_angle(PI / 4.0);
497 let so2_2 = SO2::from_angle(PI / 4.0 + 1e-12);
498 let so2_3 = SO2::from_angle(PI / 2.0);
499
500 assert!(so2_1.is_approx(&so2_1, 1e-10));
501 assert!(so2_1.is_approx(&so2_2, 1e-10));
502 assert!(!so2_1.is_approx(&so2_3, 1e-10));
503 }
504
505 #[test]
506 fn test_so2_tangent_small_adj() {
507 let tangent = SO2Tangent::new(PI / 6.0);
508 let small_adj = tangent.small_adj();
509
510 assert!((small_adj[(0, 0)]).abs() < 1e-10);
512 }
513
514 #[test]
515 fn test_so2_tangent_lie_bracket() {
516 let tangent_a = SO2Tangent::new(0.1);
517 let tangent_b = SO2Tangent::new(0.2);
518
519 let bracket = tangent_a.lie_bracket(&tangent_b);
520
521 assert!(bracket.is_zero(1e-10));
523
524 let bracket_ba = tangent_b.lie_bracket(&tangent_a);
526 assert!(bracket.lie_bracket(&tangent_b).is_zero(1e-10)); assert!(bracket_ba.is_zero(1e-10));
530 }
531
532 #[test]
533 fn test_so2_tangent_is_approx() {
534 let tangent_1 = SO2Tangent::new(0.5);
535 let tangent_2 = SO2Tangent::new(0.5 + 1e-12);
536 let tangent_3 = SO2Tangent::new(1.0);
537
538 assert!(tangent_1.is_approx(&tangent_1, 1e-10));
539 assert!(tangent_1.is_approx(&tangent_2, 1e-10));
540 assert!(!tangent_1.is_approx(&tangent_3, 1e-10));
541 }
542
543 #[test]
544 fn test_so2_generator() {
545 let tangent = SO2Tangent::new(1.0);
546 let generator = tangent.generator(0);
547
548 let expected = Matrix2::new(0.0, -1.0, 1.0, 0.0);
550
551 assert!((generator - expected).norm() < 1e-10);
552 }
553
554 #[test]
555 #[should_panic]
556 fn test_so2_generator_invalid_index() {
557 let tangent = SO2Tangent::new(1.0);
558 let _generator = tangent.generator(1); }
560
561 #[test]
562 fn test_so2_bracket_hat_relationship() {
563 let a = SO2Tangent::new(0.1);
564 let b = SO2Tangent::new(0.2);
565
566 let bracket_hat = a.lie_bracket(&b).hat();
568 let expected = a.hat() * b.hat() - b.hat() * a.hat();
569
570 assert!((bracket_hat - expected).norm() < 1e-10);
571 assert!(expected.norm() < 1e-10); }
573
574 #[test]
575 fn test_so2_right_jacobian_numerical() {
576 let epsilon = 1e-7;
577 let tolerance = 1e-4;
578
579 let tangent = SO2Tangent::new(0.5);
580 let jr_analytical = tangent.right_jacobian();
581
582 let angle_vec = DVector::from_vec(vec![tangent.angle()]);
584 let jr_numerical = numerical_jacobian(
585 |theta| {
586 let tang = SO2Tangent::new(theta[0]);
587 let so2 = tang.exp(None);
588 let log_result = so2.log(None);
589 DVector::from_vec(vec![log_result.angle()])
590 },
591 &angle_vec,
592 1,
593 epsilon,
594 );
595
596 assert!(
597 (jr_analytical - &jr_numerical).norm() < tolerance,
598 "Right Jacobian mismatch: analytical = {}, numerical = {}",
599 jr_analytical,
600 jr_numerical
601 );
602 }
603
604 #[test]
605 fn test_so2_left_jacobian_numerical() {
606 let epsilon = 1e-7;
607 let tolerance = 1e-4;
608
609 let tangent = SO2Tangent::new(0.5);
610 let jl_analytical = tangent.left_jacobian();
611
612 let angle_vec = DVector::from_vec(vec![tangent.angle()]);
613 let jl_numerical = numerical_jacobian(
614 |theta| {
615 let tang = SO2Tangent::new(theta[0]);
616 let so2 = tang.exp(None);
617 let log_result = so2.log(None);
618 DVector::from_vec(vec![log_result.angle()])
619 },
620 &angle_vec,
621 1,
622 epsilon,
623 );
624
625 assert!((jl_analytical - jl_numerical).norm() < tolerance);
626 }
627
628 #[test]
631 fn test_so2_jacobian_inverse_identity() {
632 let tangent = SO2Tangent::new(0.5);
634 let jr = tangent.right_jacobian();
635 let jr_inv = tangent.right_jacobian_inv();
636 let product = jr * jr_inv;
637
638 assert!((product[(0, 0)] - 1.0).abs() < 1e-10);
639
640 let jl = tangent.left_jacobian();
642 let jl_inv = tangent.left_jacobian_inv();
643 let product_left = jl * jl_inv;
644
645 assert!((product_left[(0, 0)] - 1.0).abs() < 1e-10);
646 }
647
648 #[test]
649 fn test_so2_display() {
650 let r = SO2::from_angle(0.5);
651 let s = format!("{r}");
652 assert!(!s.is_empty(), "Display should produce output, got: {s}");
653
654 let t = SO2Tangent::new(1.2);
655 let st = format!("{t}");
656 assert!(
657 !st.is_empty(),
658 "Tangent Display should produce output, got: {st}"
659 );
660 }
661
662 #[test]
663 fn test_so2_from_dvector_and_back() {
664 let angle = 1.0f64;
665 let v = DVector::from_vec(vec![angle]);
666 let r = SO2::from(v);
667 let back: DVector<f64> = DVector::from(r);
669 assert_eq!(back.len(), 1);
670 assert!((back[0] - angle).abs() < 1e-9);
672 }
673
674 #[test]
675 fn test_so2_tangent_from_dvector_and_back() {
676 let v = DVector::from_vec(vec![0.7f64]);
677 let t = SO2Tangent::from(v);
678 let v2: DVector<f64> = DVector::from(t);
679 assert!((v2[0] - 0.7).abs() < 1e-10);
680 }
681
682 #[test]
683 fn test_so2_rotation_matrix() {
684 let r = SO2::from_angle(0.0);
685 let mat = r.rotation_matrix();
686 assert!((mat[(0, 0)] - 1.0).abs() < 1e-10);
687 assert!(mat[(0, 1)].abs() < 1e-10);
688 }
689
690 #[test]
691 fn test_so2_complex_angle_accessors() {
692 let angle = std::f64::consts::FRAC_PI_4;
693 let r = SO2::from_angle(angle);
694 let c = r.complex();
695 assert!((c.re - angle.cos()).abs() < 1e-9);
696 assert!((c.im - angle.sin()).abs() < 1e-9);
697 assert!((r.angle() - angle).abs() < 1e-9);
698 }
699
700 #[test]
701 fn test_so2_normalize_is_valid() {
702 let mut r = SO2::from_angle(0.3);
703 r.normalize();
704 assert!(r.is_valid(1e-6));
705 }
706
707 #[test]
708 fn test_so2_tangent_normalized() {
709 let t_pos = SO2Tangent::new(3.0);
710 let tn = t_pos.normalized();
711 assert!((tn.angle() - 1.0).abs() < 1e-9);
712
713 let t_neg = SO2Tangent::new(-2.0);
714 let tn_neg = t_neg.normalized();
715 assert!((tn_neg.angle() - (-1.0)).abs() < 1e-9);
716
717 let t_zero = SO2Tangent::new(0.0);
718 let tn_zero = t_zero.normalized();
719 assert!((tn_zero.angle()).abs() < 1e-9);
720 }
721
722 #[test]
723 fn test_so2_tangent_is_zero() {
724 let zero = SO2Tangent::new(0.0);
725 assert!(zero.is_zero(1e-9));
726 let nonzero = SO2Tangent::new(0.1);
727 assert!(!nonzero.is_zero(1e-9));
728 }
729
730 #[test]
731 fn test_so2_random() {
732 let r = SO2::random();
733 assert!(r.is_valid(1e-6));
734
735 let t = SO2Tangent::random();
736 let _ = t; }
738
739 #[test]
740 fn test_so2_adjoint_zero_jacobian_identity() {
741 let r = SO2::from_angle(0.5);
742 let adj = r.adjoint();
743 assert!((adj[0] - 1.0).abs() < 1e-10);
744
745 let zj = SO2::zero_jacobian();
746 assert!(zj[0].abs() < 1e-10);
747
748 let ji = SO2::jacobian_identity();
749 assert!((ji[0] - 1.0).abs() < 1e-10);
750 }
751
752 #[test]
753 fn test_so2_compose_with_jacobians() {
754 let r1 = SO2::from_angle(0.3);
755 let r2 = SO2::from_angle(0.2);
756 let mut j_self = Matrix1::zeros();
757 let mut j_other = Matrix1::zeros();
758 let result = r1.compose(&r2, Some(&mut j_self), Some(&mut j_other));
759 assert!(result.is_valid(1e-9));
760 assert!(j_self[0].is_finite());
761 assert!(j_other[0].is_finite());
762 }
763
764 #[test]
765 fn test_so2_log_with_jacobian() {
766 let r = SO2::from_angle(0.5);
767 let mut jac = Matrix1::zeros();
768 let t = r.log(Some(&mut jac));
769 assert!((t.angle() - 0.5).abs() < 1e-9);
770 assert!((jac[0] - 1.0).abs() < 1e-10);
771 }
772
773 #[test]
774 fn test_so2_inverse_with_jacobian() {
775 let r = SO2::from_angle(0.4);
776 let mut jac = Matrix1::zeros();
777 let inv = r.inverse(Some(&mut jac));
778 assert!(inv.is_valid(1e-9));
779 assert!(jac[0].is_finite());
780 }
781
782 #[test]
783 fn test_so2_tangent_hat() {
784 let t = SO2Tangent::new(1.0);
785 let hat = t.hat();
786 assert!(hat[(0, 0)].abs() < 1e-10);
788 assert!((hat[(1, 0)] - 1.0).abs() < 1e-10);
789 assert!((hat[(0, 1)] - (-1.0)).abs() < 1e-10);
790 }
791
792 #[test]
793 fn test_so2_tangent_exp_with_jacobian() {
794 use crate::Tangent;
795 let t = SO2Tangent::new(0.3);
796 let mut jac = Matrix1::zeros();
797 let r = t.exp(Some(&mut jac));
798 assert!(r.is_valid(1e-9));
799 assert!((jac[0] - 1.0).abs() < 1e-10);
800 }
801
802 #[test]
803 fn test_so2_tangent_zero() {
804 use crate::Tangent;
805 let zero = SO2Tangent::zero();
806 assert!(zero.is_zero(1e-9));
807 }
808}