slamkit_rs/mapping/
triangulation.rs

1use nalgebra as na;
2use opencv::{
3    calib3d,
4    core::{CV_64F, Mat, Point2f, Vector},
5    prelude::*,
6};
7use serde::{Deserialize, Serialize};
8
9use crate::odometry::CameraIntrinsics;
10
11/// A 3D map point
12#[derive(Debug, Clone, Serialize, Deserialize)]
13pub struct MapPoint {
14    /// 3D position in world coordinates
15    pub position: na::Point3<f64>,
16    /// Descriptor (for matching)
17    pub descriptor: Option<Vec<u8>>,
18    /// Number of times this point has been observed
19    pub observations: usize,
20    /// ID of the point
21    pub id: usize,
22}
23
24impl MapPoint {
25    /// Create a new map point
26    pub fn new(position: na::Point3<f64>, id: usize) -> Self {
27        Self {
28            position,
29            descriptor: None,
30            observations: 1,
31            id,
32        }
33    }
34
35    /// Create a new map point with descriptor
36    pub fn with_descriptor(position: na::Point3<f64>, descriptor: Vec<u8>, id: usize) -> Self {
37        Self {
38            position,
39            descriptor: Some(descriptor),
40            observations: 1,
41            id,
42        }
43    }
44
45    /// Add observation count
46    pub fn add_observation(&mut self) {
47        self.observations += 1;
48    }
49}
50
51/// Triangulator for computing 3D points from 2D correspondences
52pub struct Triangulator {
53    intrinsics: CameraIntrinsics,
54    /// Minimum parallax angle in degrees (to ensure good triangulation)
55    min_parallax_deg: f64,
56    /// Maximum reprojection error to accept a point
57    max_reproj_error: f64,
58}
59
60impl Triangulator {
61    /// Create a new triangulator with the given camera intrinsics
62    pub fn new(intrinsics: CameraIntrinsics) -> Self {
63        Self {
64            intrinsics,
65            min_parallax_deg: 1.0,
66            max_reproj_error: 4.0, // TODO: Implement a better default value
67        }
68    }
69
70    /// Set minimum parallax angle in degrees
71    pub fn with_min_parallax(mut self, deg: f64) -> Self {
72        self.min_parallax_deg = deg;
73        self
74    }
75
76    /// Set maximum reprojection error
77    pub fn with_max_reproj_error(mut self, error: f64) -> Self {
78        self.max_reproj_error = error;
79        self
80    }
81
82    /// Triangulate 3D points from two camera poses and matched 2D points
83    ///
84    /// Arguments
85    /// - `pose1` - (R, t) of the first camera (world to camera transform)
86    /// - `pose2` - (R, t) of the second camera (world to camera transform)
87    /// - `points1` - 2D points in the first image
88    /// - `points2` - 2D points in the second image
89    ///
90    /// Returns
91    /// Vector of successfully triangulated MapPoints
92    pub fn triangulate(
93        &self,
94        pose1: &(na::Matrix3<f64>, na::Vector3<f64>),
95        pose2: &(na::Matrix3<f64>, na::Vector3<f64>),
96        points1: &Vector<Point2f>,
97        points2: &Vector<Point2f>,
98        descriptors: Option<&Mat>,
99    ) -> Result<Vec<MapPoint>, Box<dyn std::error::Error>> {
100        if points1.len() != points2.len() {
101            return Err("Point arrays must have the same length".into());
102        }
103
104        if points1.is_empty() {
105            return Ok(Vec::new());
106        }
107
108        // Build projection matrices P1 = K * [R1 | t1] and P2 = K * [R2 | t2]
109        let proj1 = self.build_projection_matrix(&pose1.0, &pose1.1)?;
110        let proj2 = self.build_projection_matrix(&pose2.0, &pose2.1)?;
111
112        // Triangulate points using OpenCV
113        let mut points_4d = Mat::default();
114        calib3d::triangulate_points(&proj1, &proj2, points1, points2, &mut points_4d)?;
115
116        // Convert homogeneous 4D points to 3D and filter
117        // Note: triangulatePoints outputs CV_32F, so we read as f32 and convert to f64
118        let mut map_points = Vec::new();
119        for i in 0..points_4d.cols() {
120            let x = *points_4d.at_2d::<f32>(0, i)? as f64;
121            let y = *points_4d.at_2d::<f32>(1, i)? as f64;
122            let z = *points_4d.at_2d::<f32>(2, i)? as f64;
123            let w = *points_4d.at_2d::<f32>(3, i)? as f64;
124
125            // Convert from homogeneous coordinates
126            if w.abs() < 1e-10 {
127                continue; // Skip points at infinity
128            }
129
130            let point_3d = na::Point3::new(x / w, y / w, z / w);
131
132            // Check if point is in front of both cameras
133            if !self.is_in_front_of_camera(&point_3d, &pose1.0, &pose1.1) {
134                continue;
135            }
136            if !self.is_in_front_of_camera(&point_3d, &pose2.0, &pose2.1) {
137                continue;
138            }
139
140            // TODO: Check parallax angle
141            // (For now, skipping this check for simplicity)
142            // Create map point with optional descriptor
143            let mut map_point = MapPoint::new(point_3d, i as usize);
144            if let Some(desc_mat) = descriptors {
145                if i < desc_mat.rows() {
146                    let mut desc_vec = Vec::new();
147                    for j in 0..desc_mat.cols() {
148                        desc_vec.push(*desc_mat.at_2d::<u8>(i, j)?);
149                    }
150                    map_point.descriptor = Some(desc_vec);
151                }
152            }
153
154            map_points.push(map_point);
155        }
156
157        Ok(map_points)
158    }
159
160    /// Build projection matrix P = K * [R | t]
161    fn build_projection_matrix(
162        &self,
163        r: &na::Matrix3<f64>,
164        t: &na::Vector3<f64>,
165    ) -> Result<Mat, Box<dyn std::error::Error>> {
166        let k = self.intrinsics.to_matrix()?;
167
168        // Create [R | t] as a 3x4 matrix
169        let mut rt = Mat::new_rows_cols_with_default(3, 4, CV_64F, opencv::core::Scalar::all(0.0))?;
170
171        for i in 0..3 {
172            for j in 0..3 {
173                *rt.at_2d_mut::<f64>(i as i32, j as i32)? = r[(i, j)];
174            }
175            *rt.at_2d_mut::<f64>(i as i32, 3)? = t[i];
176        }
177
178        // Compute P = K * [R | t]
179        let mut proj = Mat::default();
180        opencv::core::gemm(&k, &rt, 1.0, &Mat::default(), 0.0, &mut proj, 0)?;
181
182        Ok(proj)
183    }
184
185    /// Check if a 3D point is in front of the camera
186    fn is_in_front_of_camera(
187        &self,
188        point: &na::Point3<f64>,
189        r: &na::Matrix3<f64>,
190        t: &na::Vector3<f64>,
191    ) -> bool {
192        // Transform point to camera coordinates
193        let point_cam = r * point + t;
194        // Check if Z is positive (in front of camera)
195        point_cam.z > 0.0
196    }
197}
198
199#[cfg(test)]
200mod tests {
201    use super::*;
202
203    #[test]
204    fn test_map_point_creation() {
205        let pos = na::Point3::new(1.0, 2.0, 3.0);
206        let point = MapPoint::new(pos, 0);
207        assert_eq!(point.position, pos);
208        assert_eq!(point.observations, 1);
209        assert_eq!(point.id, 0);
210        assert!(point.descriptor.is_none());
211    }
212
213    #[test]
214    fn test_map_point_with_descriptor() {
215        let pos = na::Point3::new(1.0, 2.0, 3.0);
216        let desc = vec![1, 2, 3, 4];
217        let point = MapPoint::with_descriptor(pos, desc.clone(), 5);
218        assert_eq!(point.position, pos);
219        assert_eq!(point.descriptor, Some(desc));
220        assert_eq!(point.id, 5);
221    }
222
223    #[test]
224    fn test_add_observation() {
225        let mut point = MapPoint::new(na::Point3::new(0.0, 0.0, 1.0), 0);
226        assert_eq!(point.observations, 1);
227        point.add_observation();
228        assert_eq!(point.observations, 2);
229    }
230
231    #[test]
232    fn test_triangulator_creation() {
233        let cam = CameraIntrinsics::kitti();
234        let triangulator = Triangulator::new(cam);
235        assert_eq!(triangulator.min_parallax_deg, 1.0);
236        assert_eq!(triangulator.max_reproj_error, 4.0);
237    }
238
239    #[test]
240    fn test_triangulator_builder() {
241        let cam = CameraIntrinsics::kitti();
242        let triangulator = Triangulator::new(cam)
243            .with_min_parallax(2.0)
244            .with_max_reproj_error(5.0);
245        assert_eq!(triangulator.min_parallax_deg, 2.0);
246        assert_eq!(triangulator.max_reproj_error, 5.0);
247    }
248
249    #[test]
250    fn test_triangulate_empty_points() {
251        let cam = CameraIntrinsics::kitti();
252        let triangulator = Triangulator::new(cam);
253
254        let pose1 = (na::Matrix3::identity(), na::Vector3::zeros());
255        let pose2 = (na::Matrix3::identity(), na::Vector3::new(1.0, 0.0, 0.0));
256
257        let points1 = Vector::new();
258        let points2 = Vector::new();
259
260        let result = triangulator.triangulate(&pose1, &pose2, &points1, &points2, None);
261        assert!(result.is_ok());
262        assert_eq!(result.unwrap().len(), 0);
263    }
264
265    #[test]
266    fn test_triangulate_mismatched_points() {
267        let cam = CameraIntrinsics::kitti();
268        let triangulator = Triangulator::new(cam);
269
270        let pose1 = (na::Matrix3::identity(), na::Vector3::zeros());
271        let pose2 = (na::Matrix3::identity(), na::Vector3::new(1.0, 0.0, 0.0));
272
273        let mut points1 = Vector::new();
274        points1.push(Point2f::new(100.0, 100.0));
275
276        let points2 = Vector::new();
277
278        let result = triangulator.triangulate(&pose1, &pose2, &points1, &points2, None);
279        assert!(result.is_err());
280    }
281
282    #[test]
283    fn test_is_in_front_of_camera() {
284        let cam = CameraIntrinsics::kitti();
285        let triangulator = Triangulator::new(cam);
286
287        let r = na::Matrix3::identity();
288        let t = na::Vector3::zeros();
289
290        let point_front = na::Point3::new(0.0, 0.0, 5.0);
291        let point_behind = na::Point3::new(0.0, 0.0, -5.0);
292
293        assert!(triangulator.is_in_front_of_camera(&point_front, &r, &t));
294        assert!(!triangulator.is_in_front_of_camera(&point_behind, &r, &t));
295    }
296
297    #[test]
298    fn test_triangulate_synthetic_points() {
299        // Create a synthetic scenario: two cameras and a few 3D points
300        let cam = CameraIntrinsics::new(500.0, 500.0, 320.0, 240.0);
301        let triangulator = Triangulator::new(cam);
302
303        // Camera 1 at origin looking along +Z
304        let pose1 = (na::Matrix3::identity(), na::Vector3::zeros());
305
306        // Camera 2 moved 1 meter to the right along X-axis
307        let pose2 = (na::Matrix3::identity(), na::Vector3::new(1.0, 0.0, 0.0));
308
309        // Create synthetic 3D points in front of both cameras
310        let point_3d_1 = na::Point3::new(0.0, 0.0, 10.0); // Center, 10m away
311        let point_3d_2 = na::Point3::new(2.0, 1.0, 10.0); // Offset point
312
313        // Project 3D points to 2D for both cameras
314        let project_point =
315            |point: &na::Point3<f64>, r: &na::Matrix3<f64>, t: &na::Vector3<f64>| {
316                let p_cam = r * point + t;
317                let x = cam.fx * (p_cam.x / p_cam.z) + cam.cx;
318                let y = cam.fy * (p_cam.y / p_cam.z) + cam.cy;
319                Point2f::new(x as f32, y as f32)
320            };
321
322        let mut points1 = Vector::new();
323        let mut points2 = Vector::new();
324
325        points1.push(project_point(&point_3d_1, &pose1.0, &pose1.1));
326        points1.push(project_point(&point_3d_2, &pose1.0, &pose1.1));
327
328        points2.push(project_point(&point_3d_1, &pose2.0, &pose2.1));
329        points2.push(project_point(&point_3d_2, &pose2.0, &pose2.1));
330
331        // Triangulate
332        let result = triangulator.triangulate(&pose1, &pose2, &points1, &points2, None);
333        if let Err(e) = &result {
334            eprintln!("Triangulation error: {}", e);
335        }
336        assert!(result.is_ok());
337
338        let map_points = result.unwrap();
339        assert!(
340            map_points.len() > 0,
341            "Should triangulate at least some points"
342        );
343
344        // Check that triangulated points are reasonable
345        for point in &map_points {
346            // Points should be in front of camera
347            assert!(point.position.z > 0.0, "Point should be in front of camera");
348            // Points should be roughly at the expected depth
349            assert!(
350                point.position.z > 5.0 && point.position.z < 15.0,
351                "Point depth should be reasonable"
352            );
353        }
354    }
355}