1use crate::batch::{DetectionBatch, DetectionBatchView};
2use crate::config::DetectorConfig;
3use crate::decoder::{TagDecoder, family_to_decoder};
4use crate::error::DetectorError;
5use crate::image::ImageView;
6use bumpalo::Bump;
7
8pub struct DetectorState {
13 pub arena: Bump,
15 pub batch: DetectionBatch,
17 pub upscale_buf: Vec<u8>,
19}
20
21impl DetectorState {
22 #[must_use]
24 pub fn new() -> Self {
25 Self {
26 arena: Bump::new(),
27 batch: DetectionBatch::new(),
28 upscale_buf: Vec::new(),
29 }
30 }
31
32 pub fn reset(&mut self) {
34 self.arena.reset();
35 }
36}
37
38impl Default for DetectorState {
39 fn default() -> Self {
40 Self::new()
41 }
42}
43
44pub struct Detector {
48 config: DetectorConfig,
49 decoders: Vec<Box<dyn TagDecoder + Send + Sync>>,
50 state: DetectorState,
51}
52
53impl Default for Detector {
54 fn default() -> Self {
55 Self::new()
56 }
57}
58
59impl Detector {
60 #[must_use]
62 pub fn new() -> Self {
63 Self::builder().build()
64 }
65
66 #[must_use]
68 pub fn builder() -> DetectorBuilder {
69 DetectorBuilder::new()
70 }
71
72 #[must_use]
74 pub fn with_config(config: DetectorConfig) -> Self {
75 Self::builder().with_config(config).build()
76 }
77
78 #[must_use]
80 pub fn state(&self) -> &DetectorState {
81 &self.state
82 }
83
84 pub fn set_families(&mut self, families: &[crate::config::TagFamily]) {
86 self.decoders.clear();
87 for &family in families {
88 self.decoders
89 .push(crate::decoder::family_to_decoder(family));
90 }
91 }
92
93 #[allow(clippy::similar_names)]
102 #[allow(clippy::too_many_lines)]
103 pub fn detect(
104 &mut self,
105 img: &ImageView,
106 intrinsics: Option<&crate::pose::CameraIntrinsics>,
107 tag_size: Option<f64>,
108 pose_mode: crate::config::PoseEstimationMode,
109 debug_telemetry: bool,
110 ) -> Result<DetectionBatchView<'_>, DetectorError> {
111 self.state.reset();
112 let state = &mut self.state;
113
114 let (detection_img, _effective_scale, refinement_img) = if self.config.decimation > 1 {
115 let new_w = img.width / self.config.decimation;
116 let new_h = img.height / self.config.decimation;
117 let decimated_data = state.arena.alloc_slice_fill_copy(new_w * new_h, 0u8);
118 let decimated_img = img
119 .decimate_to(self.config.decimation, decimated_data)
120 .map_err(DetectorError::Preprocessing)?;
121 (decimated_img, 1.0 / self.config.decimation as f64, *img)
122 } else if self.config.upscale_factor > 1 {
123 let new_w = img.width * self.config.upscale_factor;
124 let new_h = img.height * self.config.upscale_factor;
125 state.upscale_buf.resize(new_w * new_h, 0);
126
127 let upscaled_img = img
128 .upscale_to(self.config.upscale_factor, &mut state.upscale_buf)
129 .map_err(DetectorError::Preprocessing)?;
130 (
131 upscaled_img,
132 self.config.upscale_factor as f64,
133 upscaled_img,
134 )
135 } else {
136 (*img, 1.0, *img)
137 };
138
139 let img = &detection_img;
140
141 let filtered_img = if self.config.enable_bilateral {
143 let filtered = state
144 .arena
145 .alloc_slice_fill_copy(img.width * img.height, 0u8);
146 crate::filter::bilateral_filter(
147 &state.arena,
148 img,
149 filtered,
150 3, self.config.bilateral_sigma_space,
152 self.config.bilateral_sigma_color,
153 );
154 ImageView::new(filtered, img.width, img.height, img.width)
155 .map_err(DetectorError::InvalidImage)?
156 } else {
157 *img
158 };
159
160 let sharpened_img = if self.config.enable_sharpening {
162 let sharpened = state
163 .arena
164 .alloc_slice_fill_copy(filtered_img.width * filtered_img.height, 0u8);
165 crate::filter::laplacian_sharpen(&filtered_img, sharpened);
166
167 ImageView::new(
168 sharpened,
169 filtered_img.width,
170 filtered_img.height,
171 filtered_img.width,
172 )
173 .map_err(DetectorError::InvalidImage)?
174 } else {
175 filtered_img
176 };
177
178 let binarized = state
179 .arena
180 .alloc_slice_fill_copy(img.width * img.height, 0u8);
181 let threshold_map = state
182 .arena
183 .alloc_slice_fill_copy(img.width * img.height, 0u8);
184
185 {
187 let engine = crate::threshold::ThresholdEngine::from_config(&self.config);
188 let tile_stats = engine.compute_tile_stats(&state.arena, &sharpened_img);
189 engine.apply_threshold_with_map(
190 &state.arena,
191 &sharpened_img,
192 &tile_stats,
193 binarized,
194 threshold_map,
195 );
196 }
197
198 let label_result = crate::segmentation::label_components_threshold_model(
200 &state.arena,
201 sharpened_img.data,
202 sharpened_img.stride,
203 threshold_map,
204 img.width,
205 img.height,
206 self.config.segmentation_connectivity == crate::config::SegmentationConnectivity::Eight,
207 self.config.quad_min_area,
208 self.config.segmentation_margin,
209 );
210
211 let (n, unrefined) = crate::quad::extract_quads_soa(
213 &mut state.batch,
214 &sharpened_img,
215 &label_result,
216 &self.config,
217 self.config.decimation,
218 &refinement_img,
219 debug_telemetry,
220 );
221
222 let mut jitter_ptr = std::ptr::null();
224 let mut num_jitter = 0;
225 if let (true, Some(unrefined_pts)) = (debug_telemetry, unrefined) {
226 num_jitter = unrefined_pts.len();
228 let jitter = state.arena.alloc_slice_fill_copy(num_jitter * 8, 0.0f32);
230 for (i, unrefined_corners) in unrefined_pts.iter().enumerate() {
231 for (j, unrefined_corner) in unrefined_corners.iter().enumerate() {
232 let dx = state.batch.corners[i][j].x - unrefined_corner.x as f32;
233 let dy = state.batch.corners[i][j].y - unrefined_corner.y as f32;
234 jitter[i * 8 + j * 2] = dx;
235 jitter[i * 8 + j * 2 + 1] = dy;
236 }
237 }
238 jitter_ptr = jitter.as_ptr();
239 }
240
241 crate::decoder::compute_homographies_soa(
243 &state.batch.corners[0..n],
244 &mut state.batch.homographies[0..n],
245 );
246
247 crate::decoder::decode_batch_soa(
249 &mut state.batch,
250 n,
251 &refinement_img,
252 &self.decoders,
253 &self.config,
254 );
255
256 let v = state.batch.partition(n);
258
259 let (repro_errors_ptr, num_repro) = run_pose_refinement(
261 &mut state.batch,
262 &state.arena,
263 v,
264 intrinsics,
265 tag_size,
266 &refinement_img,
267 pose_mode,
268 &self.config,
269 debug_telemetry,
270 );
271
272 let telemetry = if debug_telemetry {
276 Some(crate::batch::TelemetryPayload {
277 binarized_ptr: binarized.as_ptr(),
278 threshold_map_ptr: threshold_map.as_ptr(),
279 subpixel_jitter_ptr: jitter_ptr,
280 num_jitter,
281 reprojection_errors_ptr: repro_errors_ptr,
282 num_reprojection: num_repro,
283 width: img.width,
284 height: img.height,
285 stride: img.width,
286 })
287 } else {
288 None
289 };
290
291 Ok(self.state.batch.view_with_telemetry(v, n, telemetry))
292 }
293
294 #[must_use]
296 pub fn config(&self) -> &DetectorConfig {
297 &self.config
298 }
299}
300
301#[allow(clippy::too_many_arguments)]
305fn run_pose_refinement(
306 batch: &mut crate::batch::DetectionBatch,
307 arena: &bumpalo::Bump,
308 v: usize,
309 intrinsics: Option<&crate::pose::CameraIntrinsics>,
310 tag_size: Option<f64>,
311 refinement_img: &ImageView,
312 pose_mode: crate::config::PoseEstimationMode,
313 config: &DetectorConfig,
314 debug_telemetry: bool,
315) -> (*const f32, usize) {
316 let mut repro_errors_ptr = std::ptr::null();
317 let mut num_repro = 0;
318
319 if let (Some(intr), Some(size)) = (intrinsics, tag_size) {
320 crate::pose::refine_poses_soa_with_config(
321 batch,
322 v,
323 intr,
324 size,
325 Some(refinement_img),
326 pose_mode,
327 config,
328 );
329
330 if debug_telemetry {
331 num_repro = v;
332 let repro_errors = arena.alloc_slice_fill_copy(num_repro, 0.0f32);
333
334 let model_pts = [
335 nalgebra::Vector3::new(0.0, 0.0, 0.0),
336 nalgebra::Vector3::new(size, 0.0, 0.0),
337 nalgebra::Vector3::new(size, size, 0.0),
338 nalgebra::Vector3::new(0.0, size, 0.0),
339 ];
340
341 for (i, repro_error) in repro_errors.iter_mut().enumerate().take(v) {
342 let det_pose_data = batch.poses[i].data;
343 let det_t = nalgebra::Vector3::new(
344 f64::from(det_pose_data[0]),
345 f64::from(det_pose_data[1]),
346 f64::from(det_pose_data[2]),
347 );
348 let det_q = nalgebra::UnitQuaternion::from_quaternion(nalgebra::Quaternion::new(
349 f64::from(det_pose_data[6]),
350 f64::from(det_pose_data[3]),
351 f64::from(det_pose_data[4]),
352 f64::from(det_pose_data[5]),
353 ));
354
355 let pose = crate::pose::Pose {
356 rotation: *det_q.to_rotation_matrix().matrix(),
357 translation: det_t,
358 };
359
360 let mut sum_sq_err = 0.0;
361 for (j, model_pt) in model_pts.iter().enumerate() {
362 let proj = pose.project(model_pt, intr);
363 let dx = proj[0] - f64::from(batch.corners[i][j].x);
364 let dy = proj[1] - f64::from(batch.corners[i][j].y);
365 sum_sq_err += dx * dx + dy * dy;
366 }
367 *repro_error = (sum_sq_err / 4.0).sqrt() as f32;
368 }
369 repro_errors_ptr = repro_errors.as_ptr();
370 }
371 }
372
373 (repro_errors_ptr, num_repro)
374}
375
376pub struct DetectorBuilder {
378 config: DetectorConfig,
379 families: Vec<crate::config::TagFamily>,
380}
381
382impl DetectorBuilder {
383 #[must_use]
385 pub fn new() -> Self {
386 Self {
387 config: DetectorConfig::default(),
388 families: Vec::new(),
389 }
390 }
391
392 #[must_use]
394 pub fn with_config(mut self, config: DetectorConfig) -> Self {
395 self.config = config;
396 self
397 }
398
399 #[must_use]
401 pub fn with_decimation(mut self, decimation: usize) -> Self {
402 self.config.decimation = decimation;
403 self
404 }
405
406 #[must_use]
408 pub fn with_family(mut self, family: crate::config::TagFamily) -> Self {
409 if !self.families.contains(&family) {
410 self.families.push(family);
411 }
412 self
413 }
414
415 #[must_use]
417 pub fn with_threads(mut self, threads: usize) -> Self {
418 self.config.nthreads = threads;
419 self
420 }
421
422 #[must_use]
424 pub fn with_upscale_factor(mut self, factor: usize) -> Self {
425 self.config.upscale_factor = factor;
426 self
427 }
428
429 #[must_use]
431 pub fn with_corner_refinement(mut self, mode: crate::config::CornerRefinementMode) -> Self {
432 self.config.refinement_mode = mode;
433 self
434 }
435
436 #[must_use]
438 pub fn with_decode_mode(mut self, mode: crate::config::DecodeMode) -> Self {
439 self.config.decode_mode = mode;
440 self
441 }
442
443 #[must_use]
445 pub fn with_connectivity(
446 mut self,
447 connectivity: crate::config::SegmentationConnectivity,
448 ) -> Self {
449 self.config.segmentation_connectivity = connectivity;
450 self
451 }
452
453 #[must_use]
455 pub fn with_threshold_tile_size(mut self, size: usize) -> Self {
456 self.config.threshold_tile_size = size;
457 self
458 }
459
460 #[must_use]
462 pub fn with_threshold_min_range(mut self, range: u8) -> Self {
463 self.config.threshold_min_range = range;
464 self
465 }
466
467 #[must_use]
469 pub fn with_adaptive_threshold_constant(mut self, c: i16) -> Self {
470 self.config.adaptive_threshold_constant = c;
471 self
472 }
473
474 #[must_use]
476 pub fn with_quad_min_area(mut self, area: u32) -> Self {
477 self.config.quad_min_area = area;
478 self
479 }
480
481 #[must_use]
483 pub fn with_quad_min_fill_ratio(mut self, ratio: f32) -> Self {
484 self.config.quad_min_fill_ratio = ratio;
485 self
486 }
487
488 #[must_use]
490 pub fn with_quad_min_edge_score(mut self, score: f64) -> Self {
491 self.config.quad_min_edge_score = score;
492 self
493 }
494
495 #[must_use]
497 pub fn with_max_hamming_error(mut self, errors: u32) -> Self {
498 self.config.max_hamming_error = errors;
499 self
500 }
501
502 #[must_use]
504 pub fn with_decoder_min_contrast(mut self, contrast: f64) -> Self {
505 self.config.decoder_min_contrast = contrast;
506 self
507 }
508
509 #[must_use]
511 pub fn with_sharpening(mut self, enable: bool) -> Self {
512 self.config.enable_sharpening = enable;
513 self
514 }
515
516 #[must_use]
518 pub fn build(self) -> Detector {
519 let mut decoders = Vec::new();
520 let families = if self.families.is_empty() {
521 vec![crate::config::TagFamily::AprilTag36h11]
522 } else {
523 self.families
524 };
525 for family in families {
526 decoders.push(family_to_decoder(family));
527 }
528
529 Detector {
530 config: self.config,
531 decoders,
532 state: DetectorState::new(),
533 }
534 }
535}
536
537impl Default for DetectorBuilder {
538 fn default() -> Self {
539 Self::new()
540 }
541}