Skip to main content

locus_core/
config.rs

1//! Configuration types for the detector pipeline.
2//!
3//! This module provides two configuration types:
4//! - [`DetectorConfig`]: Pipeline-level configuration (immutable after construction)
5//! - [`DetectOptions`]: Per-call options (e.g., which tag families to decode)
6
7// ============================================================================
8// DetectorConfig: Pipeline-level configuration
9// ============================================================================
10
11/// Segmentation connectivity mode.
12#[derive(Clone, Copy, Debug, PartialEq)]
13#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
14pub enum SegmentationConnectivity {
15    /// 4-connectivity: Pixels connect horizontally and vertically only.
16    /// Required for separating checkerboard corners.
17    Four,
18    /// 8-connectivity: Pixels connect horizontally, vertically, and diagonally.
19    /// Better for isolated tags with broken borders.
20    Eight,
21}
22
23/// Mode for subpixel corner refinement.
24#[derive(Clone, Copy, Debug, PartialEq)]
25#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
26pub enum CornerRefinementMode {
27    /// No subpixel refinement (integer pixel precision).
28    None,
29    /// Edge-based refinement using gradient maxima (Default).
30    Edge,
31    /// GridFit: Optimizes corners by maximizing code contrast.
32    GridFit,
33    /// Erf: Fits a Gaussian to the gradient profile for sub-pixel edge alignment.
34    Erf,
35}
36
37/// Mode for decoding strategy.
38#[derive(Clone, Copy, Debug, PartialEq)]
39#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
40pub enum DecodeMode {
41    /// Hard-decision decoding using Hamming distance (fastest).
42    Hard,
43    /// Soft-decision decoding using Log-Likelihood Ratios (better for noise/blur).
44    Soft,
45}
46
47/// Mode for 3D pose estimation quality.
48#[derive(Clone, Copy, Debug, PartialEq)]
49#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
50pub enum PoseEstimationMode {
51    /// Standard IPPE + Levenberg-Marquardt with identity weights (Fast).
52    Fast,
53    /// Structure Tensor + Weighted Levenberg-Marquardt (Accurate, Slower).
54    ///
55    /// This models corner uncertainty using image gradients and weights the
56    /// PnP optimization to prefer "sharp" directions, significantly improving
57    /// accuracy (RMSE) at the cost of ~0.5ms per tag.
58    Accurate,
59}
60
61/// Pipeline-level configuration for the detector.
62///
63/// These settings affect the fundamental behavior of the detection pipeline
64/// and are immutable after the `Detector` is constructed. Use the builder
65/// pattern for ergonomic construction.
66///
67/// # Example
68/// ```
69/// use locus_core::config::DetectorConfig;
70///
71/// let config = DetectorConfig::builder()
72///     .threshold_tile_size(16)
73///     .quad_min_area(200)
74///     .build();
75/// ```
76#[derive(Clone, Copy, Debug, PartialEq)]
77#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
78pub struct DetectorConfig {
79    // Threshold parameters
80    /// Tile size for adaptive thresholding (default: 4).
81    /// Larger tiles are faster but less adaptive to local contrast.
82    pub threshold_tile_size: usize,
83    /// Minimum intensity range in a tile to be considered valid (default: 10).
84    /// Tiles with lower range are treated as uniform (no edges).
85    pub threshold_min_range: u8,
86
87    // Adaptive filtering parameters
88    /// Enable bilateral pre-filtering for edge-preserving noise reduction (default: true).
89    pub enable_bilateral: bool,
90    /// Bilateral spatial sigma for spatial smoothing (default: 3.0).
91    pub bilateral_sigma_space: f32,
92    /// Bilateral color sigma for edge preservation (default: 30.0).
93    /// Higher values = more smoothing across edges.
94    pub bilateral_sigma_color: f32,
95
96    /// Enable Laplacian sharpening to enhance edges for small tags (default: true).
97    pub enable_sharpening: bool,
98
99    /// Enable adaptive threshold window sizing based on gradient (default: true).
100    pub enable_adaptive_window: bool,
101    /// Minimum threshold window radius for high-gradient regions (default: 2 = 5x5).
102    pub threshold_min_radius: usize,
103    /// Maximum threshold window radius for low-gradient regions (default: 7 = 15x15).
104    pub threshold_max_radius: usize,
105    /// Constant subtracted from local mean in adaptive thresholding (default: 3).
106    pub adaptive_threshold_constant: i16,
107    /// Gradient magnitude threshold above which the minimum window radius is used (default: 40).
108    pub adaptive_threshold_gradient_threshold: u8,
109
110    // Quad filtering parameters
111    /// Minimum quad area in pixels (default: 16).
112    pub quad_min_area: u32,
113    /// Maximum aspect ratio of bounding box (default: 3.0).
114    pub quad_max_aspect_ratio: f32,
115    /// Minimum fill ratio (pixel count / bbox area) (default: 0.3).
116    pub quad_min_fill_ratio: f32,
117    /// Maximum fill ratio (default: 0.95).
118    pub quad_max_fill_ratio: f32,
119    /// Minimum edge length in pixels (default: 4.0).
120    pub quad_min_edge_length: f64,
121    /// Minimum edge alignment score (0.0 to 1.0)
122    pub quad_min_edge_score: f64,
123    /// PSF blur factor for subpixel refinement (e.g., 0.6)
124    pub subpixel_refinement_sigma: f64,
125    /// Minimum deviation from threshold for a pixel to be connected in threshold-model CCL (default: 2).
126    pub segmentation_margin: i16,
127    /// Segmentation connectivity (4-way or 8-way).
128    pub segmentation_connectivity: SegmentationConnectivity,
129    /// Factor to upscale the image before detection (1 = no upscaling).
130    /// Increasing this to 2 allows detecting smaller tags (e.g., < 15px)
131    /// at the cost of processing speed (O(N^2)). Nearest-neighbor interpolation is used.
132    pub upscale_factor: usize,
133
134    // Decoder parameters
135    /// Minimum contrast range for Otsu-based bit classification (default: 20.0).
136    /// For checkerboard patterns with densely packed tags, lower values (e.g., 10.0)
137    /// can improve recall on small/blurry tags.
138    pub decoder_min_contrast: f64,
139    /// Strategy for refining corner positions (default: Edge).
140    pub refinement_mode: CornerRefinementMode,
141    /// Decoding mode (Hard vs Soft).
142    pub decode_mode: DecodeMode,
143}
144
145impl Default for DetectorConfig {
146    fn default() -> Self {
147        Self {
148            threshold_tile_size: 8,
149            threshold_min_range: 10,
150            enable_bilateral: false,
151            bilateral_sigma_space: 0.8,
152            bilateral_sigma_color: 30.0,
153            enable_sharpening: false,
154            enable_adaptive_window: false,
155            threshold_min_radius: 2,
156            threshold_max_radius: 15,
157            adaptive_threshold_constant: 0, // Most sensitive
158            adaptive_threshold_gradient_threshold: 10,
159            quad_min_area: 16,
160            quad_max_aspect_ratio: 10.0,
161            quad_min_fill_ratio: 0.10,
162            quad_max_fill_ratio: 0.98,
163            quad_min_edge_length: 2.0,
164            quad_min_edge_score: 0.1,
165            subpixel_refinement_sigma: 0.6,
166            segmentation_margin: 1,
167            segmentation_connectivity: SegmentationConnectivity::Eight,
168            upscale_factor: 1,
169            decoder_min_contrast: 20.0,
170            refinement_mode: CornerRefinementMode::Erf,
171            decode_mode: DecodeMode::Hard,
172        }
173    }
174}
175
176impl DetectorConfig {
177    /// Create a new builder for `DetectorConfig`.
178    #[must_use]
179    pub fn builder() -> DetectorConfigBuilder {
180        DetectorConfigBuilder::default()
181    }
182}
183
184/// Builder for [`DetectorConfig`].
185#[derive(Default)]
186pub struct DetectorConfigBuilder {
187    threshold_tile_size: Option<usize>,
188    threshold_min_range: Option<u8>,
189    enable_bilateral: Option<bool>,
190    bilateral_sigma_space: Option<f32>,
191    bilateral_sigma_color: Option<f32>,
192    enable_sharpening: Option<bool>,
193    enable_adaptive_window: Option<bool>,
194    threshold_min_radius: Option<usize>,
195    threshold_max_radius: Option<usize>,
196    adaptive_threshold_constant: Option<i16>,
197    adaptive_threshold_gradient_threshold: Option<u8>,
198    quad_min_area: Option<u32>,
199    quad_max_aspect_ratio: Option<f32>,
200    quad_min_fill_ratio: Option<f32>,
201    quad_max_fill_ratio: Option<f32>,
202    quad_min_edge_length: Option<f64>,
203    /// Minimum gradient magnitude along edges (rejects weak candidates).
204    pub quad_min_edge_score: Option<f64>,
205    /// Sigma for Gaussian in subpixel refinement.
206    pub subpixel_refinement_sigma: Option<f64>,
207    /// Margin for threshold-model segmentation.
208    pub segmentation_margin: Option<i16>,
209    /// Connectivity mode for segmentation (4 or 8).
210    pub segmentation_connectivity: Option<SegmentationConnectivity>,
211    /// Upscale factor for low-res images (1 = no upscale).
212    pub upscale_factor: Option<usize>,
213    /// Minimum contrast for decoder to accept a tag.
214    pub decoder_min_contrast: Option<f64>,
215    /// Refinement mode.
216    pub refinement_mode: Option<CornerRefinementMode>,
217    /// Decoding mode.
218    pub decode_mode: Option<DecodeMode>,
219}
220
221impl DetectorConfigBuilder {
222    /// Set the tile size for adaptive thresholding.
223    #[must_use]
224    pub fn threshold_tile_size(mut self, size: usize) -> Self {
225        self.threshold_tile_size = Some(size);
226        self
227    }
228
229    /// Set the minimum intensity range for valid tiles.
230    #[must_use]
231    pub fn threshold_min_range(mut self, range: u8) -> Self {
232        self.threshold_min_range = Some(range);
233        self
234    }
235
236    /// Set the minimum quad area.
237    #[must_use]
238    pub fn quad_min_area(mut self, area: u32) -> Self {
239        self.quad_min_area = Some(area);
240        self
241    }
242
243    /// Set the maximum aspect ratio.
244    #[must_use]
245    pub fn quad_max_aspect_ratio(mut self, ratio: f32) -> Self {
246        self.quad_max_aspect_ratio = Some(ratio);
247        self
248    }
249
250    /// Set the minimum fill ratio.
251    #[must_use]
252    pub fn quad_min_fill_ratio(mut self, ratio: f32) -> Self {
253        self.quad_min_fill_ratio = Some(ratio);
254        self
255    }
256
257    /// Set the maximum fill ratio.
258    #[must_use]
259    pub fn quad_max_fill_ratio(mut self, ratio: f32) -> Self {
260        self.quad_max_fill_ratio = Some(ratio);
261        self
262    }
263
264    /// Set the minimum edge length.
265    #[must_use]
266    pub fn quad_min_edge_length(mut self, length: f64) -> Self {
267        self.quad_min_edge_length = Some(length);
268        self
269    }
270
271    /// Set the minimum edge gradient score.
272    #[must_use]
273    pub fn quad_min_edge_score(mut self, score: f64) -> Self {
274        self.quad_min_edge_score = Some(score);
275        self
276    }
277
278    /// Enable or disable bilateral pre-filtering.
279    #[must_use]
280    pub fn enable_bilateral(mut self, enable: bool) -> Self {
281        self.enable_bilateral = Some(enable);
282        self
283    }
284
285    /// Set bilateral spatial sigma.
286    #[must_use]
287    pub fn bilateral_sigma_space(mut self, sigma: f32) -> Self {
288        self.bilateral_sigma_space = Some(sigma);
289        self
290    }
291
292    /// Set bilateral color sigma.
293    #[must_use]
294    pub fn bilateral_sigma_color(mut self, sigma: f32) -> Self {
295        self.bilateral_sigma_color = Some(sigma);
296        self
297    }
298
299    /// Enable or disable Laplacian sharpening.
300    #[must_use]
301    pub fn enable_sharpening(mut self, enable: bool) -> Self {
302        self.enable_sharpening = Some(enable);
303        self
304    }
305
306    /// Enable or disable adaptive threshold window sizing.
307    #[must_use]
308    pub fn enable_adaptive_window(mut self, enable: bool) -> Self {
309        self.enable_adaptive_window = Some(enable);
310        self
311    }
312
313    /// Set minimum threshold window radius.
314    #[must_use]
315    pub fn threshold_min_radius(mut self, radius: usize) -> Self {
316        self.threshold_min_radius = Some(radius);
317        self
318    }
319
320    /// Set maximum threshold window radius.
321    #[must_use]
322    pub fn threshold_max_radius(mut self, radius: usize) -> Self {
323        self.threshold_max_radius = Some(radius);
324        self
325    }
326
327    /// Set the constant subtracted from local mean in adaptive thresholding.
328    #[must_use]
329    pub fn adaptive_threshold_constant(mut self, c: i16) -> Self {
330        self.adaptive_threshold_constant = Some(c);
331        self
332    }
333
334    /// Set the gradient threshold for adaptive window sizing.
335    #[must_use]
336    pub fn adaptive_threshold_gradient_threshold(mut self, threshold: u8) -> Self {
337        self.adaptive_threshold_gradient_threshold = Some(threshold);
338        self
339    }
340
341    /// Build the configuration, using defaults for unset fields.
342    #[must_use]
343    pub fn build(self) -> DetectorConfig {
344        let d = DetectorConfig::default();
345        DetectorConfig {
346            threshold_tile_size: self.threshold_tile_size.unwrap_or(d.threshold_tile_size),
347            threshold_min_range: self.threshold_min_range.unwrap_or(d.threshold_min_range),
348            enable_bilateral: self.enable_bilateral.unwrap_or(d.enable_bilateral),
349            bilateral_sigma_space: self
350                .bilateral_sigma_space
351                .unwrap_or(d.bilateral_sigma_space),
352            bilateral_sigma_color: self
353                .bilateral_sigma_color
354                .unwrap_or(d.bilateral_sigma_color),
355            enable_sharpening: self.enable_sharpening.unwrap_or(d.enable_sharpening),
356            enable_adaptive_window: self
357                .enable_adaptive_window
358                .unwrap_or(d.enable_adaptive_window),
359            threshold_min_radius: self.threshold_min_radius.unwrap_or(d.threshold_min_radius),
360            threshold_max_radius: self.threshold_max_radius.unwrap_or(d.threshold_max_radius),
361            adaptive_threshold_constant: self
362                .adaptive_threshold_constant
363                .unwrap_or(d.adaptive_threshold_constant),
364            adaptive_threshold_gradient_threshold: self
365                .adaptive_threshold_gradient_threshold
366                .unwrap_or(d.adaptive_threshold_gradient_threshold),
367            quad_min_area: self.quad_min_area.unwrap_or(d.quad_min_area),
368            quad_max_aspect_ratio: self
369                .quad_max_aspect_ratio
370                .unwrap_or(d.quad_max_aspect_ratio),
371            quad_min_fill_ratio: self.quad_min_fill_ratio.unwrap_or(d.quad_min_fill_ratio),
372            quad_max_fill_ratio: self.quad_max_fill_ratio.unwrap_or(d.quad_max_fill_ratio),
373            quad_min_edge_length: self.quad_min_edge_length.unwrap_or(d.quad_min_edge_length),
374            quad_min_edge_score: self.quad_min_edge_score.unwrap_or(d.quad_min_edge_score),
375            subpixel_refinement_sigma: self
376                .subpixel_refinement_sigma
377                .unwrap_or(d.subpixel_refinement_sigma),
378            segmentation_margin: self.segmentation_margin.unwrap_or(d.segmentation_margin),
379            segmentation_connectivity: self
380                .segmentation_connectivity
381                .unwrap_or(d.segmentation_connectivity),
382            upscale_factor: self.upscale_factor.unwrap_or(d.upscale_factor),
383            decoder_min_contrast: self.decoder_min_contrast.unwrap_or(d.decoder_min_contrast),
384            refinement_mode: self.refinement_mode.unwrap_or(d.refinement_mode),
385            decode_mode: self.decode_mode.unwrap_or(d.decode_mode),
386        }
387    }
388
389    /// Set the segmentation connectivity.
390    #[must_use]
391    pub fn segmentation_connectivity(mut self, connectivity: SegmentationConnectivity) -> Self {
392        self.segmentation_connectivity = Some(connectivity);
393        self
394    }
395
396    /// Set the segmentation margin for threshold-model CCL.
397    #[must_use]
398    pub fn segmentation_margin(mut self, margin: i16) -> Self {
399        self.segmentation_margin = Some(margin);
400        self
401    }
402
403    /// Set the upscale factor (1 = no upscaling, 2 = 2x, etc.).
404    #[must_use]
405    pub fn upscale_factor(mut self, factor: usize) -> Self {
406        self.upscale_factor = Some(factor);
407        self
408    }
409
410    /// Set the minimum contrast for decoder bit classification.
411    /// Lower values (e.g., 10.0) improve recall on small/blurry checkerboard tags.
412    #[must_use]
413    pub fn decoder_min_contrast(mut self, contrast: f64) -> Self {
414        self.decoder_min_contrast = Some(contrast);
415        self
416    }
417
418    /// Set the corner refinement mode.
419    #[must_use]
420    pub fn refinement_mode(mut self, mode: CornerRefinementMode) -> Self {
421        self.refinement_mode = Some(mode);
422        self
423    }
424
425    /// Set the decoding mode (Hard or Soft).
426    #[must_use]
427    pub fn decode_mode(mut self, mode: DecodeMode) -> Self {
428        self.decode_mode = Some(mode);
429        self
430    }
431}
432
433// ============================================================================
434// DetectOptions: Per-call detection options
435// ============================================================================
436
437/// Tag family identifier for per-call decoder selection.
438#[derive(Clone, Copy, Debug, PartialEq, Eq, Hash)]
439#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
440pub enum TagFamily {
441    /// AprilTag 36h11 family (587 codes, 11-bit hamming distance).
442    AprilTag36h11,
443    /// AprilTag 16h5 family (30 codes, 5-bit hamming distance).
444    AprilTag16h5,
445    /// ArUco 4x4_50 dictionary.
446    ArUco4x4_50,
447    /// ArUco 4x4_100 dictionary.
448    ArUco4x4_100,
449}
450
451impl TagFamily {
452    /// Returns all available tag families.
453    #[must_use]
454    pub const fn all() -> &'static [TagFamily] {
455        &[
456            TagFamily::AprilTag36h11,
457            TagFamily::AprilTag16h5,
458            TagFamily::ArUco4x4_50,
459            TagFamily::ArUco4x4_100,
460        ]
461    }
462}
463
464/// Per-call detection options.
465///
466/// These allow customizing which tag families to decode for a specific call,
467/// enabling performance optimization when you know which tags to expect.
468///
469/// # Example
470/// ```
471/// use locus_core::config::{DetectOptions, TagFamily};
472///
473/// // Only search for AprilTag 36h11 tags (fastest)
474/// let options = DetectOptions::with_families(&[TagFamily::AprilTag36h11]);
475///
476/// // Search for multiple families
477/// let multi = DetectOptions::with_families(&[
478///     TagFamily::AprilTag36h11,
479///     TagFamily::ArUco4x4_50,
480/// ]);
481/// ```
482#[derive(Clone, Debug, PartialEq)]
483#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
484pub struct DetectOptions {
485    /// Tag families to attempt decoding. Empty means use detector defaults.
486    pub families: Vec<TagFamily>,
487    /// Camera intrinsics for 3D pose estimation. If None, pose is not computed.
488    pub intrinsics: Option<crate::pose::CameraIntrinsics>,
489    /// Physical size of the tag in world units (e.g. meters) for 3D pose estimation.
490    pub tag_size: Option<f64>,
491    /// Decimation factor for preprocessing (1 = no decimation).
492    /// Preprocessing and segmentation operate on a downsampled image of size (W/D, H/D).
493    pub decimation: usize,
494    /// Mode for 3D pose estimation (Fast vs Accurate).
495    pub pose_estimation_mode: PoseEstimationMode,
496}
497
498impl Default for DetectOptions {
499    fn default() -> Self {
500        Self {
501            families: Vec::new(),
502            intrinsics: None,
503            tag_size: None,
504            decimation: 1,
505            pose_estimation_mode: PoseEstimationMode::Fast,
506        }
507    }
508}
509
510impl DetectOptions {
511    /// Create a new builder for `DetectOptions`.
512    #[must_use]
513    pub fn builder() -> DetectOptionsBuilder {
514        DetectOptionsBuilder::default()
515    }
516    /// Create options that decode only the specified tag families.
517    #[must_use]
518    pub fn with_families(families: &[TagFamily]) -> Self {
519        Self {
520            families: families.to_vec(),
521            intrinsics: None,
522            tag_size: None,
523            decimation: 1,
524            pose_estimation_mode: PoseEstimationMode::Fast,
525        }
526    }
527
528    /// Create options that decode all known tag families.
529    #[must_use]
530    pub fn all_families() -> Self {
531        Self {
532            families: TagFamily::all().to_vec(),
533            intrinsics: None,
534            tag_size: None,
535            decimation: 1,
536            pose_estimation_mode: PoseEstimationMode::Fast,
537        }
538    }
539}
540
541/// Builder for [`DetectOptions`].
542pub struct DetectOptionsBuilder {
543    families: Vec<TagFamily>,
544    intrinsics: Option<crate::pose::CameraIntrinsics>,
545    tag_size: Option<f64>,
546    decimation: usize,
547    pose_estimation_mode: PoseEstimationMode,
548}
549
550impl Default for DetectOptionsBuilder {
551    fn default() -> Self {
552        Self {
553            families: Vec::new(),
554            intrinsics: None,
555            tag_size: None,
556            decimation: 1,
557            pose_estimation_mode: PoseEstimationMode::Fast,
558        }
559    }
560}
561
562impl DetectOptionsBuilder {
563    /// Set the tag families to decode.
564    #[must_use]
565    pub fn families(mut self, families: &[TagFamily]) -> Self {
566        self.families = families.to_vec();
567        self
568    }
569
570    /// Set camera intrinsics for pose estimation.
571    #[must_use]
572    pub fn intrinsics(mut self, fx: f64, fy: f64, cx: f64, cy: f64) -> Self {
573        self.intrinsics = Some(crate::pose::CameraIntrinsics::new(fx, fy, cx, cy));
574        self
575    }
576
577    /// Set physical tag size for pose estimation.
578    #[must_use]
579    pub fn tag_size(mut self, size: f64) -> Self {
580        self.tag_size = Some(size);
581        self
582    }
583
584    /// Set the decimation factor (1 = no decimation).
585    #[must_use]
586    pub fn decimation(mut self, decimation: usize) -> Self {
587        self.decimation = decimation.max(1);
588        self
589    }
590
591    /// Set the pose estimation mode.
592    #[must_use]
593    pub fn pose_estimation_mode(mut self, mode: PoseEstimationMode) -> Self {
594        self.pose_estimation_mode = mode;
595        self
596    }
597
598    /// Build the options.
599    #[must_use]
600    pub fn build(self) -> DetectOptions {
601        DetectOptions {
602            families: self.families,
603            intrinsics: self.intrinsics,
604            tag_size: self.tag_size,
605            decimation: self.decimation,
606            pose_estimation_mode: self.pose_estimation_mode,
607        }
608    }
609}
610
611#[cfg(test)]
612mod tests {
613    use super::*;
614
615    #[test]
616    fn test_detector_config_builder() {
617        let config = DetectorConfig::builder()
618            .threshold_tile_size(16)
619            .quad_min_area(1000)
620            .build();
621        assert_eq!(config.threshold_tile_size, 16);
622        assert_eq!(config.quad_min_area, 1000);
623        // Check defaults
624        assert_eq!(config.threshold_min_range, 10);
625    }
626
627    #[test]
628    fn test_detector_config_defaults() {
629        let config = DetectorConfig::default();
630        assert_eq!(config.threshold_tile_size, 8);
631        assert_eq!(config.quad_min_area, 16);
632    }
633
634    #[test]
635    fn test_detect_options_families() {
636        let opt = DetectOptions::with_families(&[TagFamily::AprilTag36h11]);
637        assert_eq!(opt.families.len(), 1);
638        assert_eq!(opt.families[0], TagFamily::AprilTag36h11);
639    }
640
641    #[test]
642    fn test_detect_options_default_empty() {
643        let opt = DetectOptions::default();
644        assert!(opt.families.is_empty());
645    }
646
647    #[test]
648    fn test_all_families() {
649        let opt = DetectOptions::all_families();
650        assert_eq!(opt.families.len(), 4);
651    }
652}