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 Gwlf,
37}
38
39#[derive(Clone, Copy, Debug, PartialEq)]
41#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
42pub enum DecodeMode {
43 Hard,
45 Soft,
47}
48
49#[derive(Clone, Copy, Debug, PartialEq)]
51#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
52pub enum PoseEstimationMode {
53 Fast,
55 Accurate,
61}
62
63#[derive(Clone, Copy, Debug, PartialEq, Default)]
65#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
66pub enum QuadExtractionMode {
67 #[default]
69 ContourRdp,
70 EdLines,
72}
73
74#[derive(Clone, Copy, Debug, PartialEq)]
80#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
81pub struct DetectorConfig {
82 pub threshold_tile_size: usize,
86 pub threshold_min_range: u8,
89
90 pub enable_bilateral: bool,
93 pub bilateral_sigma_space: f32,
95 pub bilateral_sigma_color: f32,
98
99 pub enable_sharpening: bool,
101
102 pub enable_adaptive_window: bool,
104 pub threshold_min_radius: usize,
106 pub threshold_max_radius: usize,
108 pub adaptive_threshold_constant: i16,
110 pub adaptive_threshold_gradient_threshold: u8,
112
113 pub quad_min_area: u32,
116 pub quad_max_aspect_ratio: f32,
118 pub quad_min_fill_ratio: f32,
120 pub quad_max_fill_ratio: f32,
122 pub quad_min_edge_length: f64,
124 pub quad_min_edge_score: f64,
126 pub subpixel_refinement_sigma: f64,
128 pub segmentation_margin: i16,
130 pub segmentation_connectivity: SegmentationConnectivity,
132 pub upscale_factor: usize,
136
137 pub decimation: usize,
139
140 pub nthreads: usize,
142
143 pub decoder_min_contrast: f64,
148 pub refinement_mode: CornerRefinementMode,
150 pub decode_mode: DecodeMode,
152 pub max_hamming_error: u32,
155
156 pub huber_delta_px: f64,
161
162 pub tikhonov_alpha_max: f64,
166
167 pub sigma_n_sq: f64,
170
171 pub structure_tensor_radius: u8,
175
176 pub gwlf_transversal_alpha: f64,
179
180 pub quad_max_elongation: f64,
183
184 pub quad_min_density: f64,
187
188 pub quad_extraction_mode: QuadExtractionMode,
190}
191
192impl Default for DetectorConfig {
193 fn default() -> Self {
194 Self {
195 threshold_tile_size: 8,
196 threshold_min_range: 10,
197 enable_bilateral: false,
198 bilateral_sigma_space: 0.8,
199 bilateral_sigma_color: 30.0,
200 enable_sharpening: false,
201 enable_adaptive_window: false,
202 threshold_min_radius: 2,
203 threshold_max_radius: 15,
204 adaptive_threshold_constant: 0,
205 adaptive_threshold_gradient_threshold: 10,
206 quad_min_area: 16,
207 quad_max_aspect_ratio: 10.0,
208 quad_min_fill_ratio: 0.10,
209 quad_max_fill_ratio: 0.98,
210 quad_min_edge_length: 4.0,
211 quad_min_edge_score: 4.0,
212 subpixel_refinement_sigma: 0.6,
213
214 segmentation_margin: 1,
215 segmentation_connectivity: SegmentationConnectivity::Eight,
216 upscale_factor: 1,
217 decimation: 1,
218 nthreads: 0,
219 decoder_min_contrast: 20.0,
220 refinement_mode: CornerRefinementMode::Erf,
221 decode_mode: DecodeMode::Hard,
222 max_hamming_error: 2,
223 huber_delta_px: 1.5,
224 tikhonov_alpha_max: 0.25,
225 sigma_n_sq: 4.0,
226 structure_tensor_radius: 2,
227 gwlf_transversal_alpha: 0.01,
228 quad_max_elongation: 0.0,
229 quad_min_density: 0.0,
230 quad_extraction_mode: QuadExtractionMode::ContourRdp,
231 }
232 }
233}
234
235impl DetectorConfig {
236 #[must_use]
238 pub fn builder() -> DetectorConfigBuilder {
239 DetectorConfigBuilder::default()
240 }
241
242 pub fn validate(&self) -> Result<(), crate::error::ConfigError> {
248 use crate::error::ConfigError;
249
250 if self.threshold_tile_size < 2 {
251 return Err(ConfigError::TileSizeTooSmall(self.threshold_tile_size));
252 }
253 if self.decimation < 1 {
254 return Err(ConfigError::InvalidDecimation(self.decimation));
255 }
256 if self.upscale_factor < 1 {
257 return Err(ConfigError::InvalidUpscaleFactor(self.upscale_factor));
258 }
259 if self.quad_min_fill_ratio < 0.0
260 || self.quad_max_fill_ratio > 1.0
261 || self.quad_min_fill_ratio >= self.quad_max_fill_ratio
262 {
263 return Err(ConfigError::InvalidFillRatio {
264 min: self.quad_min_fill_ratio,
265 max: self.quad_max_fill_ratio,
266 });
267 }
268 if self.quad_min_edge_length <= 0.0 {
269 return Err(ConfigError::InvalidEdgeLength(self.quad_min_edge_length));
270 }
271 Ok(())
272 }
273
274 #[must_use]
281 pub fn production_default() -> Self {
282 Self::builder()
283 .refinement_mode(CornerRefinementMode::Erf)
284 .enable_sharpening(true)
285 .threshold_tile_size(8)
286 .quad_max_elongation(20.0)
287 .quad_min_density(0.15)
288 .build()
289 }
290
291 #[must_use]
305 pub fn sota_pure_tags_default() -> Self {
306 Self::builder()
307 .refinement_mode(CornerRefinementMode::Erf)
308 .enable_sharpening(true)
309 .threshold_tile_size(8)
310 .quad_max_elongation(20.0)
311 .quad_min_density(0.15)
312 .decode_mode(DecodeMode::Soft)
313 .build()
314 }
315
316 #[must_use]
334 pub fn sota_checkerboard_default() -> Self {
335 Self::builder()
336 .refinement_mode(CornerRefinementMode::Erf)
337 .enable_sharpening(false)
338 .threshold_tile_size(8)
339 .quad_max_elongation(20.0)
340 .quad_min_density(0.15)
341 .segmentation_connectivity(SegmentationConnectivity::Four)
342 .decoder_min_contrast(10.0)
343 .quad_min_edge_score(2.0)
344 .decode_mode(DecodeMode::Soft)
345 .build()
346 }
347
348 #[must_use]
352 pub fn fast_default() -> Self {
353 Self::builder()
354 .refinement_mode(CornerRefinementMode::Edge)
355 .enable_sharpening(false)
356 .threshold_tile_size(8)
357 .build()
358 }
359
360 #[must_use]
381 pub fn sota_metrology_default() -> Self {
382 Self::builder()
383 .quad_extraction_mode(QuadExtractionMode::EdLines)
384 .refinement_mode(CornerRefinementMode::None)
385 .enable_sharpening(false)
386 .enable_bilateral(false)
387 .quad_max_elongation(20.0)
388 .quad_min_density(0.15)
389 .decode_mode(DecodeMode::Hard)
390 .threshold_tile_size(8)
391 .build()
392 }
393}
394
395#[derive(Default)]
397pub struct DetectorConfigBuilder {
398 threshold_tile_size: Option<usize>,
399 threshold_min_range: Option<u8>,
400 enable_bilateral: Option<bool>,
401 bilateral_sigma_space: Option<f32>,
402 bilateral_sigma_color: Option<f32>,
403 enable_sharpening: Option<bool>,
404 enable_adaptive_window: Option<bool>,
405 threshold_min_radius: Option<usize>,
406 threshold_max_radius: Option<usize>,
407 adaptive_threshold_constant: Option<i16>,
408 adaptive_threshold_gradient_threshold: Option<u8>,
409 quad_min_area: Option<u32>,
410 quad_max_aspect_ratio: Option<f32>,
411 quad_min_fill_ratio: Option<f32>,
412 quad_max_fill_ratio: Option<f32>,
413 quad_min_edge_length: Option<f64>,
414 pub quad_min_edge_score: Option<f64>,
416 pub subpixel_refinement_sigma: Option<f64>,
418 pub segmentation_margin: Option<i16>,
420 pub segmentation_connectivity: Option<SegmentationConnectivity>,
422 pub upscale_factor: Option<usize>,
424 pub decoder_min_contrast: Option<f64>,
426 pub refinement_mode: Option<CornerRefinementMode>,
428 pub decode_mode: Option<DecodeMode>,
430 pub max_hamming_error: Option<u32>,
432 pub gwlf_transversal_alpha: Option<f64>,
434 pub quad_max_elongation: Option<f64>,
436 pub quad_min_density: Option<f64>,
438 pub quad_extraction_mode: Option<QuadExtractionMode>,
440 pub huber_delta_px: Option<f64>,
442 pub tikhonov_alpha_max: Option<f64>,
444 pub sigma_n_sq: Option<f64>,
446 pub structure_tensor_radius: Option<u8>,
448}
449
450impl DetectorConfigBuilder {
451 #[must_use]
453 pub fn threshold_tile_size(mut self, size: usize) -> Self {
454 self.threshold_tile_size = Some(size);
455 self
456 }
457
458 #[must_use]
460 pub fn threshold_min_range(mut self, range: u8) -> Self {
461 self.threshold_min_range = Some(range);
462 self
463 }
464
465 #[must_use]
467 pub fn quad_min_area(mut self, area: u32) -> Self {
468 self.quad_min_area = Some(area);
469 self
470 }
471
472 #[must_use]
474 pub fn quad_max_aspect_ratio(mut self, ratio: f32) -> Self {
475 self.quad_max_aspect_ratio = Some(ratio);
476 self
477 }
478
479 #[must_use]
481 pub fn quad_min_fill_ratio(mut self, ratio: f32) -> Self {
482 self.quad_min_fill_ratio = Some(ratio);
483 self
484 }
485
486 #[must_use]
488 pub fn quad_max_fill_ratio(mut self, ratio: f32) -> Self {
489 self.quad_max_fill_ratio = Some(ratio);
490 self
491 }
492
493 #[must_use]
495 pub fn quad_min_edge_length(mut self, length: f64) -> Self {
496 self.quad_min_edge_length = Some(length);
497 self
498 }
499
500 #[must_use]
502 pub fn quad_min_edge_score(mut self, score: f64) -> Self {
503 self.quad_min_edge_score = Some(score);
504 self
505 }
506
507 #[must_use]
509 pub fn enable_bilateral(mut self, enable: bool) -> Self {
510 self.enable_bilateral = Some(enable);
511 self
512 }
513
514 #[must_use]
516 pub fn bilateral_sigma_space(mut self, sigma: f32) -> Self {
517 self.bilateral_sigma_space = Some(sigma);
518 self
519 }
520
521 #[must_use]
523 pub fn bilateral_sigma_color(mut self, sigma: f32) -> Self {
524 self.bilateral_sigma_color = Some(sigma);
525 self
526 }
527
528 #[must_use]
530 pub fn enable_sharpening(mut self, enable: bool) -> Self {
531 self.enable_sharpening = Some(enable);
532 self
533 }
534
535 #[must_use]
537 pub fn enable_adaptive_window(mut self, enable: bool) -> Self {
538 self.enable_adaptive_window = Some(enable);
539 self
540 }
541
542 #[must_use]
544 pub fn threshold_min_radius(mut self, radius: usize) -> Self {
545 self.threshold_min_radius = Some(radius);
546 self
547 }
548
549 #[must_use]
551 pub fn threshold_max_radius(mut self, radius: usize) -> Self {
552 self.threshold_max_radius = Some(radius);
553 self
554 }
555
556 #[must_use]
558 pub fn adaptive_threshold_constant(mut self, c: i16) -> Self {
559 self.adaptive_threshold_constant = Some(c);
560 self
561 }
562
563 #[must_use]
565 pub fn adaptive_threshold_gradient_threshold(mut self, threshold: u8) -> Self {
566 self.adaptive_threshold_gradient_threshold = Some(threshold);
567 self
568 }
569
570 #[must_use]
572 pub fn build(self) -> DetectorConfig {
573 let d = DetectorConfig::default();
574 DetectorConfig {
575 threshold_tile_size: self.threshold_tile_size.unwrap_or(d.threshold_tile_size),
576 threshold_min_range: self.threshold_min_range.unwrap_or(d.threshold_min_range),
577 enable_bilateral: self.enable_bilateral.unwrap_or(d.enable_bilateral),
578 bilateral_sigma_space: self
579 .bilateral_sigma_space
580 .unwrap_or(d.bilateral_sigma_space),
581 bilateral_sigma_color: self
582 .bilateral_sigma_color
583 .unwrap_or(d.bilateral_sigma_color),
584 enable_sharpening: self.enable_sharpening.unwrap_or(d.enable_sharpening),
585 enable_adaptive_window: self
586 .enable_adaptive_window
587 .unwrap_or(d.enable_adaptive_window),
588 threshold_min_radius: self.threshold_min_radius.unwrap_or(d.threshold_min_radius),
589 threshold_max_radius: self.threshold_max_radius.unwrap_or(d.threshold_max_radius),
590 adaptive_threshold_constant: self
591 .adaptive_threshold_constant
592 .unwrap_or(d.adaptive_threshold_constant),
593 adaptive_threshold_gradient_threshold: self
594 .adaptive_threshold_gradient_threshold
595 .unwrap_or(d.adaptive_threshold_gradient_threshold),
596 quad_min_area: self.quad_min_area.unwrap_or(d.quad_min_area),
597 quad_max_aspect_ratio: self
598 .quad_max_aspect_ratio
599 .unwrap_or(d.quad_max_aspect_ratio),
600 quad_min_fill_ratio: self.quad_min_fill_ratio.unwrap_or(d.quad_min_fill_ratio),
601 quad_max_fill_ratio: self.quad_max_fill_ratio.unwrap_or(d.quad_max_fill_ratio),
602 quad_min_edge_length: self.quad_min_edge_length.unwrap_or(d.quad_min_edge_length),
603 quad_min_edge_score: self.quad_min_edge_score.unwrap_or(d.quad_min_edge_score),
604 subpixel_refinement_sigma: self
605 .subpixel_refinement_sigma
606 .unwrap_or(d.subpixel_refinement_sigma),
607 segmentation_margin: self.segmentation_margin.unwrap_or(d.segmentation_margin),
608 segmentation_connectivity: self
609 .segmentation_connectivity
610 .unwrap_or(d.segmentation_connectivity),
611 upscale_factor: self.upscale_factor.unwrap_or(d.upscale_factor),
612 decimation: 1, nthreads: 0, decoder_min_contrast: self.decoder_min_contrast.unwrap_or(d.decoder_min_contrast),
615 refinement_mode: self.refinement_mode.unwrap_or(d.refinement_mode),
616 decode_mode: self.decode_mode.unwrap_or(d.decode_mode),
617 max_hamming_error: self.max_hamming_error.unwrap_or(d.max_hamming_error),
618 huber_delta_px: self.huber_delta_px.unwrap_or(d.huber_delta_px),
619 tikhonov_alpha_max: self.tikhonov_alpha_max.unwrap_or(d.tikhonov_alpha_max),
620 sigma_n_sq: self.sigma_n_sq.unwrap_or(d.sigma_n_sq),
621 structure_tensor_radius: self
622 .structure_tensor_radius
623 .unwrap_or(d.structure_tensor_radius),
624 gwlf_transversal_alpha: self
625 .gwlf_transversal_alpha
626 .unwrap_or(d.gwlf_transversal_alpha),
627 quad_max_elongation: self.quad_max_elongation.unwrap_or(d.quad_max_elongation),
628 quad_min_density: self.quad_min_density.unwrap_or(d.quad_min_density),
629 quad_extraction_mode: self.quad_extraction_mode.unwrap_or(d.quad_extraction_mode),
630 }
631 }
632
633 pub fn validated_build(self) -> Result<DetectorConfig, crate::error::ConfigError> {
639 let config = self.build();
640 config.validate()?;
641 Ok(config)
642 }
643
644 #[must_use]
646 pub fn segmentation_connectivity(mut self, connectivity: SegmentationConnectivity) -> Self {
647 self.segmentation_connectivity = Some(connectivity);
648 self
649 }
650
651 #[must_use]
653 pub fn segmentation_margin(mut self, margin: i16) -> Self {
654 self.segmentation_margin = Some(margin);
655 self
656 }
657
658 #[must_use]
660 pub fn upscale_factor(mut self, factor: usize) -> Self {
661 self.upscale_factor = Some(factor);
662 self
663 }
664
665 #[must_use]
668 pub fn decoder_min_contrast(mut self, contrast: f64) -> Self {
669 self.decoder_min_contrast = Some(contrast);
670 self
671 }
672
673 #[must_use]
675 pub fn refinement_mode(mut self, mode: CornerRefinementMode) -> Self {
676 self.refinement_mode = Some(mode);
677 self
678 }
679
680 #[must_use]
682 pub fn decode_mode(mut self, mode: DecodeMode) -> Self {
683 self.decode_mode = Some(mode);
684 self
685 }
686
687 #[must_use]
689 pub fn max_hamming_error(mut self, errors: u32) -> Self {
690 self.max_hamming_error = Some(errors);
691 self
692 }
693
694 #[must_use]
696 pub fn gwlf_transversal_alpha(mut self, alpha: f64) -> Self {
697 self.gwlf_transversal_alpha = Some(alpha);
698 self
699 }
700
701 #[must_use]
704 pub fn quad_max_elongation(mut self, max_elongation: f64) -> Self {
705 self.quad_max_elongation = Some(max_elongation);
706 self
707 }
708
709 #[must_use]
712 pub fn quad_min_density(mut self, min_density: f64) -> Self {
713 self.quad_min_density = Some(min_density);
714 self
715 }
716
717 #[must_use]
719 pub fn quad_extraction_mode(mut self, mode: QuadExtractionMode) -> Self {
720 self.quad_extraction_mode = Some(mode);
721 self
722 }
723
724 #[must_use]
726 pub fn huber_delta_px(mut self, delta: f64) -> Self {
727 self.huber_delta_px = Some(delta);
728 self
729 }
730
731 #[must_use]
733 pub fn tikhonov_alpha_max(mut self, alpha: f64) -> Self {
734 self.tikhonov_alpha_max = Some(alpha);
735 self
736 }
737
738 #[must_use]
740 pub fn sigma_n_sq(mut self, sigma_n_sq: f64) -> Self {
741 self.sigma_n_sq = Some(sigma_n_sq);
742 self
743 }
744
745 #[must_use]
747 pub fn structure_tensor_radius(mut self, radius: u8) -> Self {
748 self.structure_tensor_radius = Some(radius);
749 self
750 }
751}
752
753#[derive(Clone, Copy, Debug, PartialEq, Eq, Hash)]
759#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
760pub enum TagFamily {
761 AprilTag16h5,
763 AprilTag36h11,
765 ArUco4x4_50,
767 ArUco4x4_100,
769}
770
771impl TagFamily {
772 #[must_use]
774 pub const fn all() -> &'static [TagFamily] {
775 &[
776 TagFamily::AprilTag16h5,
777 TagFamily::AprilTag36h11,
778 TagFamily::ArUco4x4_50,
779 TagFamily::ArUco4x4_100,
780 ]
781 }
782}
783
784#[derive(Clone, Debug, PartialEq)]
789#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
790pub struct DetectOptions {
791 pub families: Vec<TagFamily>,
793 pub intrinsics: Option<crate::pose::CameraIntrinsics>,
795 pub tag_size: Option<f64>,
797 pub decimation: usize,
800 pub pose_estimation_mode: PoseEstimationMode,
802}
803
804impl Default for DetectOptions {
805 fn default() -> Self {
806 Self {
807 families: Vec::new(),
808 intrinsics: None,
809 tag_size: None,
810 decimation: 1,
811 pose_estimation_mode: PoseEstimationMode::Fast,
812 }
813 }
814}
815
816impl DetectOptions {
817 #[must_use]
819 pub fn builder() -> DetectOptionsBuilder {
820 DetectOptionsBuilder::default()
821 }
822 #[must_use]
824 pub fn with_families(families: &[TagFamily]) -> Self {
825 Self {
826 families: families.to_vec(),
827 intrinsics: None,
828 tag_size: None,
829 decimation: 1,
830 pose_estimation_mode: PoseEstimationMode::Fast,
831 }
832 }
833
834 #[must_use]
836 pub fn all_families() -> Self {
837 Self {
838 families: TagFamily::all().to_vec(),
839 intrinsics: None,
840 tag_size: None,
841 decimation: 1,
842 pose_estimation_mode: PoseEstimationMode::Fast,
843 }
844 }
845}
846
847pub struct DetectOptionsBuilder {
849 families: Vec<TagFamily>,
850 intrinsics: Option<crate::pose::CameraIntrinsics>,
851 tag_size: Option<f64>,
852 decimation: usize,
853 pose_estimation_mode: PoseEstimationMode,
854}
855
856impl Default for DetectOptionsBuilder {
857 fn default() -> Self {
858 Self {
859 families: Vec::new(),
860 intrinsics: None,
861 tag_size: None,
862 decimation: 1,
863 pose_estimation_mode: PoseEstimationMode::Fast,
864 }
865 }
866}
867
868impl DetectOptionsBuilder {
869 #[must_use]
871 pub fn families(mut self, families: &[TagFamily]) -> Self {
872 self.families = families.to_vec();
873 self
874 }
875
876 #[must_use]
878 pub fn intrinsics(mut self, fx: f64, fy: f64, cx: f64, cy: f64) -> Self {
879 self.intrinsics = Some(crate::pose::CameraIntrinsics::new(fx, fy, cx, cy));
880 self
881 }
882
883 #[must_use]
885 pub fn tag_size(mut self, size: f64) -> Self {
886 self.tag_size = Some(size);
887 self
888 }
889
890 #[must_use]
892 pub fn decimation(mut self, decimation: usize) -> Self {
893 self.decimation = decimation.max(1);
894 self
895 }
896
897 #[must_use]
899 pub fn pose_estimation_mode(mut self, mode: PoseEstimationMode) -> Self {
900 self.pose_estimation_mode = mode;
901 self
902 }
903
904 #[must_use]
906 pub fn build(self) -> DetectOptions {
907 DetectOptions {
908 families: self.families,
909 intrinsics: self.intrinsics,
910 tag_size: self.tag_size,
911 decimation: self.decimation,
912 pose_estimation_mode: self.pose_estimation_mode,
913 }
914 }
915}
916
917#[cfg(test)]
918mod tests {
919 use super::*;
920
921 #[test]
922 #[allow(clippy::float_cmp)]
923 fn test_detector_config_builder() {
924 let config = DetectorConfig::builder()
925 .threshold_tile_size(16)
926 .quad_min_area(1000)
927 .build();
928 assert_eq!(config.threshold_tile_size, 16);
929 assert_eq!(config.quad_min_area, 1000);
930 assert_eq!(config.threshold_min_range, 10);
932 assert_eq!(config.quad_min_edge_score, 4.0);
933 assert_eq!(config.max_hamming_error, 2);
934 }
935
936 #[test]
937 #[allow(clippy::float_cmp)]
938 fn test_detector_config_defaults() {
939 let config = DetectorConfig::default();
940 assert_eq!(config.threshold_tile_size, 8);
941 assert_eq!(config.quad_min_area, 16);
942 assert_eq!(config.quad_min_edge_length, 4.0);
943 assert_eq!(config.max_hamming_error, 2);
944 }
945
946 #[test]
947 fn test_detect_options_families() {
948 let opt = DetectOptions::with_families(&[TagFamily::AprilTag36h11]);
949 assert_eq!(opt.families.len(), 1);
950 assert_eq!(opt.families[0], TagFamily::AprilTag36h11);
951 }
952
953 #[test]
954 fn test_detect_options_default_empty() {
955 let opt = DetectOptions::default();
956 assert!(opt.families.is_empty());
957 }
958
959 #[test]
960 fn test_all_families() {
961 let opt = DetectOptions::all_families();
962 assert_eq!(opt.families.len(), 4);
963 }
964
965 #[test]
966 fn test_default_config_is_valid() {
967 let config = DetectorConfig::default();
968 assert!(config.validate().is_ok());
969 }
970
971 #[test]
972 fn test_production_config_is_valid() {
973 let config = DetectorConfig::production_default();
974 assert!(config.validate().is_ok());
975 }
976
977 #[test]
978 fn test_validation_rejects_bad_tile_size() {
979 let config = DetectorConfig {
980 threshold_tile_size: 1,
981 ..DetectorConfig::default()
982 };
983 assert!(config.validate().is_err());
984 }
985
986 #[test]
987 fn test_validation_rejects_bad_fill_ratio() {
988 let config = DetectorConfig {
989 quad_min_fill_ratio: 0.9,
990 quad_max_fill_ratio: 0.5,
991 ..DetectorConfig::default()
992 };
993 assert!(config.validate().is_err());
994 }
995
996 #[test]
997 fn test_validation_rejects_negative_edge_length() {
998 let config = DetectorConfig {
999 quad_min_edge_length: -1.0,
1000 ..DetectorConfig::default()
1001 };
1002 assert!(config.validate().is_err());
1003 }
1004
1005 #[test]
1006 fn test_validated_build_catches_errors() {
1007 let result = DetectorConfig::builder()
1008 .threshold_tile_size(0)
1009 .validated_build();
1010 assert!(result.is_err());
1011 }
1012}