use anyhow::Result;
use vision_calibration_core::{FxFyCxCySkew, Iso3, Pt2, Pt3, RansacOptions, Real};
mod dlt;
mod epnp;
mod p3p;
mod pose_utils;
mod ransac;
pub use dlt::dlt;
pub use epnp::epnp;
pub use p3p::p3p;
pub use ransac::dlt_ransac;
#[derive(Debug, Clone, Copy)]
pub struct PnpSolver;
impl PnpSolver {
pub fn dlt(world: &[Pt3], image: &[Pt2], k: &FxFyCxCySkew<Real>) -> Result<Iso3> {
dlt::dlt(world, image, k)
}
pub fn p3p(world: &[Pt3], image: &[Pt2], k: &FxFyCxCySkew<Real>) -> Result<Vec<Iso3>> {
p3p::p3p(world, image, k)
}
pub fn epnp(world: &[Pt3], image: &[Pt2], k: &FxFyCxCySkew<Real>) -> Result<Iso3> {
epnp::epnp(world, image, k)
}
pub fn dlt_ransac(
world: &[Pt3],
image: &[Pt2],
k: &FxFyCxCySkew<Real>,
opts: &RansacOptions,
) -> Result<(Iso3, Vec<usize>)> {
ransac::dlt_ransac(world, image, k, opts)
}
}