use crate::{CameraPoint, KeyPointWorldMatch, KeyPointsMatch, NormalizedKeyPoint, WorldPoint};
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<f64>);
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)) as f32
}
}
impl WorldPose {
pub fn projection_error(&self, correspondence: KeyPointWorldMatch) -> Vector2<f64> {
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)
}
#[rustfmt::skip]
pub fn projection_pose_jacobian(&self, point: WorldPoint) -> MatrixMN<f64, 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::<f64, 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<f64, 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<f64, 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<f64>);
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<f64>);
impl RelativeCameraPose {
pub fn transform(&self, CameraPoint(point): CameraPoint) -> CameraPoint {
let Self(iso) = *self;
CameraPoint(iso * point)
}
pub fn essential_matrix(&self) -> EssentialMatrix {
EssentialMatrix(
*self.0.rotation.to_rotation_matrix().matrix()
* self.0.translation.vector.cross_matrix(),
)
}
}
#[derive(Debug, Clone, Copy, PartialEq, PartialOrd, AsMut, AsRef, Deref, DerefMut, From, Into)]
pub struct EssentialMatrix(pub Matrix3<f64>);
impl Model<KeyPointsMatch> for EssentialMatrix {
fn residual(&self, data: &KeyPointsMatch) -> f32 {
let Self(mat) = *self;
let KeyPointsMatch(NormalizedKeyPoint(a), NormalizedKeyPoint(b)) = *data;
(b.to_homogeneous().transpose() * mat * a.to_homogeneous())[0] as f32
}
}
impl EssentialMatrix {
pub fn possible_poses_unfixed_bearing(
&self,
epsilon: f64,
max_iterations: usize,
) -> Option<(Rotation3<f64>, Rotation3<f64>, Vector3<f64>)> {
let Self(essential) = *self;
let essential = essential;
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, epsilon, max_iterations);
let u_v_t = svd.map(|svd| {
if let SVD {
u: Some(u),
v_t: Some(v_t),
singular_values,
} = svd
{
let mut sources: [usize; 3] = [0, 1, 2];
sources.sort_unstable_by_key(|&ix| float_ord::FloatOrd(-singular_values[ix]));
let mut sorted_u = Matrix3::zeros();
let mut sorted_v_t = Matrix3::zeros();
for (&ix, mut column) in sources.iter().zip(sorted_u.column_iter_mut()) {
column.copy_from(&u.column(ix));
}
for (&ix, mut row) in sources.iter().zip(sorted_v_t.row_iter_mut()) {
row.copy_from(&v_t.row(ix));
}
(sorted_u, sorted_v_t)
} else {
panic!("Didn't get U and V matrix in SVD");
}
});
let u_v_t = u_v_t.map(|(mut u, mut v_t)| {
if u.determinant() < 0.0 {
for n in u.column_mut(2).iter_mut() {
*n *= -1.0;
}
}
if v_t.determinant() < 0.0 {
for n in v_t.row_mut(2).iter_mut() {
*n *= -1.0;
}
}
(u, v_t)
});
u_v_t.map(|(u, v_t)| {
(
Rotation3::from_matrix_unchecked(u * w * v_t),
Rotation3::from_matrix_unchecked(u * wt * v_t),
u.column(2).into_owned(),
)
})
}
pub fn possible_rotations(
&self,
epsilon: f64,
max_iterations: usize,
) -> Option<[Rotation3<f64>; 2]> {
self.possible_poses_unfixed_bearing(epsilon, max_iterations)
.map(|(rot_a, rot_b, _)| [rot_a, rot_b])
}
pub fn possible_rotations_and_bearings(
&self,
epsilon: f64,
max_iterations: usize,
) -> Option<[(Rotation3<f64>, Vector3<f64>); 2]> {
self.possible_poses_unfixed_bearing(epsilon, max_iterations)
.map(|(rot_a, rot_b, t)| {
[
(rot_a, rot_a.transpose() * t),
(rot_b, rot_b.transpose() * t),
]
})
}
pub fn solve_pose(
&self,
consensus_ratio: f64,
epsilon: f64,
max_iterations: usize,
bearing_scale: impl Fn(Vector3<f64>, CameraPoint, NormalizedKeyPoint) -> f64,
correspondences: impl Iterator<Item = (CameraPoint, NormalizedKeyPoint)>,
) -> Option<RelativeCameraPose> {
self.possible_rotations_and_bearings(epsilon, max_iterations)
.and_then(|poses| {
let (ts, total) = correspondences.fold(
([(0.0, 0usize); 2], 0usize),
|(mut ts, total), (a, b)| {
let trans_and_agree = |(rot, bearing)| {
let untranslated = CameraPoint(rot * a.0);
let translation_scale = bearing_scale(bearing, untranslated, b);
(
translation_scale,
translation_scale * bearing.z + untranslated.z > 1.0,
)
};
for (tn, &pose) in ts.iter_mut().zip(&poses) {
if let (scale, true) = trans_and_agree(pose) {
tn.0 += scale;
tn.1 += 1;
}
}
(ts, total + 1)
},
);
if total == 0 {
return None;
}
let best = core::cmp::max(ts[0].1, ts[1].1);
if (best as f64 / total as f64) < consensus_ratio && best != 0 {
return None;
}
let (rot, trans) = match ts[0].1.cmp(&ts[1].1) {
Ordering::Equal => return None,
Ordering::Greater => (poses[0].0, poses[0].1 * ts[0].0 / ts[0].1 as f64),
Ordering::Less => (poses[1].0, poses[1].1 * ts[1].0 / ts[1].1 as f64),
};
Some(RelativeCameraPose(Isometry3::from_parts(
trans.into(),
UnitQuaternion::from_rotation_matrix(&rot),
)))
})
}
}