1use crate::batch::{MAX_CANDIDATES, Point2f};
4use crate::pose::{CameraIntrinsics, Pose, projection_jacobian, symmetrize_jtj6};
5use nalgebra::{Matrix2, Matrix6, UnitQuaternion, Vector3, Vector6};
6use std::sync::Arc;
7
8#[derive(Debug, Clone)]
12pub enum BoardConfigError {
13 DictionaryTooSmall {
15 required: usize,
17 available: usize,
19 },
20}
21
22impl std::fmt::Display for BoardConfigError {
23 fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
24 match self {
25 Self::DictionaryTooSmall {
26 required,
27 available,
28 } => write!(
29 f,
30 "board requires {required} tag IDs but the dictionary only has {available}"
31 ),
32 }
33 }
34}
35
36impl std::error::Error for BoardConfigError {}
37
38#[derive(Clone, Debug)]
46pub struct LoRansacConfig {
47 pub k_min: u32,
51 pub k_max: u32,
54 pub confidence: f64,
56 pub tau_outer_sq: f64,
63 pub tau_inner_sq: f64,
69 pub tau_aw_lm_sq: f64,
77 pub lo_max_iterations: u32,
82 pub min_inliers: usize,
84}
85
86impl Default for LoRansacConfig {
87 fn default() -> Self {
88 Self {
89 k_min: 15,
90 k_max: 50,
91 confidence: 0.9999,
92 tau_outer_sq: 100.0, tau_inner_sq: 1.0, tau_aw_lm_sq: 100.0, lo_max_iterations: 5,
96 min_inliers: 4,
97 }
98 }
99}
100
101#[derive(Clone, Debug)]
108pub struct AprilGridTopology {
109 pub rows: usize,
111 pub cols: usize,
113 pub marker_length: f64,
115 pub spacing: f64,
117 pub obj_points: Vec<Option<[[f64; 3]; 4]>>,
119}
120
121impl AprilGridTopology {
122 #[must_use]
130 pub fn from_obj_points(
131 rows: usize,
132 cols: usize,
133 marker_length: f64,
134 obj_points: Vec<Option<[[f64; 3]; 4]>>,
135 ) -> Self {
136 Self {
137 rows,
138 cols,
139 marker_length,
140 spacing: 0.0,
141 obj_points,
142 }
143 }
144
145 pub fn new(
157 rows: usize,
158 cols: usize,
159 spacing: f64,
160 marker_length: f64,
161 max_tag_id: usize,
162 ) -> Result<Self, BoardConfigError> {
163 let num_markers = rows * cols;
164 if num_markers > max_tag_id {
165 return Err(BoardConfigError::DictionaryTooSmall {
166 required: num_markers,
167 available: max_tag_id,
168 });
169 }
170
171 let mut obj_points = vec![None; num_markers];
172 let step = marker_length + spacing;
173 let board_width = cols as f64 * marker_length + (cols - 1) as f64 * spacing;
174 let board_height = rows as f64 * marker_length + (rows - 1) as f64 * spacing;
175 let offset_x = -board_width / 2.0;
176 let offset_y = -board_height / 2.0;
177
178 for r in 0..rows {
179 for c in 0..cols {
180 let x = offset_x + c as f64 * step;
181 let y = offset_y + r as f64 * step;
182 let idx = r * cols + c;
183 obj_points[idx] = Some([
184 [x, y, 0.0],
185 [x + marker_length, y, 0.0],
186 [x + marker_length, y + marker_length, 0.0],
187 [x, y + marker_length, 0.0],
188 ]);
189 }
190 }
191
192 Ok(Self {
193 rows,
194 cols,
195 marker_length,
196 spacing,
197 obj_points,
198 })
199 }
200}
201
202#[derive(Clone, Debug)]
218pub struct CharucoTopology {
219 pub rows: usize,
221 pub cols: usize,
223 pub marker_length: f64,
225 pub square_length: f64,
227 pub obj_points: Vec<Option<[[f64; 3]; 4]>>,
229 pub saddle_points: Vec<[f64; 3]>,
233 pub tag_cell_corners: Vec<[Option<usize>; 4]>,
241}
242
243impl CharucoTopology {
244 pub fn new(
256 rows: usize,
257 cols: usize,
258 square_length: f64,
259 marker_length: f64,
260 max_tag_id: usize,
261 ) -> Result<Self, BoardConfigError> {
262 let num_markers = (rows * cols).div_ceil(2);
263 if num_markers > max_tag_id {
264 return Err(BoardConfigError::DictionaryTooSmall {
265 required: num_markers,
266 available: max_tag_id,
267 });
268 }
269
270 let total_width = cols as f64 * square_length;
271 let total_height = rows as f64 * square_length;
272 let offset_x = -total_width / 2.0;
273 let offset_y = -total_height / 2.0;
274 let marker_padding = (square_length - marker_length) / 2.0;
275
276 let mut obj_points = vec![None; num_markers];
277 let mut marker_idx = 0;
278 for r in 0..rows {
279 for c in 0..cols {
280 if (r + c) % 2 == 0 {
281 let x = offset_x + c as f64 * square_length + marker_padding;
282 let y = offset_y + r as f64 * square_length + marker_padding;
283 if marker_idx < obj_points.len() {
284 obj_points[marker_idx] = Some([
285 [x, y, 0.0],
286 [x + marker_length, y, 0.0],
287 [x + marker_length, y + marker_length, 0.0],
288 [x, y + marker_length, 0.0],
289 ]);
290 marker_idx += 1;
291 }
292 }
293 }
294 }
295
296 let saddle_cols = cols.saturating_sub(1);
298 let num_saddles = rows.saturating_sub(1) * saddle_cols;
299 let mut saddle_points = Vec::with_capacity(num_saddles);
300 for sr in 0..rows.saturating_sub(1) {
301 for sc in 0..saddle_cols {
302 let x = offset_x + (sc + 1) as f64 * square_length;
303 let y = offset_y + (sr + 1) as f64 * square_length;
304 saddle_points.push([x, y, 0.0]);
305 }
306 }
307
308 let mut tag_cell_corners = vec![[None; 4]; num_markers];
312 let saddle_id = |sr: isize, sc: isize| -> Option<usize> {
313 let saddle_rows_max: isize = rows.saturating_sub(1).cast_signed();
314 let saddle_cols_max: isize = cols.saturating_sub(1).cast_signed();
315 if sr < 0 || sc < 0 || sr >= saddle_rows_max || sc >= saddle_cols_max {
316 None
317 } else {
318 Some(sr.cast_unsigned() * saddle_cols + sc.cast_unsigned())
319 }
320 };
321 let mut midx = 0usize;
322 for r in 0..rows {
323 for c in 0..cols {
324 if (r + c) % 2 == 0 {
325 let ri = r.cast_signed();
326 let ci = c.cast_signed();
327 tag_cell_corners[midx] = [
328 saddle_id(ri - 1, ci - 1), saddle_id(ri - 1, ci), saddle_id(ri, ci), saddle_id(ri, ci - 1), ];
333 midx += 1;
334 }
335 }
336 }
337
338 Ok(Self {
339 rows,
340 cols,
341 marker_length,
342 square_length,
343 obj_points,
344 saddle_points,
345 tag_cell_corners,
346 })
347 }
348}
349
350#[derive(Clone, Debug)]
354pub struct BoardPose {
355 pub pose: Pose,
357 pub covariance: Matrix6<f64>,
360}
361
362pub struct PointCorrespondences<'a> {
380 pub image_points: &'a [Point2f],
382 pub object_points: &'a [[f64; 3]],
384 pub information_matrices: &'a [Matrix2<f64>],
388 pub group_size: usize,
391 pub seed_poses: &'a [Option<Pose>],
395}
396
397impl PointCorrespondences<'_> {
398 #[inline]
400 #[must_use]
401 pub fn num_groups(&self) -> usize {
402 self.image_points.len() / self.group_size
403 }
404}
405
406#[derive(Default)]
417pub struct RobustPoseSolver {
418 pub lo_ransac: LoRansacConfig,
420}
421
422impl RobustPoseSolver {
423 #[must_use]
425 pub fn new() -> Self {
426 Self::default()
427 }
428
429 #[must_use]
431 pub fn with_lo_ransac_config(mut self, cfg: LoRansacConfig) -> Self {
432 self.lo_ransac = cfg;
433 self
434 }
435
436 #[must_use]
443 pub fn estimate(
444 &self,
445 corr: &PointCorrespondences<'_>,
446 intrinsics: &CameraIntrinsics,
447 ) -> Option<BoardPose> {
448 if corr.num_groups() < 4 {
449 return None;
450 }
451
452 let (best_pose, _tight_mask) = self.lo_ransac_loop(corr, intrinsics)?;
454
455 let (aw_lm_mask, _) =
459 self.evaluate_inliers(&best_pose, corr, intrinsics, self.lo_ransac.tau_aw_lm_sq);
460
461 let (refined_pose, covariance) =
463 self.refine_aw_lm(&best_pose, corr, intrinsics, &aw_lm_mask);
464
465 Some(BoardPose {
466 pose: refined_pose,
467 covariance,
468 })
469 }
470
471 #[allow(clippy::too_many_lines, clippy::cast_sign_loss)]
482 fn lo_ransac_loop(
483 &self,
484 corr: &PointCorrespondences<'_>,
485 intrinsics: &CameraIntrinsics,
486 ) -> Option<(Pose, [u64; 16])> {
487 let cfg = &self.lo_ransac;
488 let num_groups = corr.num_groups();
489
490 let mut global_best_tight_count = 0usize;
491 let mut global_best_seed: Option<Pose> = None;
492 let mut dynamic_k = cfg.k_max;
493
494 let mut rng_seed = 0x1337u32;
496
497 for iter in 0..cfg.k_max {
498 let mut sample = [0usize; 4];
500 let mut found = 0usize;
501 let mut attempts = 0u32;
502 while found < 4 && attempts < 1000 {
503 attempts += 1;
504 rng_seed ^= rng_seed << 13;
505 rng_seed ^= rng_seed >> 17;
506 rng_seed ^= rng_seed << 5;
507 let s = (rng_seed as usize) % num_groups;
508 if !sample[..found].contains(&s) {
509 sample[found] = s;
510 found += 1;
511 }
512 }
513 if found < 4 {
514 continue;
515 }
516
517 let mut best_outer_count = 0usize;
519 let mut best_outer_mask = [0u64; 16];
520 let mut best_outer_pose: Option<Pose> = None;
521
522 for &s_val in &sample {
523 let Some(pose_init) = corr.seed_poses[s_val] else {
524 continue;
525 };
526
527 let (outer_mask, outer_count) =
528 self.evaluate_inliers(&pose_init, corr, intrinsics, cfg.tau_outer_sq);
529
530 if outer_count >= cfg.min_inliers && outer_count > best_outer_count {
531 best_outer_count = outer_count;
532 best_outer_mask = outer_mask;
533 best_outer_pose = Some(pose_init);
534 }
535 }
536
537 let Some(seed_pose) = best_outer_pose else {
538 continue;
539 };
540
541 let (_gn_pose, _tight_mask, tight_count) =
546 self.lo_inner(seed_pose, &best_outer_mask, corr, intrinsics);
547
548 if tight_count > global_best_tight_count {
549 global_best_tight_count = tight_count;
550 global_best_seed = Some(seed_pose);
551
552 let inlier_ratio = tight_count as f64 / num_groups as f64;
553 if inlier_ratio >= 0.99 {
554 dynamic_k = cfg.k_min;
555 } else {
556 let p_fail = 1.0 - cfg.confidence;
557 let p_good_sample = 1.0 - inlier_ratio.powi(4);
558 let k_compute = p_fail.ln() / p_good_sample.ln();
559 dynamic_k = (k_compute.max(0.0).ceil() as u32).clamp(cfg.k_min, cfg.k_max);
560 }
561 }
562
563 if iter >= cfg.k_min && iter >= dynamic_k {
565 break;
566 }
567 }
568
569 let final_seed = global_best_seed?;
570 Some((final_seed, [0u64; 16]))
571 }
572
573 fn lo_inner(
579 &self,
580 seed_pose: Pose,
581 outer_mask: &[u64; 16],
582 corr: &PointCorrespondences<'_>,
583 intrinsics: &CameraIntrinsics,
584 ) -> (Pose, [u64; 16], usize) {
585 let cfg = &self.lo_ransac;
586
587 let (init_inner_mask, init_inner_count) =
588 self.evaluate_inliers(&seed_pose, corr, intrinsics, cfg.tau_inner_sq);
589
590 let mut lo_pose = seed_pose;
591 let mut lo_gn_mask = *outer_mask;
593 let mut prev_inner_count = init_inner_count;
594
595 let mut best_pose = seed_pose;
596 let mut best_mask = init_inner_mask;
597 let mut best_count = init_inner_count;
598
599 for _lo_iter in 0..cfg.lo_max_iterations {
600 let new_pose = self.gn_step(&lo_pose, corr, intrinsics, &lo_gn_mask);
601
602 let (new_inner_mask, new_inner_count) =
603 self.evaluate_inliers(&new_pose, corr, intrinsics, cfg.tau_inner_sq);
604
605 if new_inner_count <= prev_inner_count {
607 break;
608 }
609
610 prev_inner_count = new_inner_count;
611 lo_pose = new_pose;
612 lo_gn_mask = new_inner_mask;
614 best_pose = new_pose;
615 best_mask = new_inner_mask;
616 best_count = new_inner_count;
617 }
618
619 (best_pose, best_mask, best_count)
620 }
621
622 #[allow(clippy::unused_self)]
638 fn evaluate_inliers(
639 &self,
640 pose: &Pose,
641 corr: &PointCorrespondences<'_>,
642 intrinsics: &CameraIntrinsics,
643 tau_sq: f64,
644 ) -> ([u64; 16], usize) {
645 let mut mask = [0u64; 16];
646 let mut count = 0usize;
647 let num_groups = corr.num_groups();
648 let gs = corr.group_size;
649
650 for g in 0..num_groups {
651 let start = g * gs;
652 let threshold = gs as f64 * tau_sq;
653
654 let mut sum_sq = 0.0f64;
655 let mut valid_group = true;
656
657 for k in start..(start + gs) {
658 let obj = corr.object_points[k];
659 let p_world = Vector3::new(obj[0], obj[1], obj[2]);
660 let p_cam = pose.rotation * p_world + pose.translation;
661 if p_cam.z < 1e-4 {
662 valid_group = false;
663 break;
664 }
665 let z_inv = 1.0 / p_cam.z;
666 let px = intrinsics.fx * p_cam.x * z_inv + intrinsics.cx;
667 let py = intrinsics.fy * p_cam.y * z_inv + intrinsics.cy;
668 let dx = px - f64::from(corr.image_points[k].x);
669 let dy = py - f64::from(corr.image_points[k].y);
670 sum_sq += dx * dx + dy * dy;
671 }
672
673 if valid_group && sum_sq < threshold {
674 count += 1;
675 mask[g / 64] |= 1 << (g % 64);
676 }
677 }
678
679 (mask, count)
680 }
681
682 #[allow(clippy::unused_self)]
689 fn gn_step(
690 &self,
691 pose: &Pose,
692 corr: &PointCorrespondences<'_>,
693 intrinsics: &CameraIntrinsics,
694 inlier_mask: &[u64; 16],
695 ) -> Pose {
696 let mut jtj = Matrix6::<f64>::zeros();
697 let mut jtr = Vector6::<f64>::zeros();
698 let gs = corr.group_size;
699 let num_groups = corr.num_groups();
700
701 for g in 0..num_groups {
702 if (inlier_mask[g / 64] & (1 << (g % 64))) == 0 {
703 continue;
704 }
705 let start = g * gs;
706
707 for k in start..(start + gs) {
708 let obj = corr.object_points[k];
709 let p_world = Vector3::new(obj[0], obj[1], obj[2]);
710 let p_cam = pose.rotation * p_world + pose.translation;
711 if p_cam.z < 1e-4 {
712 continue;
713 }
714 let z_inv = 1.0 / p_cam.z;
715 let x_z = p_cam.x * z_inv;
716 let y_z = p_cam.y * z_inv;
717
718 let u = intrinsics.fx * x_z + intrinsics.cx;
719 let v = intrinsics.fy * y_z + intrinsics.cy;
720
721 let res_u = f64::from(corr.image_points[k].x) - u;
722 let res_v = f64::from(corr.image_points[k].y) - v;
723
724 let (ju0, ju2, ju3, ju4, ju5, jv1, jv2, jv3, jv4, jv5) =
728 projection_jacobian(x_z, y_z, z_inv, intrinsics);
729
730 jtr[0] += ju0 * res_u;
731 jtr[1] += jv1 * res_v;
732 jtr[2] += ju2 * res_u + jv2 * res_v;
733 jtr[3] += ju3 * res_u + jv3 * res_v;
734 jtr[4] += ju4 * res_u + jv4 * res_v;
735 jtr[5] += ju5 * res_u + jv5 * res_v;
736
737 jtj[(0, 0)] += ju0 * ju0;
738 jtj[(0, 2)] += ju0 * ju2;
739 jtj[(0, 3)] += ju0 * ju3;
740 jtj[(0, 4)] += ju0 * ju4;
741 jtj[(0, 5)] += ju0 * ju5;
742
743 jtj[(1, 1)] += jv1 * jv1;
744 jtj[(1, 2)] += jv1 * jv2;
745 jtj[(1, 3)] += jv1 * jv3;
746 jtj[(1, 4)] += jv1 * jv4;
747 jtj[(1, 5)] += jv1 * jv5;
748
749 jtj[(2, 2)] += ju2 * ju2 + jv2 * jv2;
750 jtj[(2, 3)] += ju2 * ju3 + jv2 * jv3;
751 jtj[(2, 4)] += ju2 * ju4 + jv2 * jv4;
752 jtj[(2, 5)] += ju2 * ju5 + jv2 * jv5;
753
754 jtj[(3, 3)] += ju3 * ju3 + jv3 * jv3;
755 jtj[(3, 4)] += ju3 * ju4 + jv3 * jv4;
756 jtj[(3, 5)] += ju3 * ju5 + jv3 * jv5;
757
758 jtj[(4, 4)] += ju4 * ju4 + jv4 * jv4;
759 jtj[(4, 5)] += ju4 * ju5 + jv4 * jv5;
760
761 jtj[(5, 5)] += ju5 * ju5 + jv5 * jv5;
762 }
763 }
764 symmetrize_jtj6(&mut jtj);
765
766 if let Some(chol) = jtj.cholesky() {
768 let delta = chol.solve(&jtr);
769 let twist = Vector3::new(delta[3], delta[4], delta[5]);
770 let dq = UnitQuaternion::from_scaled_axis(twist);
771 Pose {
772 rotation: (dq * UnitQuaternion::from_matrix(&pose.rotation))
773 .to_rotation_matrix()
774 .into_inner(),
775 translation: pose.translation + Vector3::new(delta[0], delta[1], delta[2]),
776 }
777 } else {
778 *pose
779 }
780 }
781
782 #[allow(clippy::too_many_lines, clippy::similar_names, clippy::unused_self)]
789 fn refine_aw_lm(
790 &self,
791 initial_pose: &Pose,
792 corr: &PointCorrespondences<'_>,
793 intrinsics: &CameraIntrinsics,
794 inlier_mask: &[u64; 16],
795 ) -> (Pose, Matrix6<f64>) {
796 let mut pose = *initial_pose;
797 let mut lambda = 1e-3;
798 let mut nu = 2.0;
799
800 let gs = corr.group_size;
801 let num_groups = corr.num_groups();
802
803 let compute_equations = |current_pose: &Pose| -> (f64, Matrix6<f64>, Vector6<f64>) {
804 let mut jtj = Matrix6::<f64>::zeros();
805 let mut jtr = Vector6::<f64>::zeros();
806 let mut total_cost = 0.0;
807
808 for g in 0..num_groups {
809 if (inlier_mask[g / 64] & (1 << (g % 64))) == 0 {
810 continue;
811 }
812 let start = g * gs;
813
814 for k in start..(start + gs) {
815 let obj = corr.object_points[k];
816 let p_world = Vector3::new(obj[0], obj[1], obj[2]);
817 let p_cam = current_pose.rotation * p_world + current_pose.translation;
818 if p_cam.z < 1e-4 {
819 total_cost += 1e6;
820 continue;
821 }
822 let z_inv = 1.0 / p_cam.z;
823 let x_z = p_cam.x * z_inv;
824 let y_z = p_cam.y * z_inv;
825
826 let u = intrinsics.fx * x_z + intrinsics.cx;
827 let v = intrinsics.fy * y_z + intrinsics.cy;
828
829 let res_u = f64::from(corr.image_points[k].x) - u;
830 let res_v = f64::from(corr.image_points[k].y) - v;
831
832 let info = corr.information_matrices[k];
833
834 let dist_sq = res_u * (info[(0, 0)] * res_u + info[(0, 1)] * res_v)
835 + res_v * (info[(1, 0)] * res_u + info[(1, 1)] * res_v);
836
837 let huber_k = 1.345;
838 let dist = dist_sq.sqrt();
839 let weight = if dist > huber_k { huber_k / dist } else { 1.0 };
840 total_cost += if dist > huber_k {
841 huber_k * (dist - 0.5 * huber_k)
842 } else {
843 0.5 * dist_sq
844 };
845
846 let (ju0, ju2, ju3, ju4, ju5, jv1, jv2, jv3, jv4, jv5) =
847 projection_jacobian(x_z, y_z, z_inv, intrinsics);
848
849 let w00 = info[(0, 0)] * weight;
850 let w01 = info[(0, 1)] * weight;
851 let w10 = info[(1, 0)] * weight;
852 let w11 = info[(1, 1)] * weight;
853
854 let k00 = ju0 * w00;
855 let k01 = ju0 * w01;
856 let k10 = jv1 * w10;
857 let k11 = jv1 * w11;
858 let k20 = ju2 * w00 + jv2 * w10;
859 let k21 = ju2 * w01 + jv2 * w11;
860 let k30 = ju3 * w00 + jv3 * w10;
861 let k31 = ju3 * w01 + jv3 * w11;
862 let k40 = ju4 * w00 + jv4 * w10;
863 let k41 = ju4 * w01 + jv4 * w11;
864 let k50 = ju5 * w00 + jv5 * w10;
865 let k51 = ju5 * w01 + jv5 * w11;
866
867 jtr[0] += k00 * res_u + k01 * res_v;
868 jtr[1] += k10 * res_u + k11 * res_v;
869 jtr[2] += k20 * res_u + k21 * res_v;
870 jtr[3] += k30 * res_u + k31 * res_v;
871 jtr[4] += k40 * res_u + k41 * res_v;
872 jtr[5] += k50 * res_u + k51 * res_v;
873
874 jtj[(0, 0)] += k00 * ju0;
875 jtj[(0, 1)] += k01 * jv1;
876 jtj[(0, 2)] += k00 * ju2 + k01 * jv2;
877 jtj[(0, 3)] += k00 * ju3 + k01 * jv3;
878 jtj[(0, 4)] += k00 * ju4 + k01 * jv4;
879 jtj[(0, 5)] += k00 * ju5 + k01 * jv5;
880
881 jtj[(1, 1)] += k11 * jv1;
882 jtj[(1, 2)] += k10 * ju2 + k11 * jv2;
883 jtj[(1, 3)] += k10 * ju3 + k11 * jv3;
884 jtj[(1, 4)] += k10 * ju4 + k11 * jv4;
885 jtj[(1, 5)] += k10 * ju5 + k11 * jv5;
886
887 jtj[(2, 2)] += k20 * ju2 + k21 * jv2;
888 jtj[(2, 3)] += k20 * ju3 + k21 * jv3;
889 jtj[(2, 4)] += k20 * ju4 + k21 * jv4;
890 jtj[(2, 5)] += k20 * ju5 + k21 * jv5;
891
892 jtj[(3, 3)] += k30 * ju3 + k31 * jv3;
893 jtj[(3, 4)] += k30 * ju4 + k31 * jv4;
894 jtj[(3, 5)] += k30 * ju5 + k31 * jv5;
895
896 jtj[(4, 4)] += k40 * ju4 + k41 * jv4;
897 jtj[(4, 5)] += k40 * ju5 + k41 * jv5;
898
899 jtj[(5, 5)] += k50 * ju5 + k51 * jv5;
900 }
901 }
902 symmetrize_jtj6(&mut jtj);
903 (total_cost, jtj, jtr)
904 };
905
906 let (mut cur_cost, mut cur_jtj, mut cur_jtr) = compute_equations(&pose);
907
908 for _iter in 0..20 {
909 if cur_jtr.amax() < 1e-8 {
910 break;
911 }
912
913 let mut jtj_damped = cur_jtj;
914 let diag = cur_jtj.diagonal();
915 for i in 0..6 {
916 jtj_damped[(i, i)] += lambda * (diag[i] + 1e-6);
917 }
918
919 if let Some(chol) = jtj_damped.cholesky() {
920 let delta = chol.solve(&cur_jtr);
921 let twist = Vector3::new(delta[3], delta[4], delta[5]);
922 let dq = UnitQuaternion::from_scaled_axis(twist);
923 let new_pose = Pose {
924 rotation: (dq * UnitQuaternion::from_matrix(&pose.rotation))
925 .to_rotation_matrix()
926 .into_inner(),
927 translation: pose.translation + Vector3::new(delta[0], delta[1], delta[2]),
928 };
929
930 let (new_cost, new_jtj, new_jtr) = compute_equations(&new_pose);
931 let rho = (cur_cost - new_cost)
932 / (0.5 * delta.dot(&(lambda * delta + cur_jtr)).max(1e-12));
933
934 if rho > 0.0 {
935 pose = new_pose;
936 cur_cost = new_cost;
937 cur_jtj = new_jtj;
938 cur_jtr = new_jtr;
939 lambda *= (1.0 - (2.0 * rho - 1.0).powi(3)).max(1.0 / 3.0);
940 nu = 2.0;
941 if delta.norm() < 1e-7 {
942 break;
943 }
944 } else {
945 lambda *= nu;
946 nu *= 2.0;
947 }
948 } else {
949 lambda *= 10.0;
950 }
951 }
952
953 let covariance = cur_jtj.try_inverse().unwrap_or_else(Matrix6::zeros);
954 (pose, covariance)
955 }
956}
957
958pub(crate) fn board_seed_from_pose6d(
968 pose6d_data: &[f32; 7],
969 tag_id: usize,
970 obj_points: &[Option<[[f64; 3]; 4]>],
971) -> Option<Pose> {
972 if pose6d_data.iter().any(|v| v.is_nan()) || pose6d_data[2].abs() < 1e-6 {
973 return None;
974 }
975 let det_t = Vector3::new(
976 f64::from(pose6d_data[0]),
977 f64::from(pose6d_data[1]),
978 f64::from(pose6d_data[2]),
979 );
980 let det_q = UnitQuaternion::from_quaternion(nalgebra::Quaternion::new(
981 f64::from(pose6d_data[6]), f64::from(pose6d_data[3]), f64::from(pose6d_data[4]), f64::from(pose6d_data[5]), ));
986 let corners = obj_points.get(tag_id)?.as_ref()?;
989 let tl = corners[0];
990 let br = corners[2];
991 let tag_center = Vector3::new(
992 (tl[0] + br[0]) * 0.5,
993 (tl[1] + br[1]) * 0.5,
994 (tl[2] + br[2]) * 0.5,
995 );
996 Some(Pose {
997 rotation: *det_q.to_rotation_matrix().matrix(),
998 translation: det_t - (det_q * tag_center),
999 })
1000}
1001
1002pub struct BoardEstimator {
1012 pub config: Arc<AprilGridTopology>,
1014 pub solver: RobustPoseSolver,
1016 scratch_img: Box<[Point2f]>,
1020 scratch_obj: Box<[[f64; 3]]>,
1021 scratch_info: Box<[Matrix2<f64>]>,
1022 scratch_seeds: Box<[Option<Pose>]>,
1023}
1024
1025impl BoardEstimator {
1026 const CORNERS_PER_TAG: usize = 4;
1027 const MAX_CORR: usize = MAX_CANDIDATES * Self::CORNERS_PER_TAG;
1028
1029 #[must_use]
1038 pub fn new(config: Arc<AprilGridTopology>) -> Self {
1039 Self {
1040 config,
1041 solver: RobustPoseSolver::new(),
1042 scratch_img: vec![Point2f { x: 0.0, y: 0.0 }; Self::MAX_CORR].into_boxed_slice(),
1043 scratch_obj: vec![[0.0f64; 3]; Self::MAX_CORR].into_boxed_slice(),
1044 scratch_info: vec![Matrix2::zeros(); Self::MAX_CORR].into_boxed_slice(),
1045 scratch_seeds: vec![None; MAX_CANDIDATES].into_boxed_slice(),
1046 }
1047 }
1048
1049 #[must_use]
1051 pub fn with_lo_ransac_config(mut self, cfg: LoRansacConfig) -> Self {
1052 self.solver.lo_ransac = cfg;
1053 self
1054 }
1055
1056 #[must_use]
1063 pub fn estimate(
1064 &mut self,
1065 batch: &crate::batch::DetectionBatchView<'_>,
1066 intrinsics: &CameraIntrinsics,
1067 ) -> Option<BoardPose> {
1068 let num_groups = self.flatten_batch(batch);
1071 if num_groups < 4 {
1072 return None;
1073 }
1074
1075 let m = num_groups * Self::CORNERS_PER_TAG;
1076 let corr = PointCorrespondences {
1077 image_points: &self.scratch_img[..m],
1078 object_points: &self.scratch_obj[..m],
1079 information_matrices: &self.scratch_info[..m],
1080 group_size: Self::CORNERS_PER_TAG,
1081 seed_poses: &self.scratch_seeds[..num_groups],
1082 };
1083
1084 self.solver.estimate(&corr, intrinsics)
1086 }
1087
1088 fn flatten_batch(&mut self, batch: &crate::batch::DetectionBatchView<'_>) -> usize {
1096 let mut g = 0usize;
1097
1098 for i in 0..batch.len() {
1099 let id = batch.ids[i] as usize;
1100 if id >= self.config.obj_points.len() {
1101 continue;
1102 }
1103 let Some(obj) = self.config.obj_points[id] else {
1104 continue;
1105 };
1106
1107 let base = g * Self::CORNERS_PER_TAG;
1108 for (j, obj_pt) in obj.iter().enumerate() {
1109 self.scratch_img[base + j] = batch.corners[i][j];
1110 self.scratch_obj[base + j] = *obj_pt;
1111 self.scratch_info[base + j] = Matrix2::new(
1114 f64::from(batch.corner_covariances[i][j * 4]),
1115 f64::from(batch.corner_covariances[i][j * 4 + 1]),
1116 f64::from(batch.corner_covariances[i][j * 4 + 2]),
1117 f64::from(batch.corner_covariances[i][j * 4 + 3]),
1118 )
1119 .try_inverse()
1120 .unwrap_or_else(Matrix2::identity);
1121 }
1122
1123 let seed = self.init_pose_from_batch_tag(i, batch);
1126 self.scratch_seeds[g] = seed;
1127 g += 1;
1128 }
1129
1130 g
1131 }
1132
1133 fn init_pose_from_batch_tag(
1137 &self,
1138 b_idx: usize,
1139 batch: &crate::batch::DetectionBatchView<'_>,
1140 ) -> Option<Pose> {
1141 board_seed_from_pose6d(
1142 &batch.poses[b_idx].data,
1143 batch.ids[b_idx] as usize,
1144 &self.config.obj_points,
1145 )
1146 }
1147}
1148
1149#[cfg(test)]
1152#[allow(
1153 clippy::unwrap_used,
1154 clippy::expect_used,
1155 clippy::cast_sign_loss,
1156 clippy::similar_names,
1157 clippy::too_many_lines,
1158 clippy::items_after_statements,
1159 missing_docs
1160)]
1161mod tests {
1162 use super::*;
1163 use crate::batch::{CandidateState, DetectionBatch, DetectionBatchView, Point2f};
1164 use nalgebra::Matrix3;
1165
1166 fn test_intrinsics() -> CameraIntrinsics {
1170 CameraIntrinsics::new(500.0, 500.0, 320.0, 240.0)
1171 }
1172
1173 fn all_corners(obj_points: &[Option<[[f64; 3]; 4]>]) -> Vec<[f64; 3]> {
1175 obj_points
1176 .iter()
1177 .filter_map(|opt| *opt)
1178 .flat_map(std::iter::IntoIterator::into_iter)
1179 .collect()
1180 }
1181
1182 fn centroid(pts: &[[f64; 3]]) -> [f64; 3] {
1184 let n = pts.len() as f64;
1185 let (sx, sy, sz) = pts.iter().fold((0.0, 0.0, 0.0), |(ax, ay, az), p| {
1186 (ax + p[0], ay + p[1], az + p[2])
1187 });
1188 [sx / n, sy / n, sz / n]
1189 }
1190
1191 fn build_synthetic_batch(
1197 obj_points: &[Option<[[f64; 3]; 4]>],
1198 pose: &Pose,
1199 intrinsics: &CameraIntrinsics,
1200 ) -> (DetectionBatch, usize) {
1201 let mut batch = DetectionBatch::new();
1202 let mut n = 0usize;
1203
1204 let q = UnitQuaternion::from_matrix(&pose.rotation);
1205
1206 for (tag_id, opt_pts) in obj_points.iter().enumerate() {
1207 let Some(obj) = opt_pts else { continue };
1208
1209 for (j, pt) in obj.iter().enumerate() {
1210 let p_world = Vector3::new(pt[0], pt[1], pt[2]);
1211 let proj = pose.project(&p_world, intrinsics);
1212 batch.corners[n][j] = Point2f {
1213 x: proj[0] as f32,
1214 y: proj[1] as f32,
1215 };
1216 }
1217
1218 let center = Vector3::new(
1220 (obj[0][0] + obj[2][0]) * 0.5,
1221 (obj[0][1] + obj[2][1]) * 0.5,
1222 (obj[0][2] + obj[2][2]) * 0.5,
1223 );
1224 let det_t = pose.rotation * center + pose.translation;
1225 batch.poses[n].data = [
1226 det_t.x as f32,
1227 det_t.y as f32,
1228 det_t.z as f32,
1229 q.i as f32,
1230 q.j as f32,
1231 q.k as f32,
1232 q.w as f32,
1233 ];
1234
1235 for j in 0..4 {
1236 batch.corner_covariances[n][j * 4] = 1.0;
1239 batch.corner_covariances[n][j * 4 + 3] = 1.0;
1240 }
1241
1242 batch.ids[n] = tag_id as u32;
1243 batch.status_mask[n] = CandidateState::Valid;
1244 n += 1;
1245 }
1246
1247 (batch, n)
1248 }
1249
1250 #[allow(clippy::type_complexity)]
1256 fn build_correspondences_from_batch(
1257 obj_points: &[Option<[[f64; 3]; 4]>],
1258 view: &DetectionBatchView<'_>,
1259 estimator: &BoardEstimator,
1260 ) -> (
1261 Vec<Point2f>,
1262 Vec<[f64; 3]>,
1263 Vec<Matrix2<f64>>,
1264 Vec<Option<Pose>>,
1265 ) {
1266 let num_valid = view.len();
1267 let mut img = Vec::with_capacity(num_valid * 4);
1268 let mut obj = Vec::with_capacity(num_valid * 4);
1269 let mut info = Vec::with_capacity(num_valid * 4);
1270 let mut seeds = Vec::with_capacity(num_valid);
1271
1272 for b_idx in 0..num_valid {
1273 let id = view.ids[b_idx] as usize;
1274 let pts = obj_points[id].unwrap();
1275 for (j, &obj_pt) in pts.iter().enumerate() {
1276 img.push(view.corners[b_idx][j]);
1277 obj.push(obj_pt);
1278 info.push(Matrix2::identity());
1279 }
1280 seeds.push(estimator.init_pose_from_batch_tag(b_idx, view));
1281 }
1282
1283 (img, obj, info, seeds)
1284 }
1285
1286 fn mean_reprojection_sq(
1289 pose: &Pose,
1290 batch: &DetectionBatch,
1291 intrinsics: &CameraIntrinsics,
1292 obj_points: &[Option<[[f64; 3]; 4]>],
1293 num_valid: usize,
1294 ) -> f64 {
1295 let mut sum_sq = 0.0f64;
1296 let mut count = 0usize;
1297 for i in 0..num_valid {
1298 let id = batch.ids[i] as usize;
1299 let obj = obj_points[id].unwrap();
1300 for (j, pt) in obj.iter().enumerate() {
1301 let p_world = Vector3::new(pt[0], pt[1], pt[2]);
1302 let proj = pose.project(&p_world, intrinsics);
1303 let dx = proj[0] - f64::from(batch.corners[i][j].x);
1304 let dy = proj[1] - f64::from(batch.corners[i][j].y);
1305 sum_sq += dx * dx + dy * dy;
1306 count += 1;
1307 }
1308 }
1309 sum_sq / count.max(1) as f64
1310 }
1311
1312 #[test]
1315 fn test_charuco_board_marker_count() {
1316 let config = CharucoTopology::new(6, 6, 0.1, 0.08, usize::MAX).unwrap();
1318 let count = config.obj_points.iter().filter(|o| o.is_some()).count();
1319 assert_eq!(count, 18);
1320 }
1321
1322 #[test]
1323 fn test_charuco_board_centroid_is_origin() {
1324 let config = CharucoTopology::new(6, 6, 0.1, 0.08, usize::MAX).unwrap();
1327 let pts = all_corners(&config.obj_points);
1328 assert!(!pts.is_empty());
1329 let c = centroid(&pts);
1330 assert!(c[0].abs() < 1e-9, "centroid x = {}", c[0]);
1331 assert!(c[1].abs() < 1e-9, "centroid y = {}", c[1]);
1332 assert!(c[2].abs() < 1e-9, "all points must lie on z = 0");
1333 }
1334
1335 #[test]
1336 fn test_charuco_corner_order_tl_tr_br_bl() {
1337 let config = CharucoTopology::new(4, 4, 0.1, 0.08, usize::MAX).unwrap();
1340 for opt in &config.obj_points {
1341 let [tl, tr, br, bl] = opt.unwrap();
1342 assert!(tl[0] < tr[0], "TL.x must be left of TR.x");
1343 assert!(
1344 (tl[1] - tr[1]).abs() < 1e-9,
1345 "TL and TR must share the same y"
1346 );
1347 assert!(
1348 (tr[0] - br[0]).abs() < 1e-9,
1349 "TR and BR must share the same x"
1350 );
1351 assert!(
1352 (bl[0] - tl[0]).abs() < 1e-9,
1353 "BL and TL must share the same x"
1354 );
1355 assert!(
1356 bl[1] > tl[1],
1357 "BL.y must be below TL.y (y increases downward)"
1358 );
1359 assert!(
1360 (bl[1] - br[1]).abs() < 1e-9,
1361 "BL and BR must share the same y"
1362 );
1363 for pt in &[tl, tr, br, bl] {
1364 assert!(pt[2].abs() < 1e-9, "all corners must lie on z = 0");
1365 }
1366 }
1367 }
1368
1369 #[test]
1370 fn test_charuco_marker_size_matches_config() {
1371 let marker_length = 0.08;
1373 let config = CharucoTopology::new(4, 4, 0.1, marker_length, usize::MAX).unwrap();
1374 for opt in &config.obj_points {
1375 let [tl, tr, _br, bl] = opt.unwrap();
1376 let width = tr[0] - tl[0];
1377 let height = bl[1] - tl[1];
1378 assert!((width - marker_length).abs() < 1e-9, "marker width {width}");
1379 assert!(
1380 (height - marker_length).abs() < 1e-9,
1381 "marker height {height}"
1382 );
1383 }
1384 }
1385
1386 #[test]
1387 fn test_charuco_board_no_marker_overlap() {
1388 let config = CharucoTopology::new(4, 4, 0.1, 0.08, usize::MAX).unwrap();
1390 let mut corners: Vec<[f64; 3]> = config
1391 .obj_points
1392 .iter()
1393 .filter_map(|o| *o)
1394 .flat_map(IntoIterator::into_iter)
1395 .collect();
1396 corners.sort_by(|a, b| {
1397 a[0].partial_cmp(&b[0])
1398 .unwrap()
1399 .then(a[1].partial_cmp(&b[1]).unwrap())
1400 });
1401 for w in corners.windows(2) {
1402 assert!(
1403 (w[0][0] - w[1][0]).abs() > 1e-9 || (w[0][1] - w[1][1]).abs() > 1e-9,
1404 "duplicate corner: {:?}",
1405 w[0]
1406 );
1407 }
1408 }
1409
1410 #[test]
1411 fn test_aprilgrid_board_marker_count() {
1412 let config = AprilGridTopology::new(4, 4, 0.01, 0.1, usize::MAX).unwrap();
1414 let count = config.obj_points.iter().filter(|o| o.is_some()).count();
1415 assert_eq!(count, 16);
1416 }
1417
1418 #[test]
1419 fn test_aprilgrid_board_centroid_is_origin() {
1420 let config = AprilGridTopology::new(6, 6, 0.01, 0.1, usize::MAX).unwrap();
1421 let pts = all_corners(&config.obj_points);
1422 let c = centroid(&pts);
1423 assert!(c[0].abs() < 1e-9, "centroid x = {}", c[0]);
1424 assert!(c[1].abs() < 1e-9, "centroid y = {}", c[1]);
1425 }
1426
1427 #[test]
1428 fn test_aprilgrid_adjacent_marker_step() {
1429 let marker_length = 0.1;
1431 let spacing = 0.02;
1432 let config = AprilGridTopology::new(2, 3, spacing, marker_length, usize::MAX).unwrap();
1433 let step = marker_length + spacing;
1434
1435 let tl0 = config.obj_points[0].unwrap()[0];
1436 let tl1 = config.obj_points[1].unwrap()[0];
1437 assert!(
1438 (tl1[0] - tl0[0] - step).abs() < 1e-9,
1439 "expected step {step}, got {}",
1440 tl1[0] - tl0[0]
1441 );
1442
1443 let tl_r0 = config.obj_points[0].unwrap()[0];
1444 let tl_r1 = config.obj_points[3].unwrap()[0]; assert!(
1446 (tl_r1[1] - tl_r0[1] - step).abs() < 1e-9,
1447 "expected row step {step}, got {}",
1448 tl_r1[1] - tl_r0[1]
1449 );
1450 }
1451
1452 fn math_test_config() -> Arc<AprilGridTopology> {
1456 Arc::new(AprilGridTopology::new(4, 4, 0.02, 0.08, usize::MAX).unwrap())
1457 }
1458
1459 #[test]
1460 fn test_evaluate_inliers_perfect_pose_all_inliers() {
1461 let config = math_test_config();
1464 let estimator = BoardEstimator::new(Arc::clone(&config));
1465 let intrinsics = test_intrinsics();
1466 let pose = Pose::new(Matrix3::identity(), Vector3::new(0.0, 0.0, 1.0));
1467 let (mut batch, num_valid) = build_synthetic_batch(&config.obj_points, &pose, &intrinsics);
1468 let v = batch.partition(num_valid);
1469 let view = batch.view(v);
1470
1471 let (img, obj, info, seeds) =
1472 build_correspondences_from_batch(&config.obj_points, &view, &estimator);
1473 let corr = PointCorrespondences {
1474 image_points: &img,
1475 object_points: &obj,
1476 information_matrices: &info,
1477 group_size: 4,
1478 seed_poses: &seeds,
1479 };
1480
1481 let solver = RobustPoseSolver::new();
1482 let (_, count) = solver.evaluate_inliers(&pose, &corr, &intrinsics, 1.0);
1483 assert_eq!(count, v, "all tags must be inliers under perfect pose");
1484 }
1485
1486 #[test]
1487 fn test_evaluate_inliers_bad_pose_no_inliers() {
1488 let config = math_test_config();
1491 let estimator = BoardEstimator::new(Arc::clone(&config));
1492 let intrinsics = test_intrinsics();
1493 let true_pose = Pose::new(Matrix3::identity(), Vector3::new(0.0, 0.0, 1.0));
1494 let (mut batch, num_valid) =
1495 build_synthetic_batch(&config.obj_points, &true_pose, &intrinsics);
1496 let v = batch.partition(num_valid);
1497 let view = batch.view(v);
1498
1499 let bad_pose = Pose::new(Matrix3::identity(), Vector3::new(0.5, 0.0, 1.0));
1500 let (img, obj, info, seeds) =
1501 build_correspondences_from_batch(&config.obj_points, &view, &estimator);
1502 let corr = PointCorrespondences {
1503 image_points: &img,
1504 object_points: &obj,
1505 information_matrices: &info,
1506 group_size: 4,
1507 seed_poses: &seeds,
1508 };
1509
1510 let solver = RobustPoseSolver::new();
1511 let (_, count) = solver.evaluate_inliers(&bad_pose, &corr, &intrinsics, 100.0);
1512 assert_eq!(
1513 count, 0,
1514 "no tags should survive under a heavily shifted pose"
1515 );
1516 }
1517
1518 #[test]
1519 fn test_evaluate_inliers_inlier_mask_consistency() {
1520 let config = math_test_config();
1522 let estimator = BoardEstimator::new(Arc::clone(&config));
1523 let intrinsics = test_intrinsics();
1524 let pose = Pose::new(Matrix3::identity(), Vector3::new(0.0, 0.0, 1.0));
1525 let (mut batch, num_valid) = build_synthetic_batch(&config.obj_points, &pose, &intrinsics);
1526 let v = batch.partition(num_valid);
1527 let view = batch.view(v);
1528
1529 let (img, obj, info, seeds) =
1530 build_correspondences_from_batch(&config.obj_points, &view, &estimator);
1531 let corr = PointCorrespondences {
1532 image_points: &img,
1533 object_points: &obj,
1534 information_matrices: &info,
1535 group_size: 4,
1536 seed_poses: &seeds,
1537 };
1538
1539 let solver = RobustPoseSolver::new();
1540 let (mask, count) = solver.evaluate_inliers(&pose, &corr, &intrinsics, 1.0);
1541
1542 let bits_set: usize = mask.iter().map(|w| w.count_ones() as usize).sum();
1543 assert_eq!(
1544 bits_set, count,
1545 "bitmask popcount must equal reported count"
1546 );
1547 }
1548
1549 #[test]
1550 fn test_init_pose_from_batch_tag_recovers_board_pose() {
1551 let config = math_test_config();
1554 let estimator = BoardEstimator::new(Arc::clone(&config));
1555 let intrinsics = test_intrinsics();
1556 let true_pose = Pose::new(Matrix3::identity(), Vector3::new(0.0, 0.0, 1.0));
1557 let (mut batch, num_valid) =
1558 build_synthetic_batch(&config.obj_points, &true_pose, &intrinsics);
1559 let v = batch.partition(num_valid);
1560 let view = batch.view(v);
1561
1562 for b_idx in 0..v {
1563 let pose = estimator
1564 .init_pose_from_batch_tag(b_idx, &view)
1565 .expect("tag must produce a valid pose");
1566 let t_error = (pose.translation - true_pose.translation).norm();
1567 assert!(
1568 t_error < 1e-5,
1569 "tag {b_idx}: translation error {t_error} m exceeds 10 µm"
1570 );
1571 }
1572 }
1573
1574 #[test]
1575 fn test_init_pose_from_batch_tag_nan_returns_none() {
1576 let config = math_test_config();
1578 let estimator = BoardEstimator::new(Arc::clone(&config));
1579 let mut batch = DetectionBatch::new();
1580 batch.ids[0] = 0;
1581 batch.poses[0].data = [f32::NAN; 7];
1582 assert!(
1583 estimator
1584 .init_pose_from_batch_tag(0, &batch.view(1))
1585 .is_none()
1586 );
1587 }
1588
1589 #[test]
1590 fn test_init_pose_from_batch_tag_near_zero_depth_returns_none() {
1591 let config = math_test_config();
1593 let estimator = BoardEstimator::new(Arc::clone(&config));
1594 let mut batch = DetectionBatch::new();
1595 batch.ids[0] = 0;
1596 batch.poses[0].data = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0]; assert!(
1598 estimator
1599 .init_pose_from_batch_tag(0, &batch.view(1))
1600 .is_none()
1601 );
1602 }
1603
1604 #[test]
1605 fn test_gn_step_reduces_reprojection_error() {
1606 let config = math_test_config();
1609 let estimator = BoardEstimator::new(Arc::clone(&config));
1610 let intrinsics = test_intrinsics();
1611 let true_pose = Pose::new(Matrix3::identity(), Vector3::new(0.0, 0.0, 1.0));
1612 let (mut batch, num_valid) =
1613 build_synthetic_batch(&config.obj_points, &true_pose, &intrinsics);
1614 let v = batch.partition(num_valid);
1615 let view = batch.view(v);
1616
1617 let perturbed = Pose::new(Matrix3::identity(), Vector3::new(0.02, 0.0, 1.0));
1618 let (img, obj, info, seeds) =
1619 build_correspondences_from_batch(&config.obj_points, &view, &estimator);
1620 let corr = PointCorrespondences {
1621 image_points: &img,
1622 object_points: &obj,
1623 information_matrices: &info,
1624 group_size: 4,
1625 seed_poses: &seeds,
1626 };
1627 let all_inliers = [u64::MAX; 16];
1628
1629 let solver = RobustPoseSolver::new();
1630 let before = mean_reprojection_sq(&perturbed, &batch, &intrinsics, &config.obj_points, v);
1631 let stepped = solver.gn_step(&perturbed, &corr, &intrinsics, &all_inliers);
1632 let after = mean_reprojection_sq(&stepped, &batch, &intrinsics, &config.obj_points, v);
1633
1634 assert!(
1635 after < before,
1636 "GN step must reduce error: {before:.6} → {after:.6} px²"
1637 );
1638 }
1639
1640 #[test]
1641 fn test_gn_step_singular_returns_original() {
1642 let config = math_test_config();
1645 let estimator = BoardEstimator::new(Arc::clone(&config));
1646 let intrinsics = test_intrinsics();
1647 let pose = Pose::new(Matrix3::identity(), Vector3::new(0.0, 0.0, 1.0));
1648 let (mut batch, num_valid) = build_synthetic_batch(&config.obj_points, &pose, &intrinsics);
1649 let v = batch.partition(num_valid);
1650 let view = batch.view(v);
1651
1652 let (img, obj, info, seeds) =
1653 build_correspondences_from_batch(&config.obj_points, &view, &estimator);
1654 let corr = PointCorrespondences {
1655 image_points: &img,
1656 object_points: &obj,
1657 information_matrices: &info,
1658 group_size: 4,
1659 seed_poses: &seeds,
1660 };
1661 let no_inliers = [0u64; 16];
1662
1663 let solver = RobustPoseSolver::new();
1664 let result = solver.gn_step(&pose, &corr, &intrinsics, &no_inliers);
1665 assert!(
1666 (result.translation - pose.translation).norm() < 1e-12,
1667 "pose must be unchanged when normal equations are singular"
1668 );
1669 }
1670
1671 #[test]
1672 fn test_refine_aw_lm_converges_from_small_offset() {
1673 let config = math_test_config();
1675 let estimator = BoardEstimator::new(Arc::clone(&config));
1676 let intrinsics = test_intrinsics();
1677 let true_pose = Pose::new(Matrix3::identity(), Vector3::new(0.0, 0.0, 1.0));
1678 let (mut batch, num_valid) =
1679 build_synthetic_batch(&config.obj_points, &true_pose, &intrinsics);
1680 let v = batch.partition(num_valid);
1681 let view = batch.view(v);
1682
1683 let perturbed = Pose::new(Matrix3::identity(), Vector3::new(0.02, -0.01, 1.0));
1684 let (img, obj, info, seeds) =
1685 build_correspondences_from_batch(&config.obj_points, &view, &estimator);
1686 let corr = PointCorrespondences {
1687 image_points: &img,
1688 object_points: &obj,
1689 information_matrices: &info,
1690 group_size: 4,
1691 seed_poses: &seeds,
1692 };
1693 let all_inliers = [u64::MAX; 16];
1694
1695 let solver = RobustPoseSolver::new();
1696 let (refined, cov) = solver.refine_aw_lm(&perturbed, &corr, &intrinsics, &all_inliers);
1697
1698 let t_error = (refined.translation - true_pose.translation).norm();
1699 assert!(
1700 t_error < 1e-4,
1701 "translation error {t_error} m exceeds 0.1 mm"
1702 );
1703
1704 for i in 0..6 {
1705 assert!(
1706 cov[(i, i)] >= 0.0,
1707 "covariance diagonal [{i},{i}] must be non-negative"
1708 );
1709 }
1710 }
1711
1712 #[test]
1713 fn test_refine_aw_lm_covariance_is_symmetric() {
1714 let config = math_test_config();
1716 let estimator = BoardEstimator::new(Arc::clone(&config));
1717 let intrinsics = test_intrinsics();
1718 let pose = Pose::new(Matrix3::identity(), Vector3::new(0.0, 0.0, 1.0));
1719 let (mut batch, num_valid) = build_synthetic_batch(&config.obj_points, &pose, &intrinsics);
1720 let v = batch.partition(num_valid);
1721 let view = batch.view(v);
1722
1723 let (img, obj, info, seeds) =
1724 build_correspondences_from_batch(&config.obj_points, &view, &estimator);
1725 let corr = PointCorrespondences {
1726 image_points: &img,
1727 object_points: &obj,
1728 information_matrices: &info,
1729 group_size: 4,
1730 seed_poses: &seeds,
1731 };
1732 let all_inliers = [u64::MAX; 16];
1733
1734 let solver = RobustPoseSolver::new();
1735 let (_, cov) = solver.refine_aw_lm(&pose, &corr, &intrinsics, &all_inliers);
1736
1737 for i in 0..6 {
1738 for j in (i + 1)..6 {
1739 assert!(
1740 (cov[(i, j)] - cov[(j, i)]).abs() < 1e-12,
1741 "covariance must be symmetric: [{i},{j}]={} ≠ [{j},{i}]={}",
1742 cov[(i, j)],
1743 cov[(j, i)]
1744 );
1745 }
1746 }
1747 }
1748
1749 #[test]
1750 fn test_estimate_none_with_fewer_than_four_valid_tags() {
1751 let config = math_test_config();
1753 let mut estimator = BoardEstimator::new(config);
1754 let intrinsics = test_intrinsics();
1755
1756 for n_valid in 0..4 {
1757 let mut batch = DetectionBatch::new();
1758 for i in 0..n_valid {
1759 batch.ids[i] = i as u32;
1760 batch.status_mask[i] = CandidateState::Valid;
1761 }
1762 let v = batch.partition(n_valid);
1763 assert!(
1764 estimator.estimate(&batch.view(v), &intrinsics).is_none(),
1765 "expected None with {n_valid} valid tags"
1766 );
1767 }
1768 }
1769
1770 #[test]
1771 fn test_estimate_end_to_end_recovers_translation() {
1772 let config = math_test_config();
1775 let mut estimator = BoardEstimator::new(Arc::clone(&config));
1776 let intrinsics = test_intrinsics();
1777 let true_pose = Pose::new(Matrix3::identity(), Vector3::new(0.05, -0.03, 1.5));
1778 let (mut batch, n) = build_synthetic_batch(&config.obj_points, &true_pose, &intrinsics);
1779 let v = batch.partition(n);
1780
1781 let result = estimator.estimate(&batch.view(v), &intrinsics);
1782 assert!(
1783 result.is_some(),
1784 "estimate() must succeed with all tags visible"
1785 );
1786
1787 let board_pose = result.unwrap();
1788 let t_error = (board_pose.pose.translation - true_pose.translation).norm();
1789 assert!(t_error < 1e-3, "translation error {t_error} m exceeds 1 mm");
1790
1791 let est_q = UnitQuaternion::from_matrix(&board_pose.pose.rotation);
1792 let true_q = UnitQuaternion::from_matrix(&true_pose.rotation);
1793 let r_error = est_q.angle_to(&true_q).to_degrees();
1794 assert!(r_error < 0.1, "rotation error {r_error}° exceeds 0.1°");
1795 }
1796
1797 #[test]
1798 fn test_estimate_covariance_is_positive_definite() {
1799 let config = math_test_config();
1801 let mut estimator = BoardEstimator::new(Arc::clone(&config));
1802 let intrinsics = test_intrinsics();
1803 let pose = Pose::new(Matrix3::identity(), Vector3::new(0.0, 0.0, 1.0));
1804 let (mut batch, n) = build_synthetic_batch(&config.obj_points, &pose, &intrinsics);
1805 let v = batch.partition(n);
1806
1807 let result = estimator.estimate(&batch.view(v), &intrinsics).unwrap();
1808 for i in 0..6 {
1809 assert!(
1810 result.covariance[(i, i)] > 0.0,
1811 "covariance diagonal [{i},{i}] must be positive"
1812 );
1813 }
1814 }
1815
1816 #[test]
1819 fn test_charuco_saddle_count() {
1820 let config = CharucoTopology::new(6, 6, 0.04, 0.03, usize::MAX).unwrap();
1822 assert_eq!(config.saddle_points.len(), 25);
1823 }
1824
1825 #[test]
1826 fn test_charuco_saddle_coords_on_grid() {
1827 let sq = 0.04_f64;
1829 let config = CharucoTopology::new(4, 4, sq, 0.03, usize::MAX).unwrap();
1830 let offset_x = -4.0 * sq / 2.0;
1831 let offset_y = -4.0 * sq / 2.0;
1832 let s0 = config.saddle_points[0];
1833 assert!(
1834 (s0[0] - (offset_x + sq)).abs() < 1e-12,
1835 "saddle x: {}",
1836 s0[0]
1837 );
1838 assert!(
1839 (s0[1] - (offset_y + sq)).abs() < 1e-12,
1840 "saddle y: {}",
1841 s0[1]
1842 );
1843 assert!(s0[2].abs() < 1e-12, "saddle z must be 0");
1844 let saddle_cols = 3usize;
1845 let s = config.saddle_points[saddle_cols + 2];
1846 assert!(
1847 (s[0] - (offset_x + 3.0 * sq)).abs() < 1e-12,
1848 "saddle x: {}",
1849 s[0]
1850 );
1851 assert!(
1852 (s[1] - (offset_y + 2.0 * sq)).abs() < 1e-12,
1853 "saddle y: {}",
1854 s[1]
1855 );
1856 }
1857
1858 #[test]
1859 fn test_charuco_saddle_adjacency_interior_marker() {
1860 let config = CharucoTopology::new(6, 6, 0.04, 0.03, usize::MAX).unwrap();
1863 let adj = config.tag_cell_corners[7];
1864 assert!(adj[0].is_some(), "TL saddle of interior marker must exist");
1865 assert!(adj[1].is_some(), "TR saddle of interior marker must exist");
1866 assert!(adj[2].is_some(), "BR saddle of interior marker must exist");
1867 assert!(adj[3].is_some(), "BL saddle of interior marker must exist");
1868 }
1869
1870 #[test]
1871 fn test_charuco_saddle_adjacency_corner_marker() {
1872 let config = CharucoTopology::new(4, 4, 0.04, 0.03, usize::MAX).unwrap();
1874 let adj = config.tag_cell_corners[0];
1875 assert!(adj[0].is_none(), "TL: (r-1,c-1) = (-1,-1) is out of bounds");
1876 assert!(adj[1].is_none(), "TR: (r-1,c) = (-1,0) is out of bounds");
1877 assert!(adj[2].is_some(), "BR: (r=0,c=0) is a valid interior saddle");
1878 assert!(adj[3].is_none(), "BL: (r,c-1) = (0,-1) is out of bounds");
1879 }
1880
1881 #[test]
1882 fn test_dictionary_bounds_check_charuco() {
1883 let err = CharucoTopology::new(10, 10, 0.04, 0.03, 49);
1886 assert!(err.is_err(), "must fail when markers > max_tag_id");
1887 }
1888
1889 #[test]
1890 fn test_dictionary_bounds_check_aprilgrid() {
1891 let err = AprilGridTopology::new(5, 5, 0.01, 0.04, 24);
1893 assert!(err.is_err(), "must fail when markers > max_tag_id");
1894 }
1895
1896 #[test]
1897 fn test_tag_family_max_id_count() {
1898 use crate::config::TagFamily;
1900 assert_eq!(TagFamily::ArUco4x4_50.max_id_count(), 50);
1901 assert_eq!(TagFamily::ArUco4x4_100.max_id_count(), 100);
1902 }
1903}