1#[derive(Clone, Copy, Debug, PartialEq)]
13#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
14pub enum SegmentationConnectivity {
15 Four,
18 Eight,
21}
22
23#[derive(Clone, Copy, Debug, PartialEq)]
25#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
26pub enum CornerRefinementMode {
27 None,
29 Edge,
31 GridFit,
33 Erf,
35}
36
37#[derive(Clone, Copy, Debug, PartialEq)]
39#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
40pub enum DecodeMode {
41 Hard,
43 Soft,
45}
46
47#[derive(Clone, Copy, Debug, PartialEq)]
49#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
50pub enum PoseEstimationMode {
51 Fast,
53 Accurate,
59}
60
61#[derive(Clone, Copy, Debug, PartialEq)]
67#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
68pub struct DetectorConfig {
69 pub threshold_tile_size: usize,
73 pub threshold_min_range: u8,
76
77 pub enable_bilateral: bool,
80 pub bilateral_sigma_space: f32,
82 pub bilateral_sigma_color: f32,
85
86 pub enable_sharpening: bool,
88
89 pub enable_adaptive_window: bool,
91 pub threshold_min_radius: usize,
93 pub threshold_max_radius: usize,
95 pub adaptive_threshold_constant: i16,
97 pub adaptive_threshold_gradient_threshold: u8,
99
100 pub quad_min_area: u32,
103 pub quad_max_aspect_ratio: f32,
105 pub quad_min_fill_ratio: f32,
107 pub quad_max_fill_ratio: f32,
109 pub quad_min_edge_length: f64,
111 pub quad_min_edge_score: f64,
113 pub subpixel_refinement_sigma: f64,
115 pub segmentation_margin: i16,
117 pub segmentation_connectivity: SegmentationConnectivity,
119 pub upscale_factor: usize,
123
124 pub decimation: usize,
126
127 pub nthreads: usize,
129
130 pub decoder_min_contrast: f64,
135 pub refinement_mode: CornerRefinementMode,
137 pub decode_mode: DecodeMode,
139 pub max_hamming_error: u32,
142
143 pub huber_delta_px: f64,
148
149 pub tikhonov_alpha_max: f64,
153
154 pub sigma_n_sq: f64,
157
158 pub structure_tensor_radius: u8,
162}
163
164impl Default for DetectorConfig {
165 fn default() -> Self {
166 Self {
167 threshold_tile_size: 8,
168 threshold_min_range: 10,
169 enable_bilateral: false,
170 bilateral_sigma_space: 0.8,
171 bilateral_sigma_color: 30.0,
172 enable_sharpening: false,
173 enable_adaptive_window: false,
174 threshold_min_radius: 2,
175 threshold_max_radius: 15,
176 adaptive_threshold_constant: 0,
177 adaptive_threshold_gradient_threshold: 10,
178 quad_min_area: 16,
179 quad_max_aspect_ratio: 10.0,
180 quad_min_fill_ratio: 0.10,
181 quad_max_fill_ratio: 0.98,
182 quad_min_edge_length: 4.0,
183 quad_min_edge_score: 4.0,
184 subpixel_refinement_sigma: 0.6,
185
186 segmentation_margin: 1,
187 segmentation_connectivity: SegmentationConnectivity::Eight,
188 upscale_factor: 1,
189 decimation: 1,
190 nthreads: 0,
191 decoder_min_contrast: 20.0,
192 refinement_mode: CornerRefinementMode::Erf,
193 decode_mode: DecodeMode::Hard,
194 max_hamming_error: 2,
195 huber_delta_px: 1.5,
196 tikhonov_alpha_max: 0.25,
197 sigma_n_sq: 4.0,
198 structure_tensor_radius: 2,
199 }
200 }
201}
202
203impl DetectorConfig {
204 #[must_use]
206 pub fn builder() -> DetectorConfigBuilder {
207 DetectorConfigBuilder::default()
208 }
209
210 pub fn validate(&self) -> Result<(), crate::error::ConfigError> {
216 use crate::error::ConfigError;
217
218 if self.threshold_tile_size < 2 {
219 return Err(ConfigError::TileSizeTooSmall(self.threshold_tile_size));
220 }
221 if self.decimation < 1 {
222 return Err(ConfigError::InvalidDecimation(self.decimation));
223 }
224 if self.upscale_factor < 1 {
225 return Err(ConfigError::InvalidUpscaleFactor(self.upscale_factor));
226 }
227 if self.quad_min_fill_ratio < 0.0
228 || self.quad_max_fill_ratio > 1.0
229 || self.quad_min_fill_ratio >= self.quad_max_fill_ratio
230 {
231 return Err(ConfigError::InvalidFillRatio {
232 min: self.quad_min_fill_ratio,
233 max: self.quad_max_fill_ratio,
234 });
235 }
236 if self.quad_min_edge_length <= 0.0 {
237 return Err(ConfigError::InvalidEdgeLength(self.quad_min_edge_length));
238 }
239 Ok(())
240 }
241
242 #[must_use]
249 pub fn production_default() -> Self {
250 Self::builder()
251 .refinement_mode(CornerRefinementMode::Erf)
252 .enable_sharpening(true)
253 .threshold_tile_size(8)
254 .build()
255 }
256
257 #[must_use]
261 pub fn fast_default() -> Self {
262 Self::builder()
263 .refinement_mode(CornerRefinementMode::Edge)
264 .enable_sharpening(false)
265 .threshold_tile_size(8)
266 .build()
267 }
268}
269
270#[derive(Default)]
272pub struct DetectorConfigBuilder {
273 threshold_tile_size: Option<usize>,
274 threshold_min_range: Option<u8>,
275 enable_bilateral: Option<bool>,
276 bilateral_sigma_space: Option<f32>,
277 bilateral_sigma_color: Option<f32>,
278 enable_sharpening: Option<bool>,
279 enable_adaptive_window: Option<bool>,
280 threshold_min_radius: Option<usize>,
281 threshold_max_radius: Option<usize>,
282 adaptive_threshold_constant: Option<i16>,
283 adaptive_threshold_gradient_threshold: Option<u8>,
284 quad_min_area: Option<u32>,
285 quad_max_aspect_ratio: Option<f32>,
286 quad_min_fill_ratio: Option<f32>,
287 quad_max_fill_ratio: Option<f32>,
288 quad_min_edge_length: Option<f64>,
289 pub quad_min_edge_score: Option<f64>,
291 pub subpixel_refinement_sigma: Option<f64>,
293 pub segmentation_margin: Option<i16>,
295 pub segmentation_connectivity: Option<SegmentationConnectivity>,
297 pub upscale_factor: Option<usize>,
299 pub decoder_min_contrast: Option<f64>,
301 pub refinement_mode: Option<CornerRefinementMode>,
303 pub decode_mode: Option<DecodeMode>,
305 pub max_hamming_error: Option<u32>,
307}
308
309impl DetectorConfigBuilder {
310 #[must_use]
312 pub fn threshold_tile_size(mut self, size: usize) -> Self {
313 self.threshold_tile_size = Some(size);
314 self
315 }
316
317 #[must_use]
319 pub fn threshold_min_range(mut self, range: u8) -> Self {
320 self.threshold_min_range = Some(range);
321 self
322 }
323
324 #[must_use]
326 pub fn quad_min_area(mut self, area: u32) -> Self {
327 self.quad_min_area = Some(area);
328 self
329 }
330
331 #[must_use]
333 pub fn quad_max_aspect_ratio(mut self, ratio: f32) -> Self {
334 self.quad_max_aspect_ratio = Some(ratio);
335 self
336 }
337
338 #[must_use]
340 pub fn quad_min_fill_ratio(mut self, ratio: f32) -> Self {
341 self.quad_min_fill_ratio = Some(ratio);
342 self
343 }
344
345 #[must_use]
347 pub fn quad_max_fill_ratio(mut self, ratio: f32) -> Self {
348 self.quad_max_fill_ratio = Some(ratio);
349 self
350 }
351
352 #[must_use]
354 pub fn quad_min_edge_length(mut self, length: f64) -> Self {
355 self.quad_min_edge_length = Some(length);
356 self
357 }
358
359 #[must_use]
361 pub fn quad_min_edge_score(mut self, score: f64) -> Self {
362 self.quad_min_edge_score = Some(score);
363 self
364 }
365
366 #[must_use]
368 pub fn enable_bilateral(mut self, enable: bool) -> Self {
369 self.enable_bilateral = Some(enable);
370 self
371 }
372
373 #[must_use]
375 pub fn bilateral_sigma_space(mut self, sigma: f32) -> Self {
376 self.bilateral_sigma_space = Some(sigma);
377 self
378 }
379
380 #[must_use]
382 pub fn bilateral_sigma_color(mut self, sigma: f32) -> Self {
383 self.bilateral_sigma_color = Some(sigma);
384 self
385 }
386
387 #[must_use]
389 pub fn enable_sharpening(mut self, enable: bool) -> Self {
390 self.enable_sharpening = Some(enable);
391 self
392 }
393
394 #[must_use]
396 pub fn enable_adaptive_window(mut self, enable: bool) -> Self {
397 self.enable_adaptive_window = Some(enable);
398 self
399 }
400
401 #[must_use]
403 pub fn threshold_min_radius(mut self, radius: usize) -> Self {
404 self.threshold_min_radius = Some(radius);
405 self
406 }
407
408 #[must_use]
410 pub fn threshold_max_radius(mut self, radius: usize) -> Self {
411 self.threshold_max_radius = Some(radius);
412 self
413 }
414
415 #[must_use]
417 pub fn adaptive_threshold_constant(mut self, c: i16) -> Self {
418 self.adaptive_threshold_constant = Some(c);
419 self
420 }
421
422 #[must_use]
424 pub fn adaptive_threshold_gradient_threshold(mut self, threshold: u8) -> Self {
425 self.adaptive_threshold_gradient_threshold = Some(threshold);
426 self
427 }
428
429 #[must_use]
431 pub fn build(self) -> DetectorConfig {
432 let d = DetectorConfig::default();
433 DetectorConfig {
434 threshold_tile_size: self.threshold_tile_size.unwrap_or(d.threshold_tile_size),
435 threshold_min_range: self.threshold_min_range.unwrap_or(d.threshold_min_range),
436 enable_bilateral: self.enable_bilateral.unwrap_or(d.enable_bilateral),
437 bilateral_sigma_space: self
438 .bilateral_sigma_space
439 .unwrap_or(d.bilateral_sigma_space),
440 bilateral_sigma_color: self
441 .bilateral_sigma_color
442 .unwrap_or(d.bilateral_sigma_color),
443 enable_sharpening: self.enable_sharpening.unwrap_or(d.enable_sharpening),
444 enable_adaptive_window: self
445 .enable_adaptive_window
446 .unwrap_or(d.enable_adaptive_window),
447 threshold_min_radius: self.threshold_min_radius.unwrap_or(d.threshold_min_radius),
448 threshold_max_radius: self.threshold_max_radius.unwrap_or(d.threshold_max_radius),
449 adaptive_threshold_constant: self
450 .adaptive_threshold_constant
451 .unwrap_or(d.adaptive_threshold_constant),
452 adaptive_threshold_gradient_threshold: self
453 .adaptive_threshold_gradient_threshold
454 .unwrap_or(d.adaptive_threshold_gradient_threshold),
455 quad_min_area: self.quad_min_area.unwrap_or(d.quad_min_area),
456 quad_max_aspect_ratio: self
457 .quad_max_aspect_ratio
458 .unwrap_or(d.quad_max_aspect_ratio),
459 quad_min_fill_ratio: self.quad_min_fill_ratio.unwrap_or(d.quad_min_fill_ratio),
460 quad_max_fill_ratio: self.quad_max_fill_ratio.unwrap_or(d.quad_max_fill_ratio),
461 quad_min_edge_length: self.quad_min_edge_length.unwrap_or(d.quad_min_edge_length),
462 quad_min_edge_score: self.quad_min_edge_score.unwrap_or(d.quad_min_edge_score),
463 subpixel_refinement_sigma: self
464 .subpixel_refinement_sigma
465 .unwrap_or(d.subpixel_refinement_sigma),
466 segmentation_margin: self.segmentation_margin.unwrap_or(d.segmentation_margin),
467 segmentation_connectivity: self
468 .segmentation_connectivity
469 .unwrap_or(d.segmentation_connectivity),
470 upscale_factor: self.upscale_factor.unwrap_or(d.upscale_factor),
471 decimation: 1, nthreads: 0, decoder_min_contrast: self.decoder_min_contrast.unwrap_or(d.decoder_min_contrast),
474 refinement_mode: self.refinement_mode.unwrap_or(d.refinement_mode),
475 decode_mode: self.decode_mode.unwrap_or(d.decode_mode),
476 max_hamming_error: self.max_hamming_error.unwrap_or(d.max_hamming_error),
477 huber_delta_px: d.huber_delta_px,
478 tikhonov_alpha_max: d.tikhonov_alpha_max,
479 sigma_n_sq: d.sigma_n_sq,
480 structure_tensor_radius: d.structure_tensor_radius,
481 }
482 }
483
484 pub fn validated_build(self) -> Result<DetectorConfig, crate::error::ConfigError> {
490 let config = self.build();
491 config.validate()?;
492 Ok(config)
493 }
494
495 #[must_use]
497 pub fn segmentation_connectivity(mut self, connectivity: SegmentationConnectivity) -> Self {
498 self.segmentation_connectivity = Some(connectivity);
499 self
500 }
501
502 #[must_use]
504 pub fn segmentation_margin(mut self, margin: i16) -> Self {
505 self.segmentation_margin = Some(margin);
506 self
507 }
508
509 #[must_use]
511 pub fn upscale_factor(mut self, factor: usize) -> Self {
512 self.upscale_factor = Some(factor);
513 self
514 }
515
516 #[must_use]
519 pub fn decoder_min_contrast(mut self, contrast: f64) -> Self {
520 self.decoder_min_contrast = Some(contrast);
521 self
522 }
523
524 #[must_use]
526 pub fn refinement_mode(mut self, mode: CornerRefinementMode) -> Self {
527 self.refinement_mode = Some(mode);
528 self
529 }
530
531 #[must_use]
533 pub fn decode_mode(mut self, mode: DecodeMode) -> Self {
534 self.decode_mode = Some(mode);
535 self
536 }
537
538 #[must_use]
540 pub fn max_hamming_error(mut self, errors: u32) -> Self {
541 self.max_hamming_error = Some(errors);
542 self
543 }
544}
545
546#[derive(Clone, Copy, Debug, PartialEq, Eq, Hash)]
552#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
553pub enum TagFamily {
554 AprilTag16h5,
556 AprilTag36h11,
558 ArUco4x4_50,
560 ArUco4x4_100,
562}
563
564impl TagFamily {
565 #[must_use]
567 pub const fn all() -> &'static [TagFamily] {
568 &[
569 TagFamily::AprilTag16h5,
570 TagFamily::AprilTag36h11,
571 TagFamily::ArUco4x4_50,
572 TagFamily::ArUco4x4_100,
573 ]
574 }
575}
576
577#[derive(Clone, Debug, PartialEq)]
582#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
583pub struct DetectOptions {
584 pub families: Vec<TagFamily>,
586 pub intrinsics: Option<crate::pose::CameraIntrinsics>,
588 pub tag_size: Option<f64>,
590 pub decimation: usize,
593 pub pose_estimation_mode: PoseEstimationMode,
595}
596
597impl Default for DetectOptions {
598 fn default() -> Self {
599 Self {
600 families: Vec::new(),
601 intrinsics: None,
602 tag_size: None,
603 decimation: 1,
604 pose_estimation_mode: PoseEstimationMode::Fast,
605 }
606 }
607}
608
609impl DetectOptions {
610 #[must_use]
612 pub fn builder() -> DetectOptionsBuilder {
613 DetectOptionsBuilder::default()
614 }
615 #[must_use]
617 pub fn with_families(families: &[TagFamily]) -> Self {
618 Self {
619 families: families.to_vec(),
620 intrinsics: None,
621 tag_size: None,
622 decimation: 1,
623 pose_estimation_mode: PoseEstimationMode::Fast,
624 }
625 }
626
627 #[must_use]
629 pub fn all_families() -> Self {
630 Self {
631 families: TagFamily::all().to_vec(),
632 intrinsics: None,
633 tag_size: None,
634 decimation: 1,
635 pose_estimation_mode: PoseEstimationMode::Fast,
636 }
637 }
638}
639
640pub struct DetectOptionsBuilder {
642 families: Vec<TagFamily>,
643 intrinsics: Option<crate::pose::CameraIntrinsics>,
644 tag_size: Option<f64>,
645 decimation: usize,
646 pose_estimation_mode: PoseEstimationMode,
647}
648
649impl Default for DetectOptionsBuilder {
650 fn default() -> Self {
651 Self {
652 families: Vec::new(),
653 intrinsics: None,
654 tag_size: None,
655 decimation: 1,
656 pose_estimation_mode: PoseEstimationMode::Fast,
657 }
658 }
659}
660
661impl DetectOptionsBuilder {
662 #[must_use]
664 pub fn families(mut self, families: &[TagFamily]) -> Self {
665 self.families = families.to_vec();
666 self
667 }
668
669 #[must_use]
671 pub fn intrinsics(mut self, fx: f64, fy: f64, cx: f64, cy: f64) -> Self {
672 self.intrinsics = Some(crate::pose::CameraIntrinsics::new(fx, fy, cx, cy));
673 self
674 }
675
676 #[must_use]
678 pub fn tag_size(mut self, size: f64) -> Self {
679 self.tag_size = Some(size);
680 self
681 }
682
683 #[must_use]
685 pub fn decimation(mut self, decimation: usize) -> Self {
686 self.decimation = decimation.max(1);
687 self
688 }
689
690 #[must_use]
692 pub fn pose_estimation_mode(mut self, mode: PoseEstimationMode) -> Self {
693 self.pose_estimation_mode = mode;
694 self
695 }
696
697 #[must_use]
699 pub fn build(self) -> DetectOptions {
700 DetectOptions {
701 families: self.families,
702 intrinsics: self.intrinsics,
703 tag_size: self.tag_size,
704 decimation: self.decimation,
705 pose_estimation_mode: self.pose_estimation_mode,
706 }
707 }
708}
709
710#[cfg(test)]
711mod tests {
712 use super::*;
713
714 #[test]
715 #[allow(clippy::float_cmp)]
716 fn test_detector_config_builder() {
717 let config = DetectorConfig::builder()
718 .threshold_tile_size(16)
719 .quad_min_area(1000)
720 .build();
721 assert_eq!(config.threshold_tile_size, 16);
722 assert_eq!(config.quad_min_area, 1000);
723 assert_eq!(config.threshold_min_range, 10);
725 assert_eq!(config.quad_min_edge_score, 4.0);
726 assert_eq!(config.max_hamming_error, 2);
727 }
728
729 #[test]
730 #[allow(clippy::float_cmp)]
731 fn test_detector_config_defaults() {
732 let config = DetectorConfig::default();
733 assert_eq!(config.threshold_tile_size, 8);
734 assert_eq!(config.quad_min_area, 16);
735 assert_eq!(config.quad_min_edge_length, 4.0);
736 assert_eq!(config.max_hamming_error, 2);
737 }
738
739 #[test]
740 fn test_detect_options_families() {
741 let opt = DetectOptions::with_families(&[TagFamily::AprilTag36h11]);
742 assert_eq!(opt.families.len(), 1);
743 assert_eq!(opt.families[0], TagFamily::AprilTag36h11);
744 }
745
746 #[test]
747 fn test_detect_options_default_empty() {
748 let opt = DetectOptions::default();
749 assert!(opt.families.is_empty());
750 }
751
752 #[test]
753 fn test_all_families() {
754 let opt = DetectOptions::all_families();
755 assert_eq!(opt.families.len(), 4);
756 }
757
758 #[test]
759 fn test_default_config_is_valid() {
760 let config = DetectorConfig::default();
761 assert!(config.validate().is_ok());
762 }
763
764 #[test]
765 fn test_production_config_is_valid() {
766 let config = DetectorConfig::production_default();
767 assert!(config.validate().is_ok());
768 }
769
770 #[test]
771 fn test_validation_rejects_bad_tile_size() {
772 let config = DetectorConfig {
773 threshold_tile_size: 1,
774 ..DetectorConfig::default()
775 };
776 assert!(config.validate().is_err());
777 }
778
779 #[test]
780 fn test_validation_rejects_bad_fill_ratio() {
781 let config = DetectorConfig {
782 quad_min_fill_ratio: 0.9,
783 quad_max_fill_ratio: 0.5,
784 ..DetectorConfig::default()
785 };
786 assert!(config.validate().is_err());
787 }
788
789 #[test]
790 fn test_validation_rejects_negative_edge_length() {
791 let config = DetectorConfig {
792 quad_min_edge_length: -1.0,
793 ..DetectorConfig::default()
794 };
795 assert!(config.validate().is_err());
796 }
797
798 #[test]
799 fn test_validated_build_catches_errors() {
800 let result = DetectorConfig::builder()
801 .threshold_tile_size(0)
802 .validated_build();
803 assert!(result.is_err());
804 }
805}