1use crate::{LieGroup, Tangent};
36use nalgebra::{DVector, Matrix3, Matrix4, Quaternion, Unit, UnitQuaternion, Vector3};
37use std::{
38 fmt,
39 fmt::{Display, Formatter},
40};
41
42#[derive(Clone, PartialEq)]
46pub struct SO3 {
47 quaternion: UnitQuaternion<f64>,
49}
50
51impl Display for SO3 {
52 fn fmt(&self, f: &mut Formatter<'_>) -> fmt::Result {
53 let q = self.quaternion.quaternion();
54 write!(
55 f,
56 "SO3(quaternion: [w: {:.4}, x: {:.4}, y: {:.4}, z: {:.4}])",
57 q.w, q.i, q.j, q.k
58 )
59 }
60}
61
62impl SO3 {
63 pub const DIM: usize = 3;
65
66 pub const DOF: usize = 3;
68
69 pub const REP_SIZE: usize = 4;
71
72 pub fn identity() -> Self {
76 SO3 {
77 quaternion: UnitQuaternion::identity(),
78 }
79 }
80
81 pub fn jacobian_identity() -> Matrix3<f64> {
85 Matrix3::<f64>::identity()
86 }
87
88 #[inline]
93 pub fn new(quaternion: UnitQuaternion<f64>) -> Self {
94 SO3 { quaternion }
95 }
96
97 pub fn from_quaternion_coeffs(x: f64, y: f64, z: f64, w: f64) -> Self {
109 let q = Quaternion::new(w, x, y, z);
110 SO3::new(UnitQuaternion::from_quaternion(q))
111 }
112
113 pub fn from_quaternion_wxyz(w: f64, x: f64, y: f64, z: f64) -> Self {
125 let q = Quaternion::new(w, x, y, z);
126 SO3::new(UnitQuaternion::from_quaternion(q))
127 }
128
129 pub fn from_euler_angles(roll: f64, pitch: f64, yaw: f64) -> Self {
131 let quaternion = UnitQuaternion::from_euler_angles(roll, pitch, yaw);
132 SO3::new(quaternion)
133 }
134
135 pub fn from_axis_angle(axis: &Vector3<f64>, angle: f64) -> Self {
137 let unit_axis = Unit::new_normalize(*axis);
138 let quaternion = UnitQuaternion::from_axis_angle(&unit_axis, angle);
139 SO3::new(quaternion)
140 }
141
142 pub fn from_scaled_axis(axis_angle: Vector3<f64>) -> Self {
144 let quaternion = UnitQuaternion::from_scaled_axis(axis_angle);
145 SO3::new(quaternion)
146 }
147
148 pub fn quaternion(&self) -> UnitQuaternion<f64> {
150 self.quaternion
151 }
152
153 pub fn from_quaternion(quaternion: UnitQuaternion<f64>) -> Self {
155 Self::new(quaternion)
156 }
157
158 pub fn to_quaternion(&self) -> UnitQuaternion<f64> {
160 self.quaternion
161 }
162
163 pub fn quat(&self) -> Quaternion<f64> {
165 *self.quaternion.quaternion()
166 }
167
168 #[inline]
170 pub fn x(&self) -> f64 {
171 self.quaternion.i
172 }
173
174 #[inline]
176 pub fn y(&self) -> f64 {
177 self.quaternion.j
178 }
179
180 #[inline]
182 pub fn z(&self) -> f64 {
183 self.quaternion.k
184 }
185
186 #[inline]
188 pub fn w(&self) -> f64 {
189 self.quaternion.w
190 }
191
192 pub fn rotation_matrix(&self) -> Matrix3<f64> {
194 self.quaternion.to_rotation_matrix().into_inner()
195 }
196
197 pub fn transform(&self) -> Matrix4<f64> {
199 self.quaternion.to_homogeneous()
200 }
201
202 pub fn set_quaternion(&mut self, coeffs: &[f64; 4]) {
204 let q = Quaternion::new(coeffs[0], coeffs[1], coeffs[2], coeffs[3]);
205 self.quaternion = UnitQuaternion::from_quaternion(q);
206 }
207
208 #[inline]
210 pub fn coeffs(&self) -> [f64; 4] {
211 let q = self.quaternion.quaternion();
212 [q.w, q.i, q.j, q.k]
213 }
214
215 pub fn distance(&self, other: &Self) -> f64 {
220 self.between(other, None, None).log(None).angle()
221 }
222}
223
224impl From<DVector<f64>> for SO3 {
226 fn from(data: DVector<f64>) -> Self {
227 SO3::from_quaternion_wxyz(data[0], data[1], data[2], data[3])
228 }
229}
230
231impl From<SO3> for DVector<f64> {
232 fn from(so3: SO3) -> Self {
233 DVector::from_vec(so3.coeffs().to_vec())
234 }
235}
236
237impl LieGroup for SO3 {
239 type TangentVector = SO3Tangent;
240 type JacobianMatrix = Matrix3<f64>;
241 type LieAlgebra = Matrix3<f64>;
242
243 fn inverse(&self, jacobian: Option<&mut Self::JacobianMatrix>) -> Self {
255 let inverse_quat = self.quaternion.inverse();
256
257 if let Some(jac) = jacobian {
258 *jac = -self.adjoint();
259 }
260
261 SO3 {
262 quaternion: inverse_quat,
263 }
264 }
265
266 fn compose(
281 &self,
282 other: &Self,
283 jacobian_self: Option<&mut Self::JacobianMatrix>,
284 jacobian_other: Option<&mut Self::JacobianMatrix>,
285 ) -> Self {
286 let result = SO3 {
287 quaternion: self.quaternion * other.quaternion,
288 };
289
290 if let Some(jac_self) = jacobian_self {
291 *jac_self = other.inverse(None).adjoint();
292 }
293
294 if let Some(jac_other) = jacobian_other {
295 *jac_other = Matrix3::identity();
296 }
297
298 result
299 }
300
301 fn log(&self, jacobian: Option<&mut Self::JacobianMatrix>) -> Self::TangentVector {
314 debug_assert!(
315 (self.quaternion.norm() - 1.0).abs() < 1e-6,
316 "SO3::log() requires normalized quaternion, norm = {}",
317 self.quaternion.norm()
318 );
319
320 let q = self.quaternion.quaternion();
321 let sin_angle_squared = q.i * q.i + q.j * q.j + q.k * q.k;
322
323 let log_coeff = if sin_angle_squared > crate::SMALL_ANGLE_THRESHOLD {
324 let sin_angle = sin_angle_squared.sqrt();
325 let cos_angle = q.w;
326
327 let two_angle = 2.0
335 * if cos_angle < 0.0 {
336 f64::atan2(-sin_angle, -cos_angle)
337 } else {
338 f64::atan2(sin_angle, cos_angle)
339 };
340
341 two_angle / sin_angle
342 } else {
343 2.0
344 };
345
346 let axis_angle = SO3Tangent::new(Vector3::new(
347 q.i * log_coeff,
348 q.j * log_coeff,
349 q.k * log_coeff,
350 ));
351
352 if let Some(jac) = jacobian {
353 *jac = axis_angle.right_jacobian_inv();
354 }
355
356 axis_angle
357 }
358
359 fn act(
360 &self,
361 vector: &Vector3<f64>,
362 jacobian_self: Option<&mut Self::JacobianMatrix>,
363 jacobian_vector: Option<&mut Matrix3<f64>>,
364 ) -> Vector3<f64> {
365 let result = self.quaternion * vector;
366
367 if let Some(jac_self) = jacobian_self {
368 let vector_hat = SO3Tangent::new(*vector).hat();
370 *jac_self = -self.rotation_matrix() * vector_hat;
371 }
372
373 if let Some(jac_vector) = jacobian_vector {
374 *jac_vector = self.rotation_matrix();
375 }
376
377 result
378 }
379
380 fn adjoint(&self) -> Self::JacobianMatrix {
381 self.rotation_matrix()
382 }
383
384 fn random() -> Self {
385 SO3 {
386 quaternion: UnitQuaternion::from_scaled_axis(Vector3::new(
387 rand::random::<f64>() * 2.0 - 1.0,
388 rand::random::<f64>() * 2.0 - 1.0,
389 rand::random::<f64>() * 2.0 - 1.0,
390 )),
391 }
392 }
393
394 fn jacobian_identity() -> Self::JacobianMatrix {
395 Matrix3::<f64>::identity()
396 }
397
398 fn zero_jacobian() -> Self::JacobianMatrix {
399 Matrix3::<f64>::zeros()
400 }
401
402 fn normalize(&mut self) {
403 let q = self.quaternion.into_inner().normalize();
404 self.quaternion = UnitQuaternion::from_quaternion(q);
405 }
406
407 fn is_valid(&self, tolerance: f64) -> bool {
408 let norm_diff = (self.quaternion.norm() - 1.0).abs();
410 norm_diff < tolerance
411 }
412
413 fn vee(&self) -> Self::TangentVector {
418 self.log(None)
419 }
420
421 fn is_approx(&self, other: &Self, tolerance: f64) -> bool {
427 let difference = self.right_minus(other, None, None);
428 difference.is_zero(tolerance)
429 }
430}
431
432#[derive(Clone, PartialEq)]
438pub struct SO3Tangent {
439 data: Vector3<f64>,
441}
442
443impl fmt::Display for SO3Tangent {
444 fn fmt(&self, f: &mut fmt::Formatter<'_>) -> fmt::Result {
445 write!(
446 f,
447 "so3(axis-angle: [{:.4}, {:.4}, {:.4}])",
448 self.data.x, self.data.y, self.data.z
449 )
450 }
451}
452
453impl From<DVector<f64>> for SO3Tangent {
455 fn from(data_vector: DVector<f64>) -> Self {
456 SO3Tangent {
457 data: Vector3::new(data_vector[0], data_vector[1], data_vector[2]),
458 }
459 }
460}
461
462impl From<SO3Tangent> for DVector<f64> {
463 fn from(so3_tangent: SO3Tangent) -> Self {
464 DVector::from_vec(vec![
465 so3_tangent.data.x,
466 so3_tangent.data.y,
467 so3_tangent.data.z,
468 ])
469 }
470}
471
472impl SO3Tangent {
473 #[inline]
478 pub fn new(axis_angle: Vector3<f64>) -> Self {
479 SO3Tangent { data: axis_angle }
480 }
481
482 pub fn from_components(x: f64, y: f64, z: f64) -> Self {
484 SO3Tangent::new(Vector3::new(x, y, z))
485 }
486
487 #[inline]
489 pub fn axis_angle(&self) -> Vector3<f64> {
490 self.data
491 }
492
493 #[inline]
495 pub fn angle(&self) -> f64 {
496 self.data.norm()
497 }
498
499 #[inline]
501 pub fn axis(&self) -> Vector3<f64> {
502 let norm = self.data.norm();
503 if norm < f64::EPSILON {
504 Vector3::identity()
505 } else {
506 self.data / norm
507 }
508 }
509
510 #[inline]
512 pub fn x(&self) -> f64 {
513 self.data.x
514 }
515
516 #[inline]
518 pub fn y(&self) -> f64 {
519 self.data.y
520 }
521
522 #[inline]
524 pub fn z(&self) -> f64 {
525 self.data.z
526 }
527
528 #[inline]
530 pub fn coeffs(&self) -> Vector3<f64> {
531 self.data
532 }
533
534 pub fn ang(&self) -> Vector3<f64> {
536 self.data
537 }
538}
539
540impl Tangent<SO3> for SO3Tangent {
542 const DIM: usize = 3;
544
545 fn exp(&self, jacobian: Option<&mut <SO3 as LieGroup>::JacobianMatrix>) -> SO3 {
559 let theta_squared = self.data.norm_squared();
560
561 let quaternion = if theta_squared > crate::SMALL_ANGLE_THRESHOLD {
562 UnitQuaternion::from_scaled_axis(self.data)
563 } else {
564 UnitQuaternion::from_quaternion(Quaternion::new(
565 1.0,
566 self.data.x / 2.0,
567 self.data.y / 2.0,
568 self.data.z / 2.0,
569 ))
570 };
571
572 if let Some(jac) = jacobian {
573 *jac = self.right_jacobian();
574 }
575
576 SO3 { quaternion }
577 }
578
579 fn right_jacobian(&self) -> <SO3 as LieGroup>::JacobianMatrix {
586 self.left_jacobian().transpose()
587 }
588
589 fn left_jacobian(&self) -> <SO3 as LieGroup>::JacobianMatrix {
596 let angle = self.data.norm_squared();
597 let tangent_skew = self.hat();
598
599 if angle <= crate::SMALL_ANGLE_THRESHOLD {
600 Matrix3::identity() + 0.5 * tangent_skew
601 } else {
602 let theta = angle.sqrt();
603 let sin_theta = theta.sin();
604 let cos_theta = theta.cos();
605
606 Matrix3::identity()
607 + (1.0 - cos_theta) / angle * tangent_skew
608 + (theta - sin_theta) / (angle * theta) * tangent_skew * tangent_skew
609 }
610 }
611
612 fn right_jacobian_inv(&self) -> <SO3 as LieGroup>::JacobianMatrix {
619 self.left_jacobian_inv().transpose()
620 }
621
622 fn left_jacobian_inv(&self) -> <SO3 as LieGroup>::JacobianMatrix {
629 let angle = self.data.norm_squared();
630 let tangent_skew = self.hat();
631
632 if angle <= crate::SMALL_ANGLE_THRESHOLD {
633 Matrix3::identity() - 0.5 * tangent_skew
634 } else {
635 let theta = angle.sqrt();
636 let sin_theta = theta.sin();
637 let cos_theta = theta.cos();
638
639 Matrix3::identity() - (0.5 * tangent_skew)
640 + (1.0 / angle - (1.0 + cos_theta) / (2.0 * theta * sin_theta))
641 * tangent_skew
642 * tangent_skew
643 }
644 }
645
646 fn hat(&self) -> <SO3 as LieGroup>::LieAlgebra {
652 Matrix3::new(
653 0.0,
654 -self.data.z,
655 self.data.y,
656 self.data.z,
657 0.0,
658 -self.data.x,
659 -self.data.y,
660 self.data.x,
661 0.0,
662 )
663 }
664
665 fn zero() -> <SO3 as LieGroup>::TangentVector {
666 Self::new(Vector3::zeros())
667 }
668
669 fn random() -> <SO3 as LieGroup>::TangentVector {
670 Self::new(Vector3::new(
671 rand::random::<f64>() * 0.2 - 0.1,
672 rand::random::<f64>() * 0.2 - 0.1,
673 rand::random::<f64>() * 0.2 - 0.1,
674 ))
675 }
676
677 fn is_zero(&self, tolerance: f64) -> bool {
678 self.data.norm() < tolerance
679 }
680
681 fn normalize(&mut self) {
682 let norm = self.data.norm();
683 if norm > f64::EPSILON {
684 self.data /= norm;
685 }
686 }
687
688 fn normalized(&self) -> <SO3 as LieGroup>::TangentVector {
689 let norm = self.data.norm();
690 if norm > f64::EPSILON {
691 SO3Tangent::new(self.data / norm)
692 } else {
693 Self::zero()
694 }
695 }
696
697 fn small_adj(&self) -> <SO3 as LieGroup>::JacobianMatrix {
701 self.hat()
702 }
703
704 fn lie_bracket(&self, other: &Self) -> <SO3 as LieGroup>::TangentVector {
708 let bracket_result = self.small_adj() * other.data;
709 SO3Tangent::new(bracket_result)
710 }
711
712 fn is_approx(&self, other: &Self, tolerance: f64) -> bool {
718 (self.data - other.data).norm() < tolerance
719 }
720
721 fn generator(&self, i: usize) -> <SO3 as LieGroup>::LieAlgebra {
729 assert!(i < 3, "SO(3) only has generators for indices 0, 1, 2");
730
731 match i {
732 0 => {
733 Matrix3::new(0.0, 0.0, 0.0, 0.0, 0.0, -1.0, 0.0, 1.0, 0.0)
735 }
736 1 => {
737 Matrix3::new(0.0, 0.0, 1.0, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0)
739 }
740 2 => {
741 Matrix3::new(0.0, -1.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0)
743 }
744 _ => unreachable!(),
745 }
746 }
747}
748
749#[cfg(test)]
750mod tests {
751 use super::*;
752 use core::f64;
753 use std::f64::consts::PI;
754
755 const TOLERANCE: f64 = 1e-12;
756
757 #[test]
758 fn test_so3_constructor_datatype() {
759 let so3 = SO3::from_quaternion_coeffs(0.0, 0.0, 0.0, 1.0);
760 assert_eq!(0.0, so3.x());
761 assert_eq!(0.0, so3.y());
762 assert_eq!(0.0, so3.z());
763 assert_eq!(1.0, so3.w());
764 }
765
766 #[test]
767 fn test_so3_constructor_quat() {
768 let quat = UnitQuaternion::identity();
769 let so3 = SO3::new(quat);
770 assert_eq!(0.0, so3.x());
771 assert_eq!(0.0, so3.y());
772 assert_eq!(0.0, so3.z());
773 assert_eq!(1.0, so3.w());
774 }
775
776 #[test]
777 fn test_so3_constructor_euler() {
778 let so3 = SO3::from_euler_angles(0.0, 0.0, 0.0);
779 assert_eq!(0.0, so3.x());
780 assert_eq!(0.0, so3.y());
781 assert_eq!(0.0, so3.z());
782 assert_eq!(1.0, so3.w());
783 }
784
785 #[test]
786 fn test_so3_identity() {
787 let so3 = SO3::identity();
788 assert_eq!(0.0, so3.x());
789 assert_eq!(0.0, so3.y());
790 assert_eq!(0.0, so3.z());
791 assert_eq!(1.0, so3.w());
792 }
793
794 #[test]
795 fn test_so3_coeffs() {
796 let so3 = SO3::from_quaternion_coeffs(0.0, 0.0, 0.0, 1.0);
798 let coeffs = so3.coeffs();
799 assert!((coeffs[0] - 1.0).abs() < TOLERANCE); assert!((coeffs[1] - 0.0).abs() < TOLERANCE); assert!((coeffs[2] - 0.0).abs() < TOLERANCE); assert!((coeffs[3] - 0.0).abs() < TOLERANCE); let so3 = SO3::from_quaternion_coeffs(0.1, 0.2, 0.3, 0.4);
806 let coeffs = so3.coeffs();
807 let original_quat = Quaternion::new(0.4, 0.1, 0.2, 0.3);
808 let normalized_quat = original_quat.normalize();
809 assert!((coeffs[0] - normalized_quat.w).abs() < TOLERANCE);
810 assert!((coeffs[1] - normalized_quat.i).abs() < TOLERANCE);
811 assert!((coeffs[2] - normalized_quat.j).abs() < TOLERANCE);
812 assert!((coeffs[3] - normalized_quat.k).abs() < TOLERANCE);
813 }
814
815 #[test]
816 fn test_so3_random() {
817 let so3 = SO3::random();
818 assert!((so3.quaternion().norm() - 1.0).abs() < TOLERANCE);
819 }
820
821 #[test]
822 fn test_so3_transform() {
823 let so3 = SO3::identity();
824 let transform = so3.transform();
825
826 assert_eq!(4, transform.nrows());
827 assert_eq!(4, transform.ncols());
828
829 for i in 0..4 {
831 for j in 0..4 {
832 if i == j {
833 assert!((transform[(i, j)] - 1.0).abs() < TOLERANCE);
834 } else {
835 assert!(transform[(i, j)].abs() < TOLERANCE);
836 }
837 }
838 }
839 }
840
841 #[test]
842 fn test_so3_rotation() {
843 let so3 = SO3::identity();
844 let rotation = so3.rotation_matrix();
845
846 assert_eq!(3, rotation.nrows());
847 assert_eq!(3, rotation.ncols());
848
849 for i in 0..3 {
851 for j in 0..3 {
852 if i == j {
853 assert!((rotation[(i, j)] - 1.0).abs() < TOLERANCE);
854 } else {
855 assert!(rotation[(i, j)].abs() < TOLERANCE);
856 }
857 }
858 }
859 }
860
861 #[test]
862 fn test_so3_inverse() {
863 let so3 = SO3::identity();
865 let so3_inv = so3.inverse(None);
866 assert_eq!(0.0, so3_inv.x());
867 assert_eq!(0.0, so3_inv.y());
868 assert_eq!(0.0, so3_inv.z());
869 assert_eq!(1.0, so3_inv.w());
870
871 let so3 = SO3::random();
873 let so3_inv = so3.inverse(None);
874 assert!((so3.x() + so3_inv.x()).abs() < TOLERANCE);
875 assert!((so3.y() + so3_inv.y()).abs() < TOLERANCE);
876 assert!((so3.z() + so3_inv.z()).abs() < TOLERANCE);
877 assert!((so3.w() - so3_inv.w()).abs() < TOLERANCE);
878 }
879
880 #[test]
881 fn test_so3_inverse_jacobian() {
882 let so3 = SO3::identity();
883 let mut jacobian = Matrix3::zeros();
884 let so3_inv = so3.inverse(Some(&mut jacobian));
885
886 assert_eq!(0.0, so3_inv.x());
888 assert_eq!(0.0, so3_inv.y());
889 assert_eq!(0.0, so3_inv.z());
890 assert_eq!(1.0, so3_inv.w());
891
892 let expected_jac = -Matrix3::identity();
894 assert!((jacobian - expected_jac).norm() < TOLERANCE);
895 }
896
897 #[test]
898 fn test_so3_rplus() {
899 let so3a = SO3::identity();
901 let so3b = SO3Tangent::new(Vector3::zeros());
902 let so3c = so3a.right_plus(&so3b, None, None);
903 assert_eq!(0.0, so3c.x());
904 assert_eq!(0.0, so3c.y());
905 assert_eq!(0.0, so3c.z());
906 assert_eq!(1.0, so3c.w());
907
908 let so3a = SO3::random();
910 let so3c = so3a.right_plus(&so3b, None, None);
911 assert!((so3a.x() - so3c.x()).abs() < TOLERANCE);
912 assert!((so3a.y() - so3c.y()).abs() < TOLERANCE);
913 assert!((so3a.z() - so3c.z()).abs() < TOLERANCE);
914 assert!((so3a.w() - so3c.w()).abs() < TOLERANCE);
915 }
916
917 #[test]
918 fn test_so3_lplus() {
919 let so3a = SO3::identity();
921 let so3t = SO3Tangent::new(Vector3::zeros());
922 let so3c = so3a.left_plus(&so3t, None, None);
923 assert_eq!(0.0, so3c.x());
924 assert_eq!(0.0, so3c.y());
925 assert_eq!(0.0, so3c.z());
926 assert_eq!(1.0, so3c.w());
927
928 let so3a = SO3::random();
930 let so3c = so3a.left_plus(&so3t, None, None);
931 assert!((so3a.x() - so3c.x()).abs() < TOLERANCE);
932 assert!((so3a.y() - so3c.y()).abs() < TOLERANCE);
933 assert!((so3a.z() - so3c.z()).abs() < TOLERANCE);
934 assert!((so3a.w() - so3c.w()).abs() < TOLERANCE);
935 }
936
937 #[test]
938 fn test_so3_rminus() {
939 let so3a = SO3::identity();
941 let so3b = SO3::identity();
942 let so3c = so3a.right_minus(&so3b, None, None);
943 assert!(so3c.x().abs() < TOLERANCE);
944 assert!(so3c.y().abs() < TOLERANCE);
945 assert!(so3c.z().abs() < TOLERANCE);
946
947 let so3a = SO3::random();
949 let so3b = so3a.clone();
950 let so3c = so3a.right_minus(&so3b, None, None);
951 assert!(so3c.data.norm() < TOLERANCE);
952 }
953
954 #[test]
955 fn test_so3_minus() {
956 let so3a = SO3::random();
958 let so3b = SO3::random();
959 let so3c = so3a.minus(&so3b, None, None);
960 let so3d = so3a.right_minus(&so3b, None, None);
961 assert!((so3c.data - so3d.data).norm() < TOLERANCE);
962 }
963
964 #[test]
965 fn test_so3_exp_log() {
966 let so3t = SO3Tangent::new(Vector3::zeros());
968 let so3 = so3t.exp(None);
969 assert_eq!(0.0, so3.x());
970 assert_eq!(0.0, so3.y());
971 assert_eq!(0.0, so3.z());
972 assert_eq!(1.0, so3.w());
973
974 let so3t = SO3Tangent::new(Vector3::new(0.1, 0.2, 0.3));
976 let so3 = so3t.exp(None);
977 let so3n = SO3Tangent::new(Vector3::new(-0.1, -0.2, -0.3));
978 let so3_inv = so3n.exp(None);
979 assert!((so3_inv.x() + so3.x()).abs() < TOLERANCE);
980 assert!((so3_inv.y() + so3.y()).abs() < TOLERANCE);
981 assert!((so3_inv.z() + so3.z()).abs() < TOLERANCE);
982 assert!((so3_inv.w() - so3.w()).abs() < TOLERANCE);
983 }
984
985 #[test]
986 fn test_so3_log() {
987 let so3 = SO3::identity();
989 let so3_log = so3.log(None);
990 assert!(so3_log.x().abs() < TOLERANCE);
991 assert!(so3_log.y().abs() < TOLERANCE);
992 assert!(so3_log.z().abs() < TOLERANCE);
993
994 let so3 = SO3::random();
996 let so3_log = so3.log(None);
997 let so3_inv_log = so3.inverse(None).log(None);
998 assert!((so3_inv_log.x() + so3_log.x()).abs() < TOLERANCE);
999 assert!((so3_inv_log.y() + so3_log.y()).abs() < TOLERANCE);
1000 assert!((so3_inv_log.z() + so3_log.z()).abs() < TOLERANCE);
1001 }
1002
1003 #[test]
1004 fn test_so3_tangent_hat() {
1005 let so3_tan = SO3Tangent::new(Vector3::new(1.0, 2.0, 3.0));
1006 let so3_lie = so3_tan.hat();
1007
1008 assert!((so3_lie[(0, 0)] - 0.0).abs() < TOLERANCE);
1009 assert!((so3_lie[(0, 1)] + 3.0).abs() < TOLERANCE);
1010 assert!((so3_lie[(0, 2)] - 2.0).abs() < TOLERANCE);
1011 assert!((so3_lie[(1, 0)] - 3.0).abs() < TOLERANCE);
1012 assert!((so3_lie[(1, 1)] - 0.0).abs() < TOLERANCE);
1013 assert!((so3_lie[(1, 2)] + 1.0).abs() < TOLERANCE);
1014 assert!((so3_lie[(2, 0)] + 2.0).abs() < TOLERANCE);
1015 assert!((so3_lie[(2, 1)] - 1.0).abs() < TOLERANCE);
1016 assert!((so3_lie[(2, 2)] - 0.0).abs() < TOLERANCE);
1017 }
1018
1019 #[test]
1020 fn test_so3_act() {
1021 let so3 = SO3::identity();
1022 let transformed_point = so3.act(&Vector3::new(1.0, 1.0, 1.0), None, None);
1023 assert!((transformed_point.x - 1.0).abs() < TOLERANCE);
1024 assert!((transformed_point.y - 1.0).abs() < TOLERANCE);
1025 assert!((transformed_point.z - 1.0).abs() < TOLERANCE);
1026
1027 let so3 = SO3::from_euler_angles(PI, PI / 2.0, PI / 4.0);
1028 let transformed_point = so3.act(&Vector3::new(1.0, 1.0, 1.0), None, None);
1029 assert!((transformed_point.x - 0.0).abs() < TOLERANCE);
1030 assert!((transformed_point.y + f64::consts::SQRT_2).abs() < 1e-10);
1031 assert!((transformed_point.z + 1.0).abs() < TOLERANCE);
1032 }
1033
1034 #[test]
1035 fn test_so3_tangent_angular_velocity() {
1036 let so3tan = SO3Tangent::new(Vector3::new(1.0, 2.0, 3.0));
1037 let ang_vel = so3tan.ang();
1038 assert!((ang_vel - Vector3::new(1.0, 2.0, 3.0)).norm() < TOLERANCE);
1039 }
1040
1041 #[test]
1042 fn test_so3_compose() {
1043 let so3_1 = SO3::random();
1044 let so3_2 = SO3::random();
1045 let composed = so3_1.compose(&so3_2, None, None);
1046 assert!(composed.is_valid(TOLERANCE));
1047
1048 let identity = SO3::identity();
1050 let composed_with_identity = so3_1.compose(&identity, None, None);
1051 assert!((composed_with_identity.distance(&so3_1)).abs() < TOLERANCE);
1052 }
1053
1054 #[test]
1055 fn test_so3_exp_log_consistency() {
1056 let tangent = SO3Tangent::new(Vector3::new(0.1, 0.2, 0.3));
1057 let so3 = tangent.exp(None);
1058 let recovered_tangent = so3.log(None);
1059 assert!((tangent.data - recovered_tangent.data).norm() < TOLERANCE);
1060 }
1061
1062 #[test]
1063 fn test_so3_right_left_jacobian_relationship() {
1064 let tangent = SO3Tangent::new(Vector3::zeros());
1066 let ljac = tangent.left_jacobian();
1067 let rjac = tangent.right_jacobian();
1068 assert!((ljac - rjac).norm() < TOLERANCE);
1069 assert!((ljac - Matrix3::identity()).norm() < TOLERANCE);
1070
1071 let tangent = SO3Tangent::new(Vector3::new(0.1, 0.2, 0.3));
1073 let ljac = tangent.left_jacobian();
1074 let rjac = tangent.right_jacobian();
1075
1076 assert!((ljac - rjac.transpose()).norm() < TOLERANCE);
1079 assert!((rjac - ljac.transpose()).norm() < TOLERANCE);
1080 }
1081
1082 #[test]
1083 fn test_so3_manifold_properties() {
1084 assert_eq!(SO3::DIM, 3);
1085 assert_eq!(SO3::DOF, 3);
1086 assert_eq!(SO3::REP_SIZE, 4);
1087 }
1088
1089 #[test]
1090 fn test_so3_normalize() {
1091 let mut so3 = SO3::from_quaternion_coeffs(0.5, 0.5, 0.5, 0.5);
1092 so3.normalize();
1093 assert!(so3.is_valid(TOLERANCE));
1094 }
1095
1096 #[test]
1097 fn test_so3_tangent_norms() {
1098 let tangent = SO3Tangent::new(Vector3::new(3.0, 4.0, 0.0));
1099 let norm = tangent.data.norm();
1100 assert!((norm - 5.0).abs() < TOLERANCE);
1101
1102 let squared_norm = tangent.data.norm_squared();
1103 assert!((squared_norm - 25.0).abs() < TOLERANCE);
1104 }
1105
1106 #[test]
1107 fn test_so3_tangent_zero() {
1108 let zero = SO3Tangent::zero();
1109 assert!(zero.data.norm() < TOLERANCE);
1110
1111 let tangent = SO3Tangent::new(Vector3::zeros());
1112 assert!(tangent.is_zero(TOLERANCE));
1113 }
1114
1115 #[test]
1116 fn test_so3_tangent_normalize() {
1117 let mut tangent = SO3Tangent::new(Vector3::new(3.0, 4.0, 0.0));
1118 tangent.normalize();
1119 assert!((tangent.data.norm() - 1.0).abs() < TOLERANCE);
1120 }
1121
1122 #[test]
1123 fn test_so3_adjoint() {
1124 let so3 = SO3::random();
1125 let adj = so3.adjoint();
1126 assert_eq!(adj.nrows(), 3);
1127 assert_eq!(adj.ncols(), 3);
1128
1129 let det = adj.determinant();
1131 assert!((det - 1.0).abs() < TOLERANCE);
1132 }
1133
1134 #[test]
1135 fn test_so3_small_angle_approximations() {
1136 let small_tangent = SO3Tangent::new(Vector3::new(1e-8, 2e-8, 3e-8));
1137 let so3 = small_tangent.exp(None);
1138 let recovered = so3.log(None);
1139 assert!((small_tangent.data - recovered.data).norm() < TOLERANCE);
1140 }
1141
1142 #[test]
1143 fn test_so3_specific_rotations() {
1144 let so3_x = SO3::from_axis_angle(&Vector3::x(), PI / 2.0);
1146 let point_y = Vector3::y();
1147 let rotated = so3_x.act(&point_y, None, None);
1148 assert!((rotated - Vector3::z()).norm() < TOLERANCE);
1149
1150 let so3_z = SO3::from_axis_angle(&Vector3::z(), PI / 2.0);
1152 let point_x = Vector3::x();
1153 let rotated = so3_z.act(&point_x, None, None);
1154 assert!((rotated - Vector3::y()).norm() < TOLERANCE);
1155 }
1156
1157 #[test]
1158 fn test_so3_from_components() {
1159 let so3 = SO3::from_quaternion_coeffs(0.0, 0.0, 0.0, 1.0);
1160 assert_eq!(so3.x(), 0.0);
1161 assert_eq!(so3.y(), 0.0);
1162 assert_eq!(so3.z(), 0.0);
1163 assert_eq!(so3.w(), 1.0);
1164 }
1165
1166 #[test]
1167 fn test_so3_tangent_from_components() {
1168 let tangent = SO3Tangent::from_components(1.0, 2.0, 3.0);
1169 assert_eq!(tangent.x(), 1.0);
1170 assert_eq!(tangent.y(), 2.0);
1171 assert_eq!(tangent.z(), 3.0);
1172 }
1173
1174 #[test]
1175 fn test_so3_consistency_with_manif() {
1176 let so3_1 = SO3::random();
1178 let so3_2 = SO3::random();
1179
1180 let so3_3 = SO3::random();
1182 let left_assoc = so3_1
1183 .compose(&so3_2, None, None)
1184 .compose(&so3_3, None, None);
1185 let right_assoc = so3_1.compose(&so3_2.compose(&so3_3, None, None), None, None);
1186
1187 assert!(left_assoc.distance(&right_assoc) < 1e-10);
1188 }
1189
1190 #[test]
1191 fn test_so3_tangent_accessors() {
1192 let tangent = SO3Tangent::new(Vector3::new(1.0, 2.0, 3.0));
1193 assert_eq!(tangent.x(), 1.0);
1194 assert_eq!(tangent.y(), 2.0);
1195 assert_eq!(tangent.z(), 3.0);
1196
1197 let coeffs = tangent.coeffs();
1198 assert_eq!(coeffs, Vector3::new(1.0, 2.0, 3.0));
1199 }
1200
1201 #[test]
1202 fn test_so3_between() {
1203 let so3_1 = SO3::random();
1204 let so3_2 = SO3::random();
1205 let between = so3_1.between(&so3_2, None, None);
1206
1207 let result = so3_1.compose(&between, None, None);
1209 assert!(result.distance(&so3_2) < TOLERANCE);
1210 }
1211
1212 #[test]
1213 fn test_so3_distance() {
1214 let so3_1 = SO3::random();
1215 let so3_2 = SO3::random();
1216 let distance = so3_1.distance(&so3_2);
1217 assert!(distance >= 0.0);
1218 assert!(so3_1.distance(&so3_1) < TOLERANCE);
1219 }
1220
1221 #[test]
1224 fn test_so3_vee() {
1225 let so3 = SO3::random();
1226 let tangent_log = so3.log(None);
1227 let tangent_vee = so3.vee();
1228
1229 assert!((tangent_log.data - tangent_vee.data).norm() < 1e-10);
1230 }
1231
1232 #[test]
1233 fn test_so3_is_approx() {
1234 let so3_1 = SO3::random();
1235 let so3_2 = so3_1.clone();
1236
1237 assert!(so3_1.is_approx(&so3_1, 1e-10));
1238 assert!(so3_1.is_approx(&so3_2, 1e-10));
1239
1240 let small_tangent = SO3Tangent::new(Vector3::new(1e-12, 1e-12, 1e-12));
1242 let so3_perturbed = so3_1.right_plus(&small_tangent, None, None);
1243 assert!(so3_1.is_approx(&so3_perturbed, 1e-10));
1244 }
1245
1246 #[test]
1247 fn test_so3_tangent_small_adj() {
1248 let axis_angle = Vector3::new(0.1, 0.2, 0.3);
1249 let tangent = SO3Tangent::new(axis_angle);
1250 let small_adj = tangent.small_adj();
1251 let hat_matrix = tangent.hat();
1252
1253 assert!((small_adj - hat_matrix).norm() < 1e-10);
1255 }
1256
1257 #[test]
1258 fn test_so3_tangent_lie_bracket() {
1259 let tangent_a = SO3Tangent::new(Vector3::new(0.1, 0.0, 0.0));
1260 let tangent_b = SO3Tangent::new(Vector3::new(0.0, 0.2, 0.0));
1261
1262 let bracket_ab = tangent_a.lie_bracket(&tangent_b);
1263 let bracket_ba = tangent_b.lie_bracket(&tangent_a);
1264
1265 assert!((bracket_ab.data + bracket_ba.data).norm() < 1e-10);
1267
1268 let bracket_aa = tangent_a.lie_bracket(&tangent_a);
1270 assert!(bracket_aa.is_zero(1e-10));
1271
1272 let bracket_hat = bracket_ab.hat();
1274 let expected = tangent_a.hat() * tangent_b.hat() - tangent_b.hat() * tangent_a.hat();
1275 assert!((bracket_hat - expected).norm() < 1e-10);
1276 }
1277
1278 #[test]
1279 fn test_so3_tangent_is_approx() {
1280 let tangent_1 = SO3Tangent::new(Vector3::new(0.1, 0.2, 0.3));
1281 let tangent_2 = SO3Tangent::new(Vector3::new(0.1 + 1e-12, 0.2, 0.3));
1282 let tangent_3 = SO3Tangent::new(Vector3::new(0.5, 0.6, 0.7));
1283
1284 assert!(tangent_1.is_approx(&tangent_1, 1e-10));
1285 assert!(tangent_1.is_approx(&tangent_2, 1e-10));
1286 assert!(!tangent_1.is_approx(&tangent_3, 1e-10));
1287 }
1288
1289 #[test]
1290 fn test_so3_generators() {
1291 let tangent = SO3Tangent::new(Vector3::new(1.0, 1.0, 1.0));
1292
1293 for i in 0..3 {
1295 let generator = tangent.generator(i);
1296
1297 assert!((generator + generator.transpose()).norm() < 1e-10);
1299
1300 assert!(generator.trace().abs() < 1e-10);
1302 }
1303
1304 let e1 = tangent.generator(0);
1306 let e2 = tangent.generator(1);
1307 let e3 = tangent.generator(2);
1308
1309 let expected_e1 = Matrix3::new(0.0, 0.0, 0.0, 0.0, 0.0, -1.0, 0.0, 1.0, 0.0);
1311 let expected_e2 = Matrix3::new(0.0, 0.0, 1.0, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0);
1312 let expected_e3 = Matrix3::new(0.0, -1.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0);
1313
1314 assert!((e1 - expected_e1).norm() < 1e-10);
1315 assert!((e2 - expected_e2).norm() < 1e-10);
1316 assert!((e3 - expected_e3).norm() < 1e-10);
1317 }
1318
1319 #[test]
1320 #[should_panic]
1321 fn test_so3_generator_invalid_index() {
1322 let tangent = SO3Tangent::new(Vector3::new(1.0, 1.0, 1.0));
1323 let _generator = tangent.generator(3); }
1325
1326 #[test]
1327 fn test_so3_jacobi_identity() {
1328 let x = SO3Tangent::new(Vector3::new(0.1, 0.0, 0.0));
1330 let y = SO3Tangent::new(Vector3::new(0.0, 0.2, 0.0));
1331 let z = SO3Tangent::new(Vector3::new(0.0, 0.0, 0.3));
1332
1333 let term1 = x.lie_bracket(&y.lie_bracket(&z));
1334 let term2 = y.lie_bracket(&z.lie_bracket(&x));
1335 let term3 = z.lie_bracket(&x.lie_bracket(&y));
1336
1337 let jacobi_sum = SO3Tangent::new(term1.data + term2.data + term3.data);
1338 assert!(jacobi_sum.is_zero(1e-10));
1339 }
1340
1341 #[test]
1344 fn test_so3_right_jacobian_numerical() {
1345 let xi = Vector3::new(0.1, 0.2, 0.3);
1350 let tangent = SO3Tangent::new(xi);
1351 let jr_analytical = tangent.right_jacobian();
1352
1353 let delta_size = 1e-6;
1355 let test_deltas = vec![
1356 Vector3::new(delta_size, 0.0, 0.0),
1357 Vector3::new(0.0, delta_size, 0.0),
1358 Vector3::new(0.0, 0.0, delta_size),
1359 ];
1360
1361 for delta in test_deltas {
1362 let analytical_result = jr_analytical * delta;
1364
1365 let base = SO3Tangent::new(xi).exp(None);
1367 let perturbed = SO3Tangent::new(xi + delta).exp(None);
1368 let base_inv = base.inverse(None);
1369 let diff_element = base_inv.compose(&perturbed, None, None);
1370 let diff_log = diff_element.log(None);
1371 let numerical_result = Vector3::new(diff_log.x(), diff_log.y(), diff_log.z());
1372
1373 let error = (analytical_result - numerical_result).norm();
1374 assert!(
1375 error < 1e-7,
1376 "Right Jacobian verification failed: error = {}, delta = {:?}",
1377 error,
1378 delta
1379 );
1380 }
1381 }
1382
1383 #[test]
1384 fn test_so3_left_jacobian_numerical() {
1385 let xi = Vector3::new(0.1, 0.2, 0.3);
1390 let tangent = SO3Tangent::new(xi);
1391 let jl_analytical = tangent.left_jacobian();
1392
1393 let delta_size = 1e-6;
1395 let test_deltas = vec![
1396 Vector3::new(delta_size, 0.0, 0.0),
1397 Vector3::new(0.0, delta_size, 0.0),
1398 Vector3::new(0.0, 0.0, delta_size),
1399 ];
1400
1401 for delta in test_deltas {
1402 let analytical_result = jl_analytical * delta;
1404
1405 let base = SO3Tangent::new(xi).exp(None);
1407 let perturbed = SO3Tangent::new(xi + delta).exp(None);
1408 let base_inv = base.inverse(None);
1409 let diff_element = perturbed.compose(&base_inv, None, None);
1410 let diff_log = diff_element.log(None);
1411 let numerical_result = Vector3::new(diff_log.x(), diff_log.y(), diff_log.z());
1412
1413 let error = (analytical_result - numerical_result).norm();
1414 assert!(
1415 error < 1e-7,
1416 "Left Jacobian verification failed: error = {}, delta = {:?}",
1417 error,
1418 delta
1419 );
1420 }
1421 }
1422
1423 #[test]
1424 fn test_so3_accumulated_error_small_rotations() {
1425 let small_rotation = SO3::from_scaled_axis(Vector3::new(0.001, 0.002, -0.001));
1427 let mut accumulated = SO3::identity();
1428
1429 for _ in 0..1000 {
1430 accumulated = accumulated.compose(&small_rotation, None, None);
1431 }
1432
1433 let expected_tangent = SO3Tangent::new(Vector3::new(1.0, 2.0, -1.0));
1435 let expected = expected_tangent.exp(None);
1436
1437 assert!(accumulated.is_approx(&expected, 1e-6));
1439 }
1440
1441 #[test]
1442 fn test_so3_inverse_composition_chain() {
1443 let rotation = SO3::from_euler_angles(0.1, 0.2, 0.3);
1445 let inverse = rotation.inverse(None);
1446 let mut accumulated = SO3::identity();
1447
1448 for _ in 0..500 {
1449 accumulated = accumulated.compose(&rotation, None, None);
1450 accumulated = accumulated.compose(&inverse, None, None);
1451 }
1452
1453 assert!(accumulated.is_approx(&SO3::identity(), 1e-9));
1455 }
1456
1457 #[test]
1460 fn test_so3_antipodal_quaternions() {
1461 let q = UnitQuaternion::from_euler_angles(0.5, 0.3, 0.2);
1463 let so3_pos = SO3::new(q);
1464 let so3_neg = SO3::new(UnitQuaternion::from_quaternion(-q.quaternion()));
1465
1466 let log_pos = so3_pos.log(None);
1468 let log_neg = so3_neg.log(None);
1469
1470 let diff_norm = (log_pos.data - log_neg.data).norm();
1472 let sum_norm = (log_pos.data + log_neg.data).norm();
1473 assert!(diff_norm < 1e-10 || sum_norm < 1e-10);
1474 }
1475
1476 #[test]
1477 fn test_so3_near_pi_rotation() {
1478 let axis = Vector3::new(1.0, 0.0, 0.0).normalize();
1480 let angle = std::f64::consts::PI - 1e-8;
1481 let so3 = SO3::from_axis_angle(&axis, angle);
1482
1483 let tangent = so3.log(None);
1484 let recovered = tangent.exp(None);
1485
1486 assert!(so3.is_approx(&recovered, 1e-6));
1487 }
1488
1489 #[test]
1490 fn test_so3_right_jacobian_inverse_identity() {
1491 let tangent = SO3Tangent::new(Vector3::new(0.001, 0.002, 0.003));
1492 let jr = tangent.right_jacobian();
1493 let jr_inv = tangent.right_jacobian_inv();
1494 let product = jr * jr_inv;
1495 let identity = Matrix3::identity();
1496
1497 assert!(
1498 (product - identity).norm() < 1e-10,
1499 "Jr * Jr_inv should be identity, got error: {}",
1500 (product - identity).norm()
1501 );
1502 }
1503
1504 #[test]
1505 fn test_so3_left_jacobian_inverse_identity() {
1506 let tangent = SO3Tangent::new(Vector3::new(0.001, 0.002, 0.003));
1507 let jl = tangent.left_jacobian();
1508 let jl_inv = tangent.left_jacobian_inv();
1509 let product = jl * jl_inv;
1510 let identity = Matrix3::identity();
1511
1512 assert!(
1513 (product - identity).norm() < 1e-10,
1514 "Jl * Jl_inv should be identity, got error: {}",
1515 (product - identity).norm()
1516 );
1517 }
1518
1519 #[test]
1520 fn test_so3_from_quaternion_wxyz() {
1521 let so3_wxyz = SO3::from_quaternion_wxyz(1.0, 0.0, 0.0, 0.0);
1523 let so3_xyzw = SO3::from_quaternion_coeffs(0.0, 0.0, 0.0, 1.0);
1524 assert!(so3_wxyz.is_approx(&so3_xyzw, 1e-12));
1525
1526 let so3_wxyz = SO3::from_quaternion_wxyz(0.4, 0.1, 0.2, 0.3);
1528 let so3_xyzw = SO3::from_quaternion_coeffs(0.1, 0.2, 0.3, 0.4);
1529 assert!(so3_wxyz.is_approx(&so3_xyzw, 1e-12));
1530 }
1531
1532 #[test]
1533 fn test_so3_tangent_is_not_dynamic() {
1534 assert!(!SO3Tangent::is_dynamic());
1535 assert_eq!(SO3Tangent::DIM, 3);
1536 }
1537
1538 #[test]
1539 fn test_so3_small_angle_threshold_exp_log() {
1540 let near_threshold_angles = [1e-6, 1e-5, 1e-4, 1e-3];
1543
1544 for &angle in &near_threshold_angles {
1545 let tangent = SO3Tangent::new(Vector3::new(angle, 0.0, 0.0));
1546 let so3 = tangent.exp(None);
1547 let recovered = so3.log(None);
1548 assert!(
1549 (tangent.data - recovered.data).norm() < 1e-10,
1550 "SO3 exp-log round-trip failed for angle = {angle}"
1551 );
1552 }
1553 }
1554
1555 #[test]
1556 fn test_so3_display() {
1557 let r = SO3::identity();
1558 let s = format!("{r}");
1559 assert!(!s.is_empty(), "Display should produce output");
1560 }
1561
1562 #[test]
1563 fn test_so3_accessors_xyzw() {
1564 let r = SO3::from_axis_angle(&Vector3::z(), std::f64::consts::FRAC_PI_2);
1565 let _ = r.x();
1566 let _ = r.y();
1567 let _ = r.z();
1568 let _ = r.w();
1569 let q = r.to_quaternion();
1570 let q2 = r.quat();
1571 assert!((q.w - q2.w).abs() < 1e-10);
1572 }
1573
1574 #[test]
1575 fn test_so3_set_quaternion_and_coeffs() {
1576 let r_orig = SO3::from_euler_angles(0.1, 0.2, 0.3);
1578 let orig_coeffs = r_orig.coeffs();
1579 assert_eq!(orig_coeffs.len(), 4);
1580
1581 let mut r2 = SO3::identity();
1583 r2.set_quaternion(&orig_coeffs);
1584 let c2 = r2.coeffs();
1585 for i in 0..4 {
1586 assert!(
1587 (c2[i] - orig_coeffs[i]).abs() < 1e-9,
1588 "coeffs[{i}] mismatch"
1589 );
1590 }
1591 }
1592
1593 #[test]
1594 fn test_so3_from_scaled_axis_constructor() {
1595 let v = Vector3::new(0.1, 0.2, 0.3);
1596 let r = SO3::from_scaled_axis(v);
1597 assert!(r.is_valid(1e-6));
1598 }
1599
1600 #[test]
1601 fn test_so3_from_axis_angle_constructor() {
1602 let axis = Vector3::x();
1603 let r = SO3::from_axis_angle(&axis, std::f64::consts::FRAC_PI_4);
1604 assert!(r.is_valid(1e-6));
1605 }
1606
1607 #[test]
1608 fn test_so3_tangent_axis_angle_accessors() {
1609 let t = SO3Tangent::new(Vector3::new(0.1, 0.2, 0.3));
1610
1611 let av = t.axis_angle();
1613 assert!((av.norm() - t.angle()).abs() < 1e-10);
1614
1615 let ax = t.axis();
1617 assert!((ax.norm() - 1.0).abs() < 1e-9);
1618
1619 let c = t.coeffs();
1624 assert_eq!(c.len(), 3);
1625
1626 let ang = t.ang();
1628 assert!((ang.norm() - t.angle()).abs() < 1e-10);
1629 }
1630
1631 #[test]
1632 fn test_so3_right_jacobian_inv() {
1633 use crate::Tangent;
1634 let t = SO3Tangent::new(Vector3::new(0.1, 0.2, 0.3));
1635 let jr_inv = t.right_jacobian_inv();
1636 assert_eq!(jr_inv.nrows(), 3);
1637 assert_eq!(jr_inv.ncols(), 3);
1638
1639 let jr = t.right_jacobian();
1640 let product = jr_inv * jr;
1641 for i in 0..3 {
1642 for j in 0..3 {
1643 let expected = if i == j { 1.0 } else { 0.0 };
1644 assert!(
1645 (product[(i, j)] - expected).abs() < 1e-4,
1646 "product[{i},{j}] = {} != {expected}",
1647 product[(i, j)]
1648 );
1649 }
1650 }
1651 }
1652
1653 #[test]
1654 fn test_so3_left_jacobian_inv() {
1655 use crate::Tangent;
1656 let t = SO3Tangent::new(Vector3::new(0.1, 0.2, 0.3));
1657 let jl_inv = t.left_jacobian_inv();
1658 assert_eq!(jl_inv.nrows(), 3);
1659
1660 let jl = t.left_jacobian();
1661 let product = jl_inv * jl;
1662 for i in 0..3 {
1663 for j in 0..3 {
1664 let expected = if i == j { 1.0 } else { 0.0 };
1665 assert!(
1666 (product[(i, j)] - expected).abs() < 1e-4,
1667 "product[{i},{j}] = {} != {expected}",
1668 product[(i, j)]
1669 );
1670 }
1671 }
1672 }
1673
1674 #[test]
1675 fn test_so3_tangent_normalized() {
1676 use crate::Tangent;
1677 let t = SO3Tangent::new(Vector3::new(0.0, 0.0, 3.0));
1678 let tn = t.normalized();
1679 assert!((tn.angle() - 1.0).abs() < 1e-9);
1680 }
1681
1682 #[test]
1683 fn test_so3_tangent_is_zero() {
1684 use crate::Tangent;
1685 let zero = SO3Tangent::new(Vector3::zeros());
1686 assert!(zero.is_zero(1e-9));
1687 let nonzero = SO3Tangent::new(Vector3::new(0.1, 0.0, 0.0));
1688 assert!(!nonzero.is_zero(1e-9));
1689 }
1690
1691 #[test]
1692 fn test_so3_inverse_with_jacobian() {
1693 use crate::LieGroup;
1694 let r = SO3::from_euler_angles(0.1, 0.2, 0.3);
1695 let mut jac = Matrix3::zeros();
1696 let inv = r.inverse(Some(&mut jac));
1697 assert!(inv.is_valid(1e-6));
1698 assert!(jac[(0, 0)].is_finite());
1699 }
1700
1701 #[test]
1702 fn test_so3_compose_with_jacobians() {
1703 use crate::LieGroup;
1704 let r1 = SO3::from_euler_angles(0.1, 0.2, 0.3);
1705 let r2 = SO3::from_euler_angles(0.4, 0.1, 0.2);
1706 let mut j_self = Matrix3::zeros();
1707 let mut j_other = Matrix3::zeros();
1708 let result = r1.compose(&r2, Some(&mut j_self), Some(&mut j_other));
1709 assert!(result.is_valid(1e-6));
1710 assert!(j_self[(0, 0)].is_finite());
1711 assert!(j_other[(0, 0)].is_finite());
1712 }
1713
1714 #[test]
1715 fn test_so3_zero_jacobian() {
1716 use crate::LieGroup;
1717 let zj = SO3::zero_jacobian();
1718 for i in 0..3 {
1719 for j in 0..3 {
1720 assert!(zj[(i, j)].abs() < 1e-10);
1721 }
1722 }
1723 }
1724
1725 #[test]
1726 fn test_so3_act_with_jacobians() {
1727 use crate::LieGroup;
1728 let r = SO3::from_euler_angles(0.1, 0.2, 0.3);
1729 let v = Vector3::new(1.0, 0.0, 0.0);
1730 let mut j_self = Matrix3::zeros();
1731 let mut j_vec = Matrix3::zeros();
1732 let result = r.act(&v, Some(&mut j_self), Some(&mut j_vec));
1733 assert!(result.norm() > 0.0);
1734 assert!(j_self[(0, 0)].is_finite());
1735 assert!(j_vec[(0, 0)].is_finite());
1736 }
1737
1738 #[test]
1739 fn test_from_dvector_wxyz() {
1740 let dv = ::nalgebra::dvector![144., 96., 72., 83.] / 205.; let so3 = SO3::from(dv.clone());
1742 assert_eq!(144. / 205., so3.w());
1743 assert_eq!(96. / 205., so3.x());
1744 assert_eq!(72. / 205., so3.y());
1745 assert_eq!(83. / 205., so3.z());
1746 }
1747
1748 #[test]
1749 fn test_from_s03_wxyz() {
1750 let so3 = SO3::from_quaternion_wxyz(144. / 205., 96. / 205., 72. / 205., 83. / 205.); let dv = DVector::<f64>::from(so3.clone());
1752 assert_eq!(144. / 205., dv[0]);
1753 assert_eq!(96. / 205., dv[1]);
1754 assert_eq!(72. / 205., dv[2]);
1755 assert_eq!(83. / 205., dv[3]);
1756 }
1757
1758 #[test]
1759 fn test_bijective_from_dvector() {
1760 let dv_expected = ::nalgebra::dvector![144., 96., 72., 83.] / 205.; let so3_expected = SO3::from(dv_expected.clone());
1762 let dv_actual = DVector::<f64>::from(so3_expected.clone());
1763 let so3_actual = SO3::from(dv_actual.clone());
1764 assert_eq!(dv_expected, dv_actual);
1765 assert!(so3_expected == so3_actual);
1766 }
1767}