pub(crate) mod batch;
pub mod board;
pub mod camera;
pub mod charuco;
pub mod config;
pub(crate) mod decoder;
pub mod detector;
pub(crate) mod dictionaries;
pub(crate) mod edge_refinement;
pub(crate) mod edlines;
pub mod error;
pub(crate) mod filter;
pub(crate) mod funnel;
pub(crate) mod gradient;
pub(crate) mod gwlf;
pub mod image;
pub mod pose;
pub(crate) mod pose_weighted;
pub(crate) mod quad;
pub(crate) mod segmentation;
pub(crate) mod simd;
pub(crate) mod simd_ccl_fusion;
pub(crate) mod strategy;
#[cfg(any(test, feature = "bench-internals"))]
pub(crate) mod test_utils;
pub(crate) mod threshold;
pub(crate) mod workspace;
pub use crate::batch::TelemetryPayload;
pub use crate::board::{AprilGridTopology, BoardConfigError, CharucoTopology};
#[cfg(feature = "non_rectified")]
pub use crate::camera::{BrownConradyModel, KannalaBrandtModel};
pub use crate::camera::{CameraModel, PinholeModel};
pub use crate::config::{
CornerRefinementMode, DecodeMode, DetectOptions, DetectorConfig, PoseEstimationMode,
QuadExtractionMode, TagFamily,
};
pub use crate::detector::{Detector, DetectorBuilder, FrameContext, LocusEngine};
pub use crate::error::{ConfigError, DetectorError};
pub use crate::image::ImageView;
pub use crate::pose::{CameraIntrinsics, DistortionCoeffs};
#[cfg(feature = "bench-internals")]
pub mod bench_api {
pub use crate::batch::*;
pub use crate::camera::*;
pub use crate::decoder::*;
pub use crate::dictionaries::*;
pub use crate::edge_refinement::*;
pub use crate::filter::*;
pub use crate::funnel::*;
pub use crate::gwlf::*;
pub use crate::pose::*;
pub use crate::pose_weighted::bench_compute_corner_covariance;
pub use crate::quad::*;
pub use crate::segmentation::*;
pub use crate::simd::sampler::*;
pub use crate::simd_ccl_fusion::*;
pub use crate::strategy::*;
pub use crate::test_utils::*;
pub use crate::threshold::*;
}
#[derive(Clone, Debug, Default)]
pub struct Detection {
pub id: u32,
pub center: [f64; 2],
pub corners: [[f64; 2]; 4],
pub hamming: u32,
pub rotation: u8,
pub decision_margin: f64,
pub bits: u64,
pub pose: Option<crate::pose::Pose>,
pub pose_covariance: Option<[[f64; 6]; 6]>,
}
impl Detection {
#[must_use]
#[allow(clippy::cast_sign_loss)]
pub fn aabb(&self) -> (usize, usize, usize, usize) {
let mut min_x = f64::INFINITY;
let mut min_y = f64::INFINITY;
let max_x = self
.corners
.iter()
.fold(f64::NEG_INFINITY, |acc, p| acc.max(p[0]));
let max_y = self
.corners
.iter()
.fold(f64::NEG_INFINITY, |acc, p| acc.max(p[1]));
for p in &self.corners {
min_x = min_x.min(p[0]);
min_y = min_y.min(p[1]);
}
(
min_x.floor().max(0.0) as usize,
min_y.floor().max(0.0) as usize,
max_x.ceil().max(0.0) as usize,
max_y.ceil().max(0.0) as usize,
)
}
}
#[derive(Clone, Copy, Debug, Default)]
pub struct Point {
pub x: f64,
pub y: f64,
}
pub use crate::pose::Pose;
#[must_use]
pub fn core_info() -> String {
"Locus Core v0.1.0 Engine (Encapsulated)".to_string()
}