camera_intrinsic_calibration/optimization/
factors.rs

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
use crate::types::DVecVec3;

use camera_intrinsic_model::*;
use nalgebra as na;
use tiny_solver::factors::Factor;

#[derive(Clone)]
pub struct ModelConvertFactor {
    pub source: GenericModel<f64>,
    pub target: GenericModel<f64>,
    pub p3ds: Vec<na::Vector3<f64>>,
}

impl ModelConvertFactor {
    pub fn new(
        source: &GenericModel<f64>,
        target: &GenericModel<f64>,
        edge_pixels: u32,
        steps: usize,
    ) -> ModelConvertFactor {
        if source.width().round() as u32 != target.width().round() as u32 {
            panic!("source width and target width are not the same.")
        } else if source.height().round() as u32 != target.height().round() as u32 {
            panic!("source height and target height are not the same.")
        }
        let mut p2ds = Vec::new();
        for r in (edge_pixels..source.height() as u32 - edge_pixels).step_by(steps) {
            for c in (edge_pixels..source.width() as u32 - edge_pixels).step_by(steps) {
                p2ds.push(na::Vector2::new(c as f64, r as f64));
            }
        }
        let p3ds = source.unproject(&p2ds);
        let p3ds: Vec<_> = p3ds
            .iter()
            .filter_map(|p| p.as_ref().map(|pp| pp.cast()))
            .collect();
        ModelConvertFactor {
            source: source.cast(),
            target: target.cast(),
            p3ds,
        }
    }
    pub fn residaul_num(&self) -> usize {
        self.p3ds.len() * 2
    }
}

impl<T: na::RealField> Factor<T> for ModelConvertFactor {
    fn residual_func(&self, params: &[nalgebra::DVector<T>]) -> nalgebra::DVector<T> {
        let model = self.target.cast::<T>().new_from_params(&params[0]);
        let p3d_template: Vec<_> = self.p3ds.iter().map(|&p| p.cast::<T>()).collect();
        let p2ds0 = self.source.cast::<T>().project(&p3d_template);
        let p2ds1 = model.project(&p3d_template);
        let diff: Vec<_> = p2ds0
            .iter()
            .zip(p2ds1)
            .flat_map(|(p0, p1)| {
                if let Some(p0) = p0 {
                    if let Some(p1) = p1 {
                        let pp = p0 - p1;
                        return vec![pp[0].clone(), pp[1].clone()];
                    }
                }
                vec![T::from_f64(10000.0).unwrap(), T::from_f64(10000.0).unwrap()]
            })
            .collect();
        na::DVector::from_vec(diff)
    }
}

pub struct UCMInitFocalAlphaFactor {
    pub target: GenericModel<f64>,
    pub p3d: na::Point3<f64>,
    pub p2d: na::Vector2<f64>,
}

impl UCMInitFocalAlphaFactor {
    pub fn new(
        target: &GenericModel<f64>,
        p3d: &glam::Vec3,
        p2d: &glam::Vec2,
    ) -> UCMInitFocalAlphaFactor {
        let target = target.cast();
        let p3d = na::Point3::new(p3d.x, p3d.y, p3d.z).cast();
        let p2d = na::Vector2::new(p2d.x, p2d.y).cast();
        UCMInitFocalAlphaFactor { target, p3d, p2d }
    }
}
impl<T: na::RealField> Factor<T> for UCMInitFocalAlphaFactor {
    fn residual_func(&self, params: &[nalgebra::DVector<T>]) -> nalgebra::DVector<T> {
        // params[[f, alpha], rvec, tvec]
        let mut cam_params = self.target.cast::<T>().params();
        cam_params[0] = params[0][0].clone();
        cam_params[1] = params[0][0].clone();
        cam_params[4] = params[0][1].clone();
        let model = self.target.cast().new_from_params(&cam_params);
        let rvec = params[1].to_vec3();
        let tvec = params[2].to_vec3();
        let transform = na::Isometry3::new(tvec, rvec);
        let p3d_t = transform * self.p3d.cast();
        let p3d_t = na::Vector3::new(p3d_t.x.clone(), p3d_t.y.clone(), p3d_t.z.clone());
        let p2d_p = model.project_one(&p3d_t);
        let p2d_tp = self.p2d.cast::<T>();
        na::dvector![
            p2d_p[0].clone() - p2d_tp[0].clone(),
            p2d_p[1].clone() - p2d_tp[1].clone()
        ]
    }
}

pub struct ReprojectionFactor {
    pub target: GenericModel<f64>,
    pub p3d: na::Point3<f64>,
    pub p2d: na::Vector2<f64>,
    pub xy_same_focal: bool,
}

impl ReprojectionFactor {
    pub fn new(
        target: &GenericModel<f64>,
        p3d: &glam::Vec3,
        p2d: &glam::Vec2,
        xy_same_focal: bool,
    ) -> ReprojectionFactor {
        let target = target.cast();
        let p3d = na::Point3::new(p3d.x, p3d.y, p3d.z).cast();
        let p2d = na::Vector2::new(p2d.x, p2d.y).cast();
        ReprojectionFactor {
            target,
            p3d,
            p2d,
            xy_same_focal,
        }
    }
}
impl<T: na::RealField> Factor<T> for ReprojectionFactor {
    fn residual_func(&self, params: &[nalgebra::DVector<T>]) -> nalgebra::DVector<T> {
        // params[params, rvec, tvec]
        let mut params0 = params[0].clone();
        if self.xy_same_focal {
            params0 = params0.clone().insert_row(1, params0[0].clone());
        }
        let model = self.target.cast().new_from_params(&params0);
        let rvec = params[1].to_vec3();
        let tvec = params[2].to_vec3();
        let transform = na::Isometry3::new(tvec, rvec);
        let p3d_t = transform * self.p3d.cast();
        let p3d_t = na::Vector3::new(p3d_t.x.clone(), p3d_t.y.clone(), p3d_t.z.clone());
        let p2d_p = model.project_one(&p3d_t);

        let p2d_tp = self.p2d.cast::<T>();
        na::dvector![
            p2d_p[0].clone() - p2d_tp[0].clone(),
            p2d_p[1].clone() - p2d_tp[1].clone()
        ]
    }
}

pub struct OtherCamReprojectionFactor {
    pub target: GenericModel<f64>,
    pub p3d: na::Point3<f64>,
    pub p2d: na::Vector2<f64>,
    pub xy_same_focal: bool,
}

impl OtherCamReprojectionFactor {
    pub fn new(
        target: &GenericModel<f64>,
        p3d: &glam::Vec3,
        p2d: &glam::Vec2,
        xy_same_focal: bool,
    ) -> OtherCamReprojectionFactor {
        let target = target.cast();
        let p3d = na::Point3::new(p3d.x, p3d.y, p3d.z).cast();
        let p2d = na::Vector2::new(p2d.x, p2d.y).cast();
        OtherCamReprojectionFactor {
            target,
            p3d,
            p2d,
            xy_same_focal,
        }
    }
}
impl<T: na::RealField> Factor<T> for OtherCamReprojectionFactor {
    fn residual_func(&self, params: &[nalgebra::DVector<T>]) -> nalgebra::DVector<T> {
        // params[params, rvec, tvec]
        let mut params0 = params[0].clone();
        if self.xy_same_focal {
            params0 = params0.clone().insert_row(1, params0[0].clone());
        }
        let model = self.target.cast().new_from_params(&params0);
        let rvec0 = params[1].to_vec3();
        let tvec0 = params[2].to_vec3();
        let t_0_b = na::Isometry3::new(tvec0, rvec0);
        let rvec1 = params[3].to_vec3();
        let tvec1 = params[4].to_vec3();
        let t_i_0 = na::Isometry3::new(tvec1, rvec1);
        let p3d_t = t_i_0 * t_0_b * self.p3d.cast();
        let p3d_t = na::Vector3::new(p3d_t.x.clone(), p3d_t.y.clone(), p3d_t.z.clone());
        let p2d_p = model.project_one(&p3d_t);

        let p2d_tp = self.p2d.cast::<T>();
        na::dvector![
            p2d_p[0].clone() - p2d_tp[0].clone(),
            p2d_p[1].clone() - p2d_tp[1].clone()
        ]
    }
}

pub struct SE3Factor {
    pub t_0_b: na::Isometry3<f64>,
    pub t_i_b: na::Isometry3<f64>,
}

impl SE3Factor {
    pub fn new(t_0_b: &na::Isometry3<f64>, t_i_b: &na::Isometry3<f64>) -> SE3Factor {
        SE3Factor {
            t_0_b: t_0_b.cast(),
            t_i_b: t_i_b.cast(),
        }
    }
}

impl<T: na::RealField> Factor<T> for SE3Factor {
    fn residual_func(&self, params: &[nalgebra::DVector<T>]) -> nalgebra::DVector<T> {
        let rvec = na::Vector3::new(
            params[0][0].clone(),
            params[0][1].clone(),
            params[0][2].clone(),
        );
        let tvec = na::Vector3::new(
            params[1][0].clone(),
            params[1][1].clone(),
            params[1][2].clone(),
        );
        let t_i_0 = na::Isometry3::new(tvec, rvec);
        let t_diff = self.t_i_b.cast().inverse() * t_i_0 * self.t_0_b.cast();
        let r_diff = t_diff.rotation.scaled_axis();
        na::dvector![
            r_diff[0].clone(),
            r_diff[1].clone(),
            r_diff[2].clone(),
            t_diff.translation.x.clone(),
            t_diff.translation.y.clone(),
            t_diff.translation.z.clone(),
        ]
    }
}