use crate::{
geom, CameraPoint, KeyPointWorldMatch, KeyPointsMatch, NormalizedKeyPoint, WorldPoint,
};
use approx::AbsDiffEq;
use core::cmp::Ordering;
use derive_more::{AsMut, AsRef, Deref, DerefMut, From, Into};
use nalgebra::{
dimension::{U2, U3, U7},
Isometry3, Matrix3, Matrix3x2, MatrixMN, Quaternion, Rotation3, Translation3, UnitQuaternion,
Vector2, Vector3, Vector4, VectorN, SVD,
};
use sample_consensus::Model;
#[derive(Debug, Clone, Copy, PartialEq, AsMut, AsRef, Deref, DerefMut, From, Into)]
pub struct WorldPose(pub Isometry3<f32>);
impl Model<KeyPointWorldMatch> for WorldPose {
fn residual(&self, data: &KeyPointWorldMatch) -> f32 {
let WorldPose(iso) = *self;
let KeyPointWorldMatch(image, world) = *data;
let new_bearing = (iso * world.coords).normalize();
let bearing_vector = image.to_homogeneous().normalize();
1.0 - bearing_vector.dot(&new_bearing)
}
}
impl WorldPose {
pub fn projection_error(&self, correspondence: KeyPointWorldMatch) -> Vector2<f32> {
let KeyPointWorldMatch(NormalizedKeyPoint(image), world) = correspondence;
let NormalizedKeyPoint(projection) = self.project(world);
image - projection
}
pub fn project(&self, point: WorldPoint) -> NormalizedKeyPoint {
self.transform(point).into()
}
pub fn transform(&self, WorldPoint(point): WorldPoint) -> CameraPoint {
let WorldPose(iso) = *self;
CameraPoint((iso * point).coords)
}
#[rustfmt::skip]
pub fn projection_pose_jacobian(&self, point: WorldPoint) -> MatrixMN<f32, U7, U2> {
let q = self.0.rotation.quaternion().coords;
let p = point.0.coords;
let pc = (self.0 * point.0).coords;
let dp_dt = Matrix3::identity();
let qv_qv_p = Matrix3::new(
q.y * p.y + q.z * p.z, q.y * p.x - 2.0 * q.x * p.y, q.z * p.x - 2.0 * q.x * p.z,
q.x * p.y - 2.0 * q.y * p.x, q.x * p.x + q.z * p.z, q.z * p.y - 2.0 * q.y * p.z,
q.x * p.z - 2.0 * q.z * p.x, q.y * p.z - 2.0 * q.z * p.y, q.x * p.x + q.y * p.y
);
let qv_p = Matrix3::new(
0.0, -p.z, p.y,
p.z, 0.0, -p.x,
-p.y, p.x, 0.0,
);
let dp_dqv = 2.0 * (q.w * qv_p + qv_qv_p);
let dp_ds = 2.0 * q.xyz().cross(&p);
let dp_dtq = MatrixMN::<f32, U7, U3>::from_rows(&[
dp_dt.row(0).into(),
dp_dt.row(1).into(),
dp_dt.row(2).into(),
dp_dqv.row(0).into(),
dp_dqv.row(1).into(),
dp_dqv.row(2).into(),
dp_ds.transpose(),
]);
let pcz = pc.z.recip();
let npcz2 = -(pcz * pcz);
let dk_dp = Matrix3x2::new(
pcz, 0.0,
0.0, pcz,
npcz2, npcz2,
);
dp_dtq * dk_dp
}
pub fn to_vec(&self) -> VectorN<f32, U7> {
let Self(iso) = *self;
let t = iso.translation.vector;
let rc = iso.rotation.quaternion().coords;
t.push(rc.x).push(rc.y).push(rc.z).push(rc.w)
}
pub fn from_vec(v: VectorN<f32, U7>) -> Self {
Self(Isometry3::from_parts(
Translation3::from(Vector3::new(v[0], v[1], v[2])),
UnitQuaternion::from_quaternion(Quaternion::from(Vector4::new(v[3], v[4], v[5], v[6]))),
))
}
}
impl From<CameraPose> for WorldPose {
fn from(camera: CameraPose) -> Self {
Self(camera.inverse())
}
}
#[derive(Debug, Clone, Copy, PartialEq, AsMut, AsRef, Deref, DerefMut, From, Into)]
pub struct CameraPose(pub Isometry3<f32>);
impl From<WorldPose> for CameraPose {
fn from(world: WorldPose) -> Self {
Self(world.inverse())
}
}
#[derive(Debug, Clone, Copy, PartialEq, AsMut, AsRef, Deref, DerefMut, From, Into)]
pub struct RelativeCameraPose(pub Isometry3<f32>);
impl RelativeCameraPose {
pub fn transform(&self, CameraPoint(point): CameraPoint) -> CameraPoint {
let Self(iso) = *self;
CameraPoint(iso * point)
}
}
#[derive(Debug, Clone, Copy, PartialEq, PartialOrd, AsMut, AsRef, Deref, DerefMut, From, Into)]
pub struct EssentialMatrix(pub Matrix3<f32>);
impl Model<KeyPointsMatch> for EssentialMatrix {
fn residual(&self, data: &KeyPointsMatch) -> f32 {
let Self(mat) = *self;
let KeyPointsMatch(NormalizedKeyPoint(a), NormalizedKeyPoint(b)) = *data;
(a.to_homogeneous().transpose() * mat * b.to_homogeneous())[0]
}
}
impl EssentialMatrix {
pub fn possible_poses(
&self,
max_iterations: usize,
) -> Option<(Rotation3<f32>, Rotation3<f32>, Vector3<f32>)> {
let Self(essential) = *self;
let w = Matrix3::new(0.0, -1.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0);
let wt = w.transpose();
let svd = SVD::try_new(
essential,
true,
true,
f32::default_epsilon(),
max_iterations,
);
let u_v = svd.map(|svd| {
if let SVD {
u: Some(u),
v_t: Some(v_t),
..
} = svd
{
(u, v_t.transpose())
} else {
panic!("Didn't get U and V matrix in SVD");
}
});
let u_v = u_v.map(|(mut u, mut v)| {
let fix_det = |m: &mut Matrix3<f32>| {
if m.determinant() < 0.0 {
for n in m.column_mut(2).iter_mut() {
*n *= -1.0;
}
}
};
fix_det(&mut u);
fix_det(&mut v);
(u, v)
});
u_v.map(|(u, v)| {
let vt = v.transpose();
(
Rotation3::from_matrix_unchecked(u * wt * vt),
Rotation3::from_matrix_unchecked(u * w * vt),
u.column(2).into_owned().normalize(),
)
})
}
pub fn solve_pose(
&self,
consensus_ratio: f32,
max_iterations: usize,
correspondences: impl Iterator<Item = (f32, NormalizedKeyPoint, NormalizedKeyPoint)>,
) -> Option<RelativeCameraPose> {
self.possible_poses(max_iterations)
.and_then(|(rot_x, rot_y, t)| {
let tx_dir = rot_x.transpose() * t;
let ty_dir = rot_y.transpose() * t;
let (xt, yt, xn, yn, total) = correspondences.fold(
(0.0, 0.0, 0usize, 0usize, 0usize),
|(mut xt, mut yt, mut xn, mut yn, total), (depth, a, b)| {
let a_point = depth * a.with_depth(1.0).0;
let trans_and_agree = |rotation, t_dir| {
let untranslated: Vector3<f32> = rotation * a_point;
let translation_scale =
geom::reproject_along_translation(untranslated.xy(), b, t_dir);
(
translation_scale,
translation_scale * t_dir.z + untranslated.z > 1.0,
)
};
if let (scale, true) = trans_and_agree(rot_x, tx_dir) {
xt += scale;
xn += 1;
}
if let (scale, true) = trans_and_agree(rot_y, ty_dir) {
yt += scale;
yn += 1;
}
(xt, yt, xn, yn, total + 1)
},
);
if (core::cmp::max(xn, yn) as f32 / total as f32) < consensus_ratio {
return None;
}
let (rot, trans) = match xn.cmp(&yn) {
Ordering::Equal => return None,
Ordering::Greater => (rot_x, xt / xn as f32 * tx_dir),
Ordering::Less => (rot_y, yt / yn as f32 * ty_dir),
};
Some(RelativeCameraPose(Isometry3::from_parts(
trans.into(),
UnitQuaternion::from_rotation_matrix(&rot),
)))
})
}
}