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 Erf,
33 Gwlf,
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, Default)]
63#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
64pub enum QuadExtractionMode {
65 #[default]
67 ContourRdp,
68 EdLines,
70}
71
72#[derive(Clone, Copy, Debug, PartialEq)]
78#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
79pub struct DetectorConfig {
80 pub threshold_tile_size: usize,
84 pub threshold_min_range: u8,
87
88 pub enable_sharpening: bool,
90
91 pub enable_adaptive_window: bool,
93 pub threshold_min_radius: usize,
95 pub threshold_max_radius: usize,
97 pub adaptive_threshold_constant: i16,
99 pub adaptive_threshold_gradient_threshold: u8,
101
102 pub quad_min_area: u32,
105 pub quad_max_aspect_ratio: f32,
107 pub quad_min_fill_ratio: f32,
109 pub quad_max_fill_ratio: f32,
111 pub quad_min_edge_length: f64,
113 pub quad_min_edge_score: f64,
115 pub subpixel_refinement_sigma: f64,
117 pub segmentation_margin: i16,
119 pub segmentation_connectivity: SegmentationConnectivity,
121 pub upscale_factor: usize,
125
126 pub decimation: usize,
128
129 pub nthreads: usize,
131
132 pub decoder_min_contrast: f64,
137 pub refinement_mode: CornerRefinementMode,
139 pub decode_mode: DecodeMode,
141 pub max_hamming_error: u32,
144
145 pub huber_delta_px: f64,
150
151 pub tikhonov_alpha_max: f64,
155
156 pub sigma_n_sq: f64,
159
160 pub structure_tensor_radius: u8,
165
166 pub gwlf_transversal_alpha: f64,
169
170 pub quad_max_elongation: f64,
173
174 pub quad_min_density: f64,
177
178 pub quad_extraction_mode: QuadExtractionMode,
180}
181
182impl Default for DetectorConfig {
183 fn default() -> Self {
184 Self {
185 threshold_tile_size: 8,
186 threshold_min_range: 10,
187 enable_sharpening: false,
188 enable_adaptive_window: false,
189 threshold_min_radius: 2,
190 threshold_max_radius: 15,
191 adaptive_threshold_constant: 0,
192 adaptive_threshold_gradient_threshold: 10,
193 quad_min_area: 16,
194 quad_max_aspect_ratio: 10.0,
195 quad_min_fill_ratio: 0.10,
196 quad_max_fill_ratio: 0.98,
197 quad_min_edge_length: 4.0,
198 quad_min_edge_score: 4.0,
199 subpixel_refinement_sigma: 0.6,
200
201 segmentation_margin: 1,
202 segmentation_connectivity: SegmentationConnectivity::Eight,
203 upscale_factor: 1,
204 decimation: 1,
205 nthreads: 0,
206 decoder_min_contrast: 20.0,
207 refinement_mode: CornerRefinementMode::Erf,
208 decode_mode: DecodeMode::Hard,
209 max_hamming_error: 2,
210 huber_delta_px: 1.5,
211 tikhonov_alpha_max: 0.25,
212 sigma_n_sq: 4.0,
213 structure_tensor_radius: 2,
214 gwlf_transversal_alpha: 0.01,
215 quad_max_elongation: 0.0,
216 quad_min_density: 0.0,
217 quad_extraction_mode: QuadExtractionMode::ContourRdp,
218 }
219 }
220}
221
222impl DetectorConfig {
223 #[must_use]
225 pub fn builder() -> DetectorConfigBuilder {
226 DetectorConfigBuilder::default()
227 }
228
229 pub fn validate(&self) -> Result<(), crate::error::ConfigError> {
235 use crate::error::ConfigError;
236
237 if self.threshold_tile_size < 2 {
238 return Err(ConfigError::TileSizeTooSmall(self.threshold_tile_size));
239 }
240 if self.decimation < 1 {
241 return Err(ConfigError::InvalidDecimation(self.decimation));
242 }
243 if self.upscale_factor < 1 {
244 return Err(ConfigError::InvalidUpscaleFactor(self.upscale_factor));
245 }
246 if self.quad_min_fill_ratio < 0.0
247 || self.quad_max_fill_ratio > 1.0
248 || self.quad_min_fill_ratio >= self.quad_max_fill_ratio
249 {
250 return Err(ConfigError::InvalidFillRatio {
251 min: self.quad_min_fill_ratio,
252 max: self.quad_max_fill_ratio,
253 });
254 }
255 if self.quad_min_edge_length <= 0.0 {
256 return Err(ConfigError::InvalidEdgeLength(self.quad_min_edge_length));
257 }
258 if self.structure_tensor_radius > 8 {
259 return Err(ConfigError::InvalidStructureTensorRadius(
260 self.structure_tensor_radius,
261 ));
262 }
263 if self.quad_extraction_mode == QuadExtractionMode::EdLines {
264 if self.refinement_mode == CornerRefinementMode::Erf {
265 return Err(ConfigError::EdLinesIncompatibleWithErf);
266 }
267 if self.decode_mode == DecodeMode::Soft {
268 return Err(ConfigError::EdLinesIncompatibleWithSoftDecode);
269 }
270 }
271 Ok(())
272 }
273}
274
275#[derive(Default)]
277pub struct DetectorConfigBuilder {
278 threshold_tile_size: Option<usize>,
279 threshold_min_range: Option<u8>,
280 enable_sharpening: Option<bool>,
281 enable_adaptive_window: Option<bool>,
282 threshold_min_radius: Option<usize>,
283 threshold_max_radius: Option<usize>,
284 adaptive_threshold_constant: Option<i16>,
285 adaptive_threshold_gradient_threshold: Option<u8>,
286 quad_min_area: Option<u32>,
287 quad_max_aspect_ratio: Option<f32>,
288 quad_min_fill_ratio: Option<f32>,
289 quad_max_fill_ratio: Option<f32>,
290 quad_min_edge_length: Option<f64>,
291 pub quad_min_edge_score: Option<f64>,
293 pub subpixel_refinement_sigma: Option<f64>,
295 pub segmentation_margin: Option<i16>,
297 pub segmentation_connectivity: Option<SegmentationConnectivity>,
299 pub upscale_factor: Option<usize>,
301 pub decoder_min_contrast: Option<f64>,
303 pub refinement_mode: Option<CornerRefinementMode>,
305 pub decode_mode: Option<DecodeMode>,
307 pub max_hamming_error: Option<u32>,
309 pub gwlf_transversal_alpha: Option<f64>,
311 pub quad_max_elongation: Option<f64>,
313 pub quad_min_density: Option<f64>,
315 pub quad_extraction_mode: Option<QuadExtractionMode>,
317 pub huber_delta_px: Option<f64>,
319 pub tikhonov_alpha_max: Option<f64>,
321 pub sigma_n_sq: Option<f64>,
323 pub structure_tensor_radius: Option<u8>,
325}
326
327impl DetectorConfigBuilder {
328 #[must_use]
330 pub fn threshold_tile_size(mut self, size: usize) -> Self {
331 self.threshold_tile_size = Some(size);
332 self
333 }
334
335 #[must_use]
337 pub fn threshold_min_range(mut self, range: u8) -> Self {
338 self.threshold_min_range = Some(range);
339 self
340 }
341
342 #[must_use]
344 pub fn quad_min_area(mut self, area: u32) -> Self {
345 self.quad_min_area = Some(area);
346 self
347 }
348
349 #[must_use]
351 pub fn quad_max_aspect_ratio(mut self, ratio: f32) -> Self {
352 self.quad_max_aspect_ratio = Some(ratio);
353 self
354 }
355
356 #[must_use]
358 pub fn quad_min_fill_ratio(mut self, ratio: f32) -> Self {
359 self.quad_min_fill_ratio = Some(ratio);
360 self
361 }
362
363 #[must_use]
365 pub fn quad_max_fill_ratio(mut self, ratio: f32) -> Self {
366 self.quad_max_fill_ratio = Some(ratio);
367 self
368 }
369
370 #[must_use]
372 pub fn quad_min_edge_length(mut self, length: f64) -> Self {
373 self.quad_min_edge_length = Some(length);
374 self
375 }
376
377 #[must_use]
379 pub fn quad_min_edge_score(mut self, score: f64) -> Self {
380 self.quad_min_edge_score = Some(score);
381 self
382 }
383
384 #[must_use]
386 pub fn enable_sharpening(mut self, enable: bool) -> Self {
387 self.enable_sharpening = Some(enable);
388 self
389 }
390
391 #[must_use]
393 pub fn enable_adaptive_window(mut self, enable: bool) -> Self {
394 self.enable_adaptive_window = Some(enable);
395 self
396 }
397
398 #[must_use]
400 pub fn threshold_min_radius(mut self, radius: usize) -> Self {
401 self.threshold_min_radius = Some(radius);
402 self
403 }
404
405 #[must_use]
407 pub fn threshold_max_radius(mut self, radius: usize) -> Self {
408 self.threshold_max_radius = Some(radius);
409 self
410 }
411
412 #[must_use]
414 pub fn adaptive_threshold_constant(mut self, c: i16) -> Self {
415 self.adaptive_threshold_constant = Some(c);
416 self
417 }
418
419 #[must_use]
421 pub fn adaptive_threshold_gradient_threshold(mut self, threshold: u8) -> Self {
422 self.adaptive_threshold_gradient_threshold = Some(threshold);
423 self
424 }
425
426 #[must_use]
428 pub fn build(self) -> DetectorConfig {
429 let d = DetectorConfig::default();
430 DetectorConfig {
431 threshold_tile_size: self.threshold_tile_size.unwrap_or(d.threshold_tile_size),
432 threshold_min_range: self.threshold_min_range.unwrap_or(d.threshold_min_range),
433 enable_sharpening: self.enable_sharpening.unwrap_or(d.enable_sharpening),
434 enable_adaptive_window: self
435 .enable_adaptive_window
436 .unwrap_or(d.enable_adaptive_window),
437 threshold_min_radius: self.threshold_min_radius.unwrap_or(d.threshold_min_radius),
438 threshold_max_radius: self.threshold_max_radius.unwrap_or(d.threshold_max_radius),
439 adaptive_threshold_constant: self
440 .adaptive_threshold_constant
441 .unwrap_or(d.adaptive_threshold_constant),
442 adaptive_threshold_gradient_threshold: self
443 .adaptive_threshold_gradient_threshold
444 .unwrap_or(d.adaptive_threshold_gradient_threshold),
445 quad_min_area: self.quad_min_area.unwrap_or(d.quad_min_area),
446 quad_max_aspect_ratio: self
447 .quad_max_aspect_ratio
448 .unwrap_or(d.quad_max_aspect_ratio),
449 quad_min_fill_ratio: self.quad_min_fill_ratio.unwrap_or(d.quad_min_fill_ratio),
450 quad_max_fill_ratio: self.quad_max_fill_ratio.unwrap_or(d.quad_max_fill_ratio),
451 quad_min_edge_length: self.quad_min_edge_length.unwrap_or(d.quad_min_edge_length),
452 quad_min_edge_score: self.quad_min_edge_score.unwrap_or(d.quad_min_edge_score),
453 subpixel_refinement_sigma: self
454 .subpixel_refinement_sigma
455 .unwrap_or(d.subpixel_refinement_sigma),
456 segmentation_margin: self.segmentation_margin.unwrap_or(d.segmentation_margin),
457 segmentation_connectivity: self
458 .segmentation_connectivity
459 .unwrap_or(d.segmentation_connectivity),
460 upscale_factor: self.upscale_factor.unwrap_or(d.upscale_factor),
461 decimation: 1, nthreads: 0, decoder_min_contrast: self.decoder_min_contrast.unwrap_or(d.decoder_min_contrast),
464 refinement_mode: self.refinement_mode.unwrap_or(d.refinement_mode),
465 decode_mode: self.decode_mode.unwrap_or(d.decode_mode),
466 max_hamming_error: self.max_hamming_error.unwrap_or(d.max_hamming_error),
467 huber_delta_px: self.huber_delta_px.unwrap_or(d.huber_delta_px),
468 tikhonov_alpha_max: self.tikhonov_alpha_max.unwrap_or(d.tikhonov_alpha_max),
469 sigma_n_sq: self.sigma_n_sq.unwrap_or(d.sigma_n_sq),
470 structure_tensor_radius: self
471 .structure_tensor_radius
472 .unwrap_or(d.structure_tensor_radius),
473 gwlf_transversal_alpha: self
474 .gwlf_transversal_alpha
475 .unwrap_or(d.gwlf_transversal_alpha),
476 quad_max_elongation: self.quad_max_elongation.unwrap_or(d.quad_max_elongation),
477 quad_min_density: self.quad_min_density.unwrap_or(d.quad_min_density),
478 quad_extraction_mode: self.quad_extraction_mode.unwrap_or(d.quad_extraction_mode),
479 }
480 }
481
482 pub fn validated_build(self) -> Result<DetectorConfig, crate::error::ConfigError> {
488 let config = self.build();
489 config.validate()?;
490 Ok(config)
491 }
492
493 #[must_use]
495 pub fn segmentation_connectivity(mut self, connectivity: SegmentationConnectivity) -> Self {
496 self.segmentation_connectivity = Some(connectivity);
497 self
498 }
499
500 #[must_use]
502 pub fn segmentation_margin(mut self, margin: i16) -> Self {
503 self.segmentation_margin = Some(margin);
504 self
505 }
506
507 #[must_use]
509 pub fn upscale_factor(mut self, factor: usize) -> Self {
510 self.upscale_factor = Some(factor);
511 self
512 }
513
514 #[must_use]
517 pub fn decoder_min_contrast(mut self, contrast: f64) -> Self {
518 self.decoder_min_contrast = Some(contrast);
519 self
520 }
521
522 #[must_use]
524 pub fn refinement_mode(mut self, mode: CornerRefinementMode) -> Self {
525 self.refinement_mode = Some(mode);
526 self
527 }
528
529 #[must_use]
531 pub fn decode_mode(mut self, mode: DecodeMode) -> Self {
532 self.decode_mode = Some(mode);
533 self
534 }
535
536 #[must_use]
538 pub fn max_hamming_error(mut self, errors: u32) -> Self {
539 self.max_hamming_error = Some(errors);
540 self
541 }
542
543 #[must_use]
545 pub fn gwlf_transversal_alpha(mut self, alpha: f64) -> Self {
546 self.gwlf_transversal_alpha = Some(alpha);
547 self
548 }
549
550 #[must_use]
553 pub fn quad_max_elongation(mut self, max_elongation: f64) -> Self {
554 self.quad_max_elongation = Some(max_elongation);
555 self
556 }
557
558 #[must_use]
561 pub fn quad_min_density(mut self, min_density: f64) -> Self {
562 self.quad_min_density = Some(min_density);
563 self
564 }
565
566 #[must_use]
568 pub fn quad_extraction_mode(mut self, mode: QuadExtractionMode) -> Self {
569 self.quad_extraction_mode = Some(mode);
570 self
571 }
572
573 #[must_use]
575 pub fn huber_delta_px(mut self, delta: f64) -> Self {
576 self.huber_delta_px = Some(delta);
577 self
578 }
579
580 #[must_use]
582 pub fn tikhonov_alpha_max(mut self, alpha: f64) -> Self {
583 self.tikhonov_alpha_max = Some(alpha);
584 self
585 }
586
587 #[must_use]
589 pub fn sigma_n_sq(mut self, sigma_n_sq: f64) -> Self {
590 self.sigma_n_sq = Some(sigma_n_sq);
591 self
592 }
593
594 #[must_use]
597 pub fn structure_tensor_radius(mut self, radius: u8) -> Self {
598 self.structure_tensor_radius = Some(radius);
599 self
600 }
601}
602
603#[derive(Clone, Copy, Debug, PartialEq, Eq, Hash)]
609#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
610pub enum TagFamily {
611 AprilTag16h5,
613 AprilTag36h11,
615 ArUco4x4_50,
617 ArUco4x4_100,
619 ArUco6x6_250,
621}
622
623impl TagFamily {
624 #[must_use]
626 pub const fn all() -> &'static [TagFamily] {
627 &[
628 TagFamily::AprilTag16h5,
629 TagFamily::AprilTag36h11,
630 TagFamily::ArUco4x4_50,
631 TagFamily::ArUco4x4_100,
632 TagFamily::ArUco6x6_250,
633 ]
634 }
635
636 #[must_use]
641 pub fn max_id_count(self) -> usize {
642 crate::dictionaries::get_dictionary(self).len()
643 }
644}
645
646#[derive(Clone, Debug, PartialEq)]
651#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
652pub struct DetectOptions {
653 pub families: Vec<TagFamily>,
655 pub intrinsics: Option<crate::pose::CameraIntrinsics>,
657 pub tag_size: Option<f64>,
659 pub decimation: usize,
662 pub pose_estimation_mode: PoseEstimationMode,
664}
665
666impl Default for DetectOptions {
667 fn default() -> Self {
668 Self {
669 families: Vec::new(),
670 intrinsics: None,
671 tag_size: None,
672 decimation: 1,
673 pose_estimation_mode: PoseEstimationMode::Fast,
674 }
675 }
676}
677
678impl DetectOptions {
679 #[must_use]
681 pub fn builder() -> DetectOptionsBuilder {
682 DetectOptionsBuilder::default()
683 }
684 #[must_use]
686 pub fn with_families(families: &[TagFamily]) -> Self {
687 Self {
688 families: families.to_vec(),
689 intrinsics: None,
690 tag_size: None,
691 decimation: 1,
692 pose_estimation_mode: PoseEstimationMode::Fast,
693 }
694 }
695
696 #[must_use]
698 pub fn all_families() -> Self {
699 Self {
700 families: TagFamily::all().to_vec(),
701 intrinsics: None,
702 tag_size: None,
703 decimation: 1,
704 pose_estimation_mode: PoseEstimationMode::Fast,
705 }
706 }
707}
708
709pub struct DetectOptionsBuilder {
711 families: Vec<TagFamily>,
712 intrinsics: Option<crate::pose::CameraIntrinsics>,
713 tag_size: Option<f64>,
714 decimation: usize,
715 pose_estimation_mode: PoseEstimationMode,
716}
717
718impl Default for DetectOptionsBuilder {
719 fn default() -> Self {
720 Self {
721 families: Vec::new(),
722 intrinsics: None,
723 tag_size: None,
724 decimation: 1,
725 pose_estimation_mode: PoseEstimationMode::Fast,
726 }
727 }
728}
729
730impl DetectOptionsBuilder {
731 #[must_use]
733 pub fn families(mut self, families: &[TagFamily]) -> Self {
734 self.families = families.to_vec();
735 self
736 }
737
738 #[must_use]
740 pub fn intrinsics(mut self, fx: f64, fy: f64, cx: f64, cy: f64) -> Self {
741 self.intrinsics = Some(crate::pose::CameraIntrinsics::new(fx, fy, cx, cy));
742 self
743 }
744
745 #[must_use]
747 pub fn tag_size(mut self, size: f64) -> Self {
748 self.tag_size = Some(size);
749 self
750 }
751
752 #[must_use]
754 pub fn decimation(mut self, decimation: usize) -> Self {
755 self.decimation = decimation.max(1);
756 self
757 }
758
759 #[must_use]
761 pub fn pose_estimation_mode(mut self, mode: PoseEstimationMode) -> Self {
762 self.pose_estimation_mode = mode;
763 self
764 }
765
766 #[must_use]
768 pub fn build(self) -> DetectOptions {
769 DetectOptions {
770 families: self.families,
771 intrinsics: self.intrinsics,
772 tag_size: self.tag_size,
773 decimation: self.decimation,
774 pose_estimation_mode: self.pose_estimation_mode,
775 }
776 }
777}
778
779#[cfg(feature = "profiles")]
786mod profile_json {
787 use super::{
788 CornerRefinementMode, DecodeMode, DetectorConfig, QuadExtractionMode,
789 SegmentationConnectivity,
790 };
791 use serde::Deserialize;
792
793 #[derive(Debug, Deserialize)]
794 #[serde(deny_unknown_fields)]
795 pub(super) struct ProfileJson {
796 #[allow(dead_code)]
797 #[serde(default)]
798 pub name: Option<String>,
799 #[serde(default)]
800 pub extends: Option<String>,
801 #[serde(default)]
802 pub threshold: ThresholdJson,
803 #[serde(default)]
804 pub quad: QuadJson,
805 #[serde(default)]
806 pub decoder: DecoderJson,
807 #[serde(default)]
808 pub pose: PoseJson,
809 #[serde(default)]
810 pub segmentation: SegmentationJson,
811 }
812
813 #[derive(Debug, Deserialize)]
814 #[serde(deny_unknown_fields)]
815 pub(super) struct ThresholdJson {
816 pub tile_size: usize,
817 pub min_range: u8,
818 pub enable_sharpening: bool,
819 pub enable_adaptive_window: bool,
820 pub min_radius: usize,
821 pub max_radius: usize,
822 pub constant: i16,
823 pub gradient_threshold: u8,
824 }
825
826 impl Default for ThresholdJson {
827 fn default() -> Self {
828 let d = DetectorConfig::default();
829 Self {
830 tile_size: d.threshold_tile_size,
831 min_range: d.threshold_min_range,
832 enable_sharpening: d.enable_sharpening,
833 enable_adaptive_window: d.enable_adaptive_window,
834 min_radius: d.threshold_min_radius,
835 max_radius: d.threshold_max_radius,
836 constant: d.adaptive_threshold_constant,
837 gradient_threshold: d.adaptive_threshold_gradient_threshold,
838 }
839 }
840 }
841
842 #[derive(Debug, Deserialize)]
843 #[serde(deny_unknown_fields)]
844 pub(super) struct QuadJson {
845 pub min_area: u32,
846 pub max_aspect_ratio: f32,
847 pub min_fill_ratio: f32,
848 pub max_fill_ratio: f32,
849 pub min_edge_length: f64,
850 pub min_edge_score: f64,
851 pub subpixel_refinement_sigma: f64,
852 pub upscale_factor: usize,
853 pub max_elongation: f64,
854 pub min_density: f64,
855 pub extraction_mode: QuadExtractionMode,
856 }
857
858 impl Default for QuadJson {
859 fn default() -> Self {
860 let d = DetectorConfig::default();
861 Self {
862 min_area: d.quad_min_area,
863 max_aspect_ratio: d.quad_max_aspect_ratio,
864 min_fill_ratio: d.quad_min_fill_ratio,
865 max_fill_ratio: d.quad_max_fill_ratio,
866 min_edge_length: d.quad_min_edge_length,
867 min_edge_score: d.quad_min_edge_score,
868 subpixel_refinement_sigma: d.subpixel_refinement_sigma,
869 upscale_factor: d.upscale_factor,
870 max_elongation: d.quad_max_elongation,
871 min_density: d.quad_min_density,
872 extraction_mode: d.quad_extraction_mode,
873 }
874 }
875 }
876
877 #[derive(Debug, Deserialize)]
878 #[serde(deny_unknown_fields)]
879 pub(super) struct DecoderJson {
880 pub min_contrast: f64,
881 pub refinement_mode: CornerRefinementMode,
882 pub decode_mode: DecodeMode,
883 pub max_hamming_error: u32,
884 pub gwlf_transversal_alpha: f64,
885 }
886
887 impl Default for DecoderJson {
888 fn default() -> Self {
889 let d = DetectorConfig::default();
890 Self {
891 min_contrast: d.decoder_min_contrast,
892 refinement_mode: d.refinement_mode,
893 decode_mode: d.decode_mode,
894 max_hamming_error: d.max_hamming_error,
895 gwlf_transversal_alpha: d.gwlf_transversal_alpha,
896 }
897 }
898 }
899
900 #[derive(Debug, Deserialize)]
901 #[serde(deny_unknown_fields)]
902 pub(super) struct PoseJson {
903 pub huber_delta_px: f64,
904 pub tikhonov_alpha_max: f64,
905 pub sigma_n_sq: f64,
906 pub structure_tensor_radius: u8,
907 }
908
909 impl Default for PoseJson {
910 fn default() -> Self {
911 let d = DetectorConfig::default();
912 Self {
913 huber_delta_px: d.huber_delta_px,
914 tikhonov_alpha_max: d.tikhonov_alpha_max,
915 sigma_n_sq: d.sigma_n_sq,
916 structure_tensor_radius: d.structure_tensor_radius,
917 }
918 }
919 }
920
921 #[derive(Debug, Deserialize)]
922 #[serde(deny_unknown_fields)]
923 pub(super) struct SegmentationJson {
924 pub connectivity: SegmentationConnectivity,
925 pub margin: i16,
926 }
927
928 impl Default for SegmentationJson {
929 fn default() -> Self {
930 let d = DetectorConfig::default();
931 Self {
932 connectivity: d.segmentation_connectivity,
933 margin: d.segmentation_margin,
934 }
935 }
936 }
937
938 impl From<ProfileJson> for DetectorConfig {
939 fn from(p: ProfileJson) -> Self {
940 let d = DetectorConfig::default();
943 DetectorConfig {
944 threshold_tile_size: p.threshold.tile_size,
945 threshold_min_range: p.threshold.min_range,
946 enable_sharpening: p.threshold.enable_sharpening,
947 enable_adaptive_window: p.threshold.enable_adaptive_window,
948 threshold_min_radius: p.threshold.min_radius,
949 threshold_max_radius: p.threshold.max_radius,
950 adaptive_threshold_constant: p.threshold.constant,
951 adaptive_threshold_gradient_threshold: p.threshold.gradient_threshold,
952 quad_min_area: p.quad.min_area,
953 quad_max_aspect_ratio: p.quad.max_aspect_ratio,
954 quad_min_fill_ratio: p.quad.min_fill_ratio,
955 quad_max_fill_ratio: p.quad.max_fill_ratio,
956 quad_min_edge_length: p.quad.min_edge_length,
957 quad_min_edge_score: p.quad.min_edge_score,
958 subpixel_refinement_sigma: p.quad.subpixel_refinement_sigma,
959 segmentation_margin: p.segmentation.margin,
960 segmentation_connectivity: p.segmentation.connectivity,
961 upscale_factor: p.quad.upscale_factor,
962 decimation: d.decimation,
963 nthreads: d.nthreads,
964 decoder_min_contrast: p.decoder.min_contrast,
965 refinement_mode: p.decoder.refinement_mode,
966 decode_mode: p.decoder.decode_mode,
967 max_hamming_error: p.decoder.max_hamming_error,
968 huber_delta_px: p.pose.huber_delta_px,
969 tikhonov_alpha_max: p.pose.tikhonov_alpha_max,
970 sigma_n_sq: p.pose.sigma_n_sq,
971 structure_tensor_radius: p.pose.structure_tensor_radius,
972 gwlf_transversal_alpha: p.decoder.gwlf_transversal_alpha,
973 quad_max_elongation: p.quad.max_elongation,
974 quad_min_density: p.quad.min_density,
975 quad_extraction_mode: p.quad.extraction_mode,
976 }
977 }
978 }
979}
980
981#[cfg(feature = "profiles")]
982const STANDARD_JSON: &str = include_str!("../profiles/standard.json");
983#[cfg(feature = "profiles")]
984const GRID_JSON: &str = include_str!("../profiles/grid.json");
985#[cfg(feature = "profiles")]
986const HIGH_ACCURACY_JSON: &str = include_str!("../profiles/high_accuracy.json");
987
988#[cfg(feature = "profiles")]
992#[must_use]
993pub fn shipped_profile_json(name: &str) -> Option<&'static str> {
994 match name {
995 "standard" => Some(STANDARD_JSON),
996 "grid" => Some(GRID_JSON),
997 "high_accuracy" => Some(HIGH_ACCURACY_JSON),
998 _ => None,
999 }
1000}
1001
1002#[cfg(feature = "profiles")]
1003impl DetectorConfig {
1004 pub fn from_profile_json(json: &str) -> Result<Self, crate::error::ConfigError> {
1015 use crate::error::ConfigError;
1016 let parsed: profile_json::ProfileJson =
1017 serde_json::from_str(json).map_err(|e| ConfigError::ProfileParse(e.to_string()))?;
1018 if let Some(name) = parsed.extends.as_deref() {
1019 return Err(ConfigError::ProfileParse(format!(
1020 "profile inheritance (extends={name:?}) is declared in the schema but \
1021 not yet resolved by the Rust loader; inline the parent profile's values"
1022 )));
1023 }
1024 let config: DetectorConfig = parsed.into();
1025 config.validate()?;
1026 Ok(config)
1027 }
1028
1029 #[must_use]
1040 #[allow(clippy::panic)] pub fn from_profile(name: &str) -> Self {
1042 let json = match name {
1043 "standard" => STANDARD_JSON,
1044 "grid" => GRID_JSON,
1045 "high_accuracy" => HIGH_ACCURACY_JSON,
1046 other => panic!(
1047 "Unknown shipped profile {other:?}; expected one of \
1048 [\"standard\", \"grid\", \"high_accuracy\"]"
1049 ),
1050 };
1051 Self::from_profile_json(json).unwrap_or_else(|e| {
1052 panic!("shipped profile {name:?} failed to load: {e}; this is a build bug")
1053 })
1054 }
1055}
1056
1057#[cfg(test)]
1058#[allow(clippy::expect_used, clippy::unwrap_used)]
1059mod tests {
1060 use super::*;
1061
1062 #[test]
1063 #[allow(clippy::float_cmp)]
1064 fn test_detector_config_builder() {
1065 let config = DetectorConfig::builder()
1066 .threshold_tile_size(16)
1067 .quad_min_area(1000)
1068 .build();
1069 assert_eq!(config.threshold_tile_size, 16);
1070 assert_eq!(config.quad_min_area, 1000);
1071 assert_eq!(config.threshold_min_range, 10);
1073 assert_eq!(config.quad_min_edge_score, 4.0);
1074 assert_eq!(config.max_hamming_error, 2);
1075 }
1076
1077 #[test]
1078 #[allow(clippy::float_cmp)]
1079 fn test_detector_config_defaults() {
1080 let config = DetectorConfig::default();
1081 assert_eq!(config.threshold_tile_size, 8);
1082 assert_eq!(config.quad_min_area, 16);
1083 assert_eq!(config.quad_min_edge_length, 4.0);
1084 assert_eq!(config.max_hamming_error, 2);
1085 }
1086
1087 #[test]
1088 fn test_detect_options_families() {
1089 let opt = DetectOptions::with_families(&[TagFamily::AprilTag36h11]);
1090 assert_eq!(opt.families.len(), 1);
1091 assert_eq!(opt.families[0], TagFamily::AprilTag36h11);
1092 }
1093
1094 #[test]
1095 fn test_detect_options_default_empty() {
1096 let opt = DetectOptions::default();
1097 assert!(opt.families.is_empty());
1098 }
1099
1100 #[test]
1101 fn test_all_families() {
1102 let opt = DetectOptions::all_families();
1103 assert_eq!(opt.families.len(), 5);
1104 }
1105
1106 #[test]
1107 fn test_default_config_is_valid() {
1108 let config = DetectorConfig::default();
1109 assert!(config.validate().is_ok());
1110 }
1111
1112 #[test]
1113 fn test_validation_rejects_bad_tile_size() {
1114 let config = DetectorConfig {
1115 threshold_tile_size: 1,
1116 ..DetectorConfig::default()
1117 };
1118 assert!(config.validate().is_err());
1119 }
1120
1121 #[test]
1122 fn test_validation_rejects_bad_fill_ratio() {
1123 let config = DetectorConfig {
1124 quad_min_fill_ratio: 0.9,
1125 quad_max_fill_ratio: 0.5,
1126 ..DetectorConfig::default()
1127 };
1128 assert!(config.validate().is_err());
1129 }
1130
1131 #[test]
1132 fn test_validation_rejects_negative_edge_length() {
1133 let config = DetectorConfig {
1134 quad_min_edge_length: -1.0,
1135 ..DetectorConfig::default()
1136 };
1137 assert!(config.validate().is_err());
1138 }
1139
1140 #[test]
1141 fn test_validation_rejects_large_structure_tensor_radius() {
1142 let config = DetectorConfig {
1143 structure_tensor_radius: 9,
1144 ..DetectorConfig::default()
1145 };
1146 assert!(config.validate().is_err());
1147 }
1148
1149 #[test]
1150 fn test_validated_build_catches_errors() {
1151 let result = DetectorConfig::builder()
1152 .threshold_tile_size(0)
1153 .validated_build();
1154 assert!(result.is_err());
1155 }
1156}