pub struct DetectorConfig {Show 35 fields
pub threshold_tile_size: usize,
pub threshold_min_range: u8,
pub enable_bilateral: bool,
pub bilateral_sigma_space: f32,
pub bilateral_sigma_color: f32,
pub enable_sharpening: bool,
pub enable_adaptive_window: bool,
pub threshold_min_radius: usize,
pub threshold_max_radius: usize,
pub adaptive_threshold_constant: i16,
pub adaptive_threshold_gradient_threshold: u8,
pub quad_min_area: u32,
pub quad_max_aspect_ratio: f32,
pub quad_min_fill_ratio: f32,
pub quad_max_fill_ratio: f32,
pub quad_min_edge_length: f64,
pub quad_min_edge_score: f64,
pub subpixel_refinement_sigma: f64,
pub segmentation_margin: i16,
pub segmentation_connectivity: SegmentationConnectivity,
pub upscale_factor: usize,
pub decimation: usize,
pub nthreads: usize,
pub decoder_min_contrast: f64,
pub refinement_mode: CornerRefinementMode,
pub decode_mode: DecodeMode,
pub max_hamming_error: u32,
pub huber_delta_px: f64,
pub tikhonov_alpha_max: f64,
pub sigma_n_sq: f64,
pub structure_tensor_radius: u8,
pub gwlf_transversal_alpha: f64,
pub quad_max_elongation: f64,
pub quad_min_density: f64,
pub quad_extraction_mode: QuadExtractionMode,
}Expand description
Pipeline-level configuration for the detector.
These settings affect the fundamental behavior of the detection pipeline
and are immutable after the Detector is constructed. Use the builder
pattern for ergonomic construction.
Fields§
§threshold_tile_size: usizeTile size for adaptive thresholding (default: 4). Larger tiles are faster but less adaptive to local contrast.
threshold_min_range: u8Minimum intensity range in a tile to be considered valid (default: 10). Tiles with lower range are treated as uniform (no edges).
enable_bilateral: boolEnable bilateral pre-filtering for edge-preserving noise reduction (default: true).
bilateral_sigma_space: f32Bilateral spatial sigma for spatial smoothing (default: 3.0).
bilateral_sigma_color: f32Bilateral color sigma for edge preservation (default: 30.0). Higher values = more smoothing across edges.
enable_sharpening: boolEnable Laplacian sharpening to enhance edges for small tags (default: true).
enable_adaptive_window: boolEnable adaptive threshold window sizing based on gradient (default: true).
threshold_min_radius: usizeMinimum threshold window radius for high-gradient regions (default: 2 = 5x5).
threshold_max_radius: usizeMaximum threshold window radius for low-gradient regions (default: 7 = 15x15).
adaptive_threshold_constant: i16Constant subtracted from local mean in adaptive thresholding (default: 3).
adaptive_threshold_gradient_threshold: u8Gradient magnitude threshold above which the minimum window radius is used (default: 40).
quad_min_area: u32Minimum quad area in pixels (default: 16).
quad_max_aspect_ratio: f32Maximum aspect ratio of bounding box (default: 3.0).
quad_min_fill_ratio: f32Minimum fill ratio (pixel count / bbox area) (default: 0.3).
quad_max_fill_ratio: f32Maximum fill ratio (default: 0.95).
quad_min_edge_length: f64Minimum edge length in pixels (default: 4.0).
quad_min_edge_score: f64Minimum edge alignment score (0.0 to 1.0)
subpixel_refinement_sigma: f64PSF blur factor for subpixel refinement (e.g., 0.6)
segmentation_margin: i16Minimum deviation from threshold for a pixel to be connected in threshold-model CCL (default: 2).
segmentation_connectivity: SegmentationConnectivitySegmentation connectivity (4-way or 8-way).
upscale_factor: usizeFactor to upscale the image before detection (1 = no upscaling). Increasing this to 2 allows detecting smaller tags (e.g., < 15px) at the cost of processing speed (O(N^2)). Nearest-neighbor interpolation is used.
decimation: usizeDecimation factor for preprocessing (1 = no decimation).
nthreads: usizeNumber of threads for parallel processing (0 = auto).
decoder_min_contrast: f64Minimum contrast range for Otsu-based bit classification (default: 20.0). For checkerboard patterns with densely packed tags, lower values (e.g., 10.0) can improve recall on small/blurry tags.
refinement_mode: CornerRefinementModeStrategy for refining corner positions (default: Edge).
decode_mode: DecodeModeDecoding mode (Hard vs Soft).
max_hamming_error: u32Maximum number of Hamming errors allowed for tag decoding (default: 2). Higher values increase recall but also increase false positive rate in noise.
huber_delta_px: f64Huber delta for LM reprojection (pixels) in Fast mode. Residuals beyond this threshold are down-weighted linearly. 1.5 px is a standard robust threshold for sub-pixel corner detectors.
tikhonov_alpha_max: f64Maximum Tikhonov regularisation alpha (px^2) for ill-conditioned corners in Accurate mode. Controls the gain-scheduled regularisation of the Structure Tensor information matrix on foreshortened tags.
sigma_n_sq: f64Pixel noise variance (sigma_n^2) assumed for the Structure Tensor covariance model in Accurate mode. Typical webcams: ~4.0.
structure_tensor_radius: u8Radius (in pixels) of the window used for Structure Tensor computation in Accurate mode. A radius of 2 yields a 5x5 window. Smaller values (1) are better for small tags; larger (3-4) for noisy images.
gwlf_transversal_alpha: f64Alpha parameter for GWLF adaptive transversal windowing. The search band is set to +/- max(2, alpha * edge_length).
quad_max_elongation: f64Maximum elongation (λ_max / λ_min) allowed for a component before contour tracing. 0.0 = disabled. Recommended: 15.0 to reject thin lines and non-square blobs.
quad_min_density: f64Minimum pixel density (pixel_count / bbox_area) required to pass the moments gate. 0.0 = disabled. Recommended: 0.2 to reject sparse/noisy regions.
quad_extraction_mode: QuadExtractionModeQuad extraction mode: legacy contour tracing (default) or EDLines.
Implementations§
Source§impl DetectorConfig
impl DetectorConfig
Sourcepub fn builder() -> DetectorConfigBuilder
pub fn builder() -> DetectorConfigBuilder
Create a new builder for DetectorConfig.
Sourcepub fn validate(&self) -> Result<(), ConfigError>
pub fn validate(&self) -> Result<(), ConfigError>
Validate the configuration, returning an error if any parameter is out of range.
§Errors
Returns [ConfigError] if any parameter violates its constraints.
Sourcepub fn production_default() -> Self
pub fn production_default() -> Self
High-fidelity configuration used for production accuracy evaluations.
This matches the default settings used in the Python CLI and Regression suite:
- Corner Refinement:
Erf - Pre-processing:
Sharpening Enabled - Tile Size:
8
SOTA configuration for dense multi-tag detection (pure_tags / forward scenes).
Optimised for maximum recall on dense scenes with many isolated tags at varying
distances, such as the ICRA 2020 forward/pure_tags_images benchmark.
Key difference from [production_default]: DecodeMode::Soft — LLR-based
decoding recovers tags that Hard-decision misses due to blur or marginal contrast,
yielding ~+19pp recall on ICRA forward (96.2% vs 76.9%) at a modest RMSE cost.
All other parameters match production_default (Erf refinement, sharpening on,
moments culling) to preserve the quad candidate quality that Hard relies on.
Trade-off: Soft decoding is ~2–4× slower on the decode phase. Use Hard
(production_default) when throughput is the primary constraint.
Sourcepub fn sota_checkerboard_default() -> Self
pub fn sota_checkerboard_default() -> Self
SOTA configuration for touching/adjacent tags in checkerboard grid patterns.
Designed for scenes where tag borders share a boundary (saddle corners), such
as the ICRA 2020 forward/checkerboard_corners_images benchmark.
Non-negotiable invariants:
segmentation_connectivity: Four— 8-connectivity merges adjacent tag regions into one component; Four-connectivity correctly separates touching borders.decoder_min_contrast: 10.0— packed tags are low-contrast; the default 20.0 causes the Otsu gate to reject valid tags at shared borders.quad_min_edge_score: 2.0— touching borders produce weaker edge scores; this relaxed threshold prevents false negatives on interior tag edges.enable_sharpening: false— Laplacian sharpening creates halos at shared borders, biasing the threshold and causing merged components.
DecodeMode::Soft is added on top of the checkerboard invariants as it may
further improve recall for low-contrast packed tags.
Sourcepub fn fast_default() -> Self
pub fn fast_default() -> Self
Low-latency configuration for high-speed tracking.
Disables heavy pre-processing and uses lighter corner refinement.
Sourcepub fn sota_metrology_default() -> Self
pub fn sota_metrology_default() -> Self
State-of-the-art metrology configuration for maximum pose accuracy.
Bridges the deterministic GN 2D solver directly to the probabilistic 3D solver:
- Phase 1 (2D Geometric Locking): EdLines Joint Gauss-Newton solver produces sub-pixel corners and their per-corner 2×2 covariance matrices (from H⁻¹).
- Phase 2 (Uncertainty Translation): GN covariances propagate to the pose
solver via
batch.corner_covariances; the Structure Tensor is used as a fallback only if the GN solver diverges for a given corner. - Phase 3 (3D Metrology): Weighted Levenberg-Marquardt minimizes Mahalanobis distance weighted by the GN-derived corner covariances.
Pre-processing filters are disabled to pass the raw PSF directly to the solver.
Hard decoding is used to maintain precision; Soft decode causes a precision
collapse (~10–20%) on EdLines due to the larger number of quad candidates.
For maximum recall on multi-tag scenes use [sota_pure_tags_default].
For touching-tag checkerboard grids use [sota_checkerboard_default].
Pose tuning targets: structure_tensor_radius, sigma_n_sq,
tikhonov_alpha_max, huber_delta_px — sweep these against your sensor profile.
Trait Implementations§
Source§impl Clone for DetectorConfig
impl Clone for DetectorConfig
Source§fn clone(&self) -> DetectorConfig
fn clone(&self) -> DetectorConfig
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for DetectorConfig
impl Debug for DetectorConfig
Source§impl Default for DetectorConfig
impl Default for DetectorConfig
Source§impl PartialEq for DetectorConfig
impl PartialEq for DetectorConfig
impl Copy for DetectorConfig
impl StructuralPartialEq for DetectorConfig
Auto Trait Implementations§
impl Freeze for DetectorConfig
impl RefUnwindSafe for DetectorConfig
impl Send for DetectorConfig
impl Sync for DetectorConfig
impl Unpin for DetectorConfig
impl UnsafeUnpin for DetectorConfig
impl UnwindSafe for DetectorConfig
Blanket Implementations§
Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Source§impl<T> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
Source§impl<T> Instrument for T
impl<T> Instrument for T
Source§fn instrument(self, span: Span) -> Instrumented<Self>
fn instrument(self, span: Span) -> Instrumented<Self>
Source§fn in_current_span(self) -> Instrumented<Self>
fn in_current_span(self) -> Instrumented<Self>
Source§impl<T> IntoEither for T
impl<T> IntoEither for T
Source§fn into_either(self, into_left: bool) -> Either<Self, Self>
fn into_either(self, into_left: bool) -> Either<Self, Self>
self into a Left variant of Either<Self, Self>
if into_left is true.
Converts self into a Right variant of Either<Self, Self>
otherwise. Read moreSource§fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
self into a Left variant of Either<Self, Self>
if into_left(&self) returns true.
Converts self into a Right variant of Either<Self, Self>
otherwise. Read moreSource§impl<T> Pointable for T
impl<T> Pointable for T
Source§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
Source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
self from the equivalent element of its
superset. Read moreSource§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
self is actually part of its subset T (and can be converted to it).Source§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
self.to_subset but without any property checks. Always succeeds.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self to the equivalent element of its superset.