use crate::{Bearing, CameraPoint, FeatureMatch, FeatureWorldMatch, Skew3, WorldPoint};
use derive_more::{AsMut, AsRef, Deref, DerefMut, From, Into};
use nalgebra::{
IsometryMatrix3, Matrix3, Matrix3x2, Matrix6x2, Matrix6x3, Point3, Rotation3, Vector3, SVD,
};
use num_traits::Float;
use sample_consensus::Model;
#[derive(Debug, Clone, Copy, PartialEq, AsMut, AsRef, Deref, DerefMut, From, Into)]
pub struct WorldPose(pub IsometryMatrix3<f64>);
impl<P> Model<FeatureWorldMatch<P>> for WorldPose
where
P: Bearing,
{
fn residual(&self, data: &FeatureWorldMatch<P>) -> f32 {
let WorldPose(iso) = *self;
let FeatureWorldMatch(feature, world) = data;
let new_bearing = (iso * world.coords).normalize();
let bearing_vector = feature.bearing();
(1.0 - bearing_vector.dot(&new_bearing)) as f32
}
}
impl WorldPose {
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) -> Matrix6x2<f64> {
let pr = (self.0.rotation * point.0).coords;
let pc = (self.0 * point.0).coords;
let dp_dt = Matrix3::<f64>::identity();
let dp_dr = Skew3::jacobian_output_to_self(pr);
let dp_dtq = Matrix6x3::<f64>::from_rows(&[
dp_dt.row(0),
dp_dt.row(1),
dp_dt.row(2),
dp_dr.row(0),
dp_dr.row(1),
dp_dr.row(2),
]);
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
}
}
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 IsometryMatrix3<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 IsometryMatrix3<f64>);
impl RelativeCameraPose {
pub fn from_parts(rotation: Rotation3<f64>, translation: Vector3<f64>) -> Self {
Self(IsometryMatrix3::from_parts(translation.into(), rotation))
}
pub fn transform(&self, CameraPoint(point): CameraPoint) -> CameraPoint {
let Self(iso) = *self;
CameraPoint(iso * point)
}
pub fn essential_matrix(&self) -> EssentialMatrix {
EssentialMatrix(self.0.translation.vector.cross_matrix() * *self.0.rotation.matrix())
}
}
#[derive(Debug, Clone, Copy, PartialEq, AsMut, AsRef, Deref, DerefMut, From, Into)]
pub struct UnscaledRelativeCameraPose(pub RelativeCameraPose);
#[derive(Debug, Clone, Copy, PartialEq, PartialOrd, AsMut, AsRef, Deref, DerefMut, From, Into)]
pub struct EssentialMatrix(pub Matrix3<f64>);
impl<P> Model<FeatureMatch<P>> for EssentialMatrix
where
P: Bearing,
{
fn residual(&self, data: &FeatureMatch<P>) -> f32 {
let Self(mat) = *self;
let FeatureMatch(a, b) = data;
let normalized = |p: &P| {
let p = p.bearing_unnormalized();
p / p.z
};
Float::abs((normalized(b).transpose() * mat * normalized(a))[0] as f32)
}
}
impl EssentialMatrix {
pub fn recondition(self, epsilon: f64, max_iterations: usize) -> Option<Self> {
let old_svd = self.try_svd(true, true, epsilon, max_iterations)?;
let mut sources = [0, 1, 2];
sources.sort_unstable_by_key(|&ix| float_ord::FloatOrd(-old_svd.singular_values[ix]));
let mut svd = old_svd;
for (dest, &source) in sources.iter().enumerate() {
svd.singular_values[dest] = old_svd.singular_values[source];
svd.u
.as_mut()
.unwrap()
.column_mut(dest)
.copy_from(&old_svd.u.as_ref().unwrap().column(source));
svd.v_t
.as_mut()
.unwrap()
.row_mut(dest)
.copy_from(&old_svd.v_t.as_ref().unwrap().row(source));
}
svd.singular_values[2] = 0.0;
let new_singular = (svd.singular_values[0] + svd.singular_values[1]) / 2.0;
svd.singular_values[0] = new_singular;
svd.singular_values[1] = new_singular;
let mat = svd.recompose().unwrap();
Some(Self(mat))
}
pub fn possible_rotations_unscaled_translation(
&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_rotations_unscaled_translation(epsilon, max_iterations)
.map(|(rot_a, rot_b, _)| [rot_a, rot_b])
}
pub fn possible_unscaled_poses(
&self,
epsilon: f64,
max_iterations: usize,
) -> Option<[UnscaledRelativeCameraPose; 4]> {
self.possible_rotations_unscaled_translation(epsilon, max_iterations)
.map(|(rot_a, rot_b, t)| {
[
UnscaledRelativeCameraPose(RelativeCameraPose::from_parts(rot_a, t)),
UnscaledRelativeCameraPose(RelativeCameraPose::from_parts(rot_b, t)),
UnscaledRelativeCameraPose(RelativeCameraPose::from_parts(rot_a, -t)),
UnscaledRelativeCameraPose(RelativeCameraPose::from_parts(rot_b, -t)),
]
})
}
pub fn possible_unscaled_poses_bearing(
&self,
epsilon: f64,
max_iterations: usize,
) -> Option<[UnscaledRelativeCameraPose; 2]> {
self.possible_rotations_unscaled_translation(epsilon, max_iterations)
.map(|(rot_a, rot_b, t)| {
[
UnscaledRelativeCameraPose(RelativeCameraPose::from_parts(rot_a, t)),
UnscaledRelativeCameraPose(RelativeCameraPose::from_parts(rot_b, t)),
]
})
}
pub fn solve_unscaled_pose<P>(
&self,
epsilon: f64,
max_iterations: usize,
consensus_ratio: f64,
triangulation_method: impl Fn(UnscaledRelativeCameraPose, P, P) -> Option<Point3<f64>>,
correspondences: impl Iterator<Item = FeatureMatch<P>>,
) -> Option<UnscaledRelativeCameraPose>
where
P: Bearing + Copy,
{
self.possible_unscaled_poses(epsilon, max_iterations)
.and_then(|poses| {
let (ts, total) = correspondences.fold(
([0usize; 4], 0usize),
|(mut ts, total), FeatureMatch(a, b)| {
let trans_and_agree = |pose| {
triangulation_method(pose, a, b)
.map(|p| {
let tp = pose.transform(CameraPoint(p));
p.coords.normalize().dot(&a.bearing()) > 0.0
&& tp.coords.normalize().dot(&b.bearing()) > 0.0
})
.unwrap_or(false)
};
for (tn, &pose) in ts.iter_mut().zip(&poses) {
if trans_and_agree(pose) {
*tn += 1;
}
}
(ts, total + 1)
},
);
if total == 0 {
return None;
}
let (ix, best) = ts
.iter()
.copied()
.enumerate()
.max_by_key(|&(_, t)| t)
.unwrap();
if (best as f64) < consensus_ratio * total as f64 && best != 0 {
return None;
}
Some(poses[ix])
})
}
pub fn solve_pose<P>(
&self,
epsilon: f64,
max_iterations: usize,
consensus_ratio: f64,
triangulation_method: impl Fn(Vector3<f64>, CameraPoint, P) -> Option<f64>,
correspondences: impl Iterator<Item = (CameraPoint, P)> + Clone,
) -> Option<RelativeCameraPose>
where
P: Bearing + Copy,
{
self.possible_unscaled_poses_bearing(epsilon, max_iterations)
.and_then(|poses| {
let (ts, total) = correspondences.fold(
([(0usize, 0.0); 2], 0usize),
|(mut ts, total), (a, b)| {
let trans_and_agree = |pose: UnscaledRelativeCameraPose| {
let untranslated = pose.rotation * a.0;
let t_scale = triangulation_method(
pose.translation.vector,
CameraPoint(untranslated),
b,
)?;
if (untranslated.coords + t_scale * pose.translation.vector)
.dot(&b.bearing())
> 0.0
{
Some(t_scale)
} else {
None
}
};
for (tn, &pose) in ts.iter_mut().zip(&poses) {
if let Some(scale) = trans_and_agree(pose) {
tn.0 += 1;
tn.1 += scale;
}
}
(ts, total + 1)
},
);
if total == 0 {
return None;
}
let (ix, (best_num, scale_acc)) = ts
.iter()
.copied()
.enumerate()
.max_by_key(|&(_, (t, _))| t)
.unwrap();
if (best_num as f64) < consensus_ratio * total as f64 && best_num != 0 {
return None;
}
let scale = scale_acc / best_num as f64;
Some(RelativeCameraPose::from_parts(
poses[ix].rotation,
scale * poses[ix].translation.vector,
))
})
}
}