Skip to main content

apex_io/
bal.rs

1//! Bundle Adjustment in the Large (BAL) dataset loader.
2//!
3//! This module provides functionality to load BAL format files, which are used
4//! for bundle adjustment benchmarks in computer vision.
5//!
6//! ## Format
7//!
8//! BAL files contain bundle adjustment problems with the following sequential structure:
9//! 1. **Header line**: `<num_cameras> <num_points> <num_observations>`
10//! 2. **Observations block**: One observation per line with format `<camera_idx> <point_idx> <x> <y>`
11//! 3. **Cameras block**: 9 sequential parameter lines per camera (one value per line)
12//! 4. **Points block**: 3 sequential coordinate lines per point (one value per line)
13//!
14//! ## Camera Model
15//!
16//! Uses Snavely's 9-parameter camera model from the Bundler structure-from-motion system:
17//! - **Rotation**: 3D axis-angle representation (rx, ry, rz) - 3 parameters
18//! - **Translation**: 3D vector (tx, ty, tz) - 3 parameters
19//! - **Focal length**: Single parameter (f) - 1 parameter
20//! - **Radial distortion**: Two coefficients (k1, k2) - 2 parameters
21//!
22//! For more details, see: <https://grail.cs.washington.edu/projects/bal/>
23//!
24//! ## Example
25//!
26//! ```no_run
27//! use apex_io::BalLoader;
28//!
29//! let dataset = BalLoader::load("data/bundle_adjustment/problem-21-11315-pre.txt")?;
30//! println!("Loaded {} cameras, {} points, {} observations",
31//!          dataset.cameras.len(),
32//!          dataset.points.len(),
33//!          dataset.observations.len());
34//! # Ok::<(), apex_io::IoError>(())
35//! ```
36
37use super::IoError;
38use nalgebra::Vector3;
39use std::fs::File;
40use std::path::Path;
41
42/// Represents a camera using Snavely's 9-parameter camera model.
43///
44/// The camera model from Bundler uses:
45/// - Axis-angle rotation representation (compact 3-parameter rotation)
46/// - 3D translation vector
47/// - Single focal length parameter
48/// - Two radial distortion coefficients
49#[derive(Debug, Clone)]
50pub struct BalCamera {
51    /// Rotation as axis-angle representation (rx, ry, rz)
52    pub rotation: Vector3<f64>,
53    /// Translation vector (tx, ty, tz)
54    pub translation: Vector3<f64>,
55    /// Focal length
56    pub focal_length: f64,
57    /// First radial distortion coefficient
58    pub k1: f64,
59    /// Second radial distortion coefficient
60    pub k2: f64,
61}
62
63/// Represents a 3D point (landmark) in the bundle adjustment problem.
64#[derive(Debug, Clone)]
65pub struct BalPoint {
66    /// 3D position (x, y, z)
67    pub position: Vector3<f64>,
68}
69
70/// Represents an observation of a 3D point by a camera.
71///
72/// Each observation links a camera to a 3D point via a 2D pixel measurement.
73#[derive(Debug, Clone)]
74pub struct BalObservation {
75    /// Index of the observing camera
76    pub camera_index: usize,
77    /// Index of the observed 3D point
78    pub point_index: usize,
79    /// Pixel x-coordinate
80    pub x: f64,
81    /// Pixel y-coordinate
82    pub y: f64,
83}
84
85/// Complete bundle adjustment dataset loaded from a BAL file.
86#[derive(Debug, Clone)]
87pub struct BalDataset {
88    /// All cameras in the dataset
89    pub cameras: Vec<BalCamera>,
90    /// All 3D points (landmarks) in the dataset
91    pub points: Vec<BalPoint>,
92    /// All observations (camera-point correspondences)
93    pub observations: Vec<BalObservation>,
94}
95
96/// Loader for BAL (Bundle Adjustment in the Large) dataset files.
97pub struct BalLoader;
98
99/// Default focal length used for cameras with negative or non-finite values.
100/// This value is used during BAL dataset loading to normalize invalid focal lengths.
101pub const DEFAULT_FOCAL_LENGTH: f64 = 500.0;
102
103impl BalCamera {
104    /// Normalizes the focal length to ensure it's valid for optimization.
105    ///
106    /// Replaces negative or non-finite focal lengths with DEFAULT_FOCAL_LENGTH,
107    /// while preserving all positive values regardless of magnitude.
108    fn normalize_focal_length(focal_length: f64) -> f64 {
109        if focal_length > 0.0 && focal_length.is_finite() {
110            focal_length
111        } else {
112            DEFAULT_FOCAL_LENGTH
113        }
114    }
115}
116
117impl BalLoader {
118    /// Loads a BAL dataset from a file.
119    ///
120    /// # Arguments
121    ///
122    /// * `path` - Path to the BAL format file
123    ///
124    /// # Returns
125    ///
126    /// Returns a `BalDataset` containing all cameras, points, and observations,
127    /// or an `IoError` if parsing fails.
128    ///
129    /// # Example
130    ///
131    /// ```no_run
132    /// use apex_io::BalLoader;
133    ///
134    /// let dataset = BalLoader::load("data/bundle_adjustment/problem-21-11315-pre.txt")?;
135    /// assert_eq!(dataset.cameras.len(), 21);
136    /// assert_eq!(dataset.points.len(), 11315);
137    /// # Ok::<(), apex_io::IoError>(())
138    /// ```
139    pub fn load(path: impl AsRef<Path>) -> Result<BalDataset, IoError> {
140        // Open file with error context
141        let file = File::open(path.as_ref()).map_err(|e| {
142            IoError::Io(e).log_with_source(format!("Failed to open BAL file: {:?}", path.as_ref()))
143        })?;
144
145        // Memory-map file for performance (following g2o.rs pattern)
146        // SAFETY: The file is opened read-only and the handle remains valid for the
147        // lifetime of `mmap`. No other thread modifies the file during this scope.
148        let mmap = unsafe {
149            memmap2::Mmap::map(&file).map_err(|e| {
150                IoError::Io(e).log_with_source("Failed to memory-map BAL file".to_string())
151            })?
152        };
153
154        // Convert to UTF-8 string
155        let content = std::str::from_utf8(&mmap).map_err(|_| IoError::Parse {
156            line: 0,
157            message: "File is not valid UTF-8".to_string(),
158        })?;
159
160        // Create line iterator (skip empty lines, trim whitespace)
161        let mut lines = content
162            .lines()
163            .enumerate()
164            .map(|(idx, line)| (idx + 1, line.trim()))
165            .filter(|(_, line)| !line.is_empty());
166
167        // Parse header
168        let (num_cameras, num_points, num_observations) = Self::parse_header(&mut lines)?;
169
170        // Parse observations
171        let observations = Self::parse_observations(&mut lines, num_observations)?;
172
173        // Parse cameras
174        let cameras = Self::parse_cameras(&mut lines, num_cameras)?;
175
176        // Parse points
177        let points = Self::parse_points(&mut lines, num_points)?;
178
179        // Validate counts match header
180        if cameras.len() != num_cameras {
181            return Err(IoError::Parse {
182                line: 0,
183                message: format!(
184                    "Camera count mismatch: header says {}, got {}",
185                    num_cameras,
186                    cameras.len()
187                ),
188            });
189        }
190
191        if points.len() != num_points {
192            return Err(IoError::Parse {
193                line: 0,
194                message: format!(
195                    "Point count mismatch: header says {}, got {}",
196                    num_points,
197                    points.len()
198                ),
199            });
200        }
201
202        if observations.len() != num_observations {
203            return Err(IoError::Parse {
204                line: 0,
205                message: format!(
206                    "Observation count mismatch: header says {}, got {}",
207                    num_observations,
208                    observations.len()
209                ),
210            });
211        }
212
213        Ok(BalDataset {
214            cameras,
215            points,
216            observations,
217        })
218    }
219
220    /// Parses the header line containing dataset dimensions.
221    fn parse_header<'a>(
222        lines: &mut impl Iterator<Item = (usize, &'a str)>,
223    ) -> Result<(usize, usize, usize), IoError> {
224        let (line_num, header_line) = lines.next().ok_or(IoError::Parse {
225            line: 1,
226            message: "Missing header line".to_string(),
227        })?;
228
229        let parts: Vec<&str> = header_line.split_whitespace().collect();
230        if parts.len() != 3 {
231            return Err(IoError::MissingFields { line: line_num });
232        }
233
234        let num_cameras = parts[0]
235            .parse::<usize>()
236            .map_err(|_| IoError::InvalidNumber {
237                line: line_num,
238                value: parts[0].to_string(),
239            })?;
240
241        let num_points = parts[1]
242            .parse::<usize>()
243            .map_err(|_| IoError::InvalidNumber {
244                line: line_num,
245                value: parts[1].to_string(),
246            })?;
247
248        let num_observations = parts[2]
249            .parse::<usize>()
250            .map_err(|_| IoError::InvalidNumber {
251                line: line_num,
252                value: parts[2].to_string(),
253            })?;
254
255        Ok((num_cameras, num_points, num_observations))
256    }
257
258    /// Parses the observations block.
259    fn parse_observations<'a>(
260        lines: &mut impl Iterator<Item = (usize, &'a str)>,
261        num_observations: usize,
262    ) -> Result<Vec<BalObservation>, IoError> {
263        let mut observations = Vec::with_capacity(num_observations);
264
265        for _ in 0..num_observations {
266            let (line_num, line) = lines.next().ok_or(IoError::Parse {
267                line: 0,
268                message: "Unexpected end of file in observations section".to_string(),
269            })?;
270
271            let parts: Vec<&str> = line.split_whitespace().collect();
272            if parts.len() != 4 {
273                return Err(IoError::MissingFields { line: line_num });
274            }
275
276            let camera_index = parts[0]
277                .parse::<usize>()
278                .map_err(|_| IoError::InvalidNumber {
279                    line: line_num,
280                    value: parts[0].to_string(),
281                })?;
282
283            let point_index = parts[1]
284                .parse::<usize>()
285                .map_err(|_| IoError::InvalidNumber {
286                    line: line_num,
287                    value: parts[1].to_string(),
288                })?;
289
290            let x = parts[2]
291                .parse::<f64>()
292                .map_err(|_| IoError::InvalidNumber {
293                    line: line_num,
294                    value: parts[2].to_string(),
295                })?;
296
297            let y = parts[3]
298                .parse::<f64>()
299                .map_err(|_| IoError::InvalidNumber {
300                    line: line_num,
301                    value: parts[3].to_string(),
302                })?;
303
304            observations.push(BalObservation {
305                camera_index,
306                point_index,
307                x,
308                y,
309            });
310        }
311
312        Ok(observations)
313    }
314
315    /// Parses the cameras block.
316    ///
317    /// Each camera has 9 parameters on sequential lines:
318    /// - 3 lines for rotation (rx, ry, rz)
319    /// - 3 lines for translation (tx, ty, tz)
320    /// - 1 line for focal length (f)
321    /// - 2 lines for radial distortion (k1, k2)
322    fn parse_cameras<'a>(
323        lines: &mut impl Iterator<Item = (usize, &'a str)>,
324        num_cameras: usize,
325    ) -> Result<Vec<BalCamera>, IoError> {
326        let mut cameras = Vec::with_capacity(num_cameras);
327
328        for camera_idx in 0..num_cameras {
329            let mut params = Vec::with_capacity(9);
330
331            // Read 9 consecutive lines for camera parameters
332            for param_idx in 0..9 {
333                let (line_num, line) = lines.next().ok_or(IoError::Parse {
334                    line: 0,
335                    message: format!(
336                        "Unexpected end of file in camera {} parameter {}",
337                        camera_idx, param_idx
338                    ),
339                })?;
340
341                let value = line
342                    .trim()
343                    .parse::<f64>()
344                    .map_err(|_| IoError::InvalidNumber {
345                        line: line_num,
346                        value: line.to_string(),
347                    })?;
348
349                params.push(value);
350            }
351
352            cameras.push(BalCamera {
353                rotation: Vector3::new(params[0], params[1], params[2]),
354                translation: Vector3::new(params[3], params[4], params[5]),
355                focal_length: BalCamera::normalize_focal_length(params[6]),
356                k1: params[7],
357                k2: params[8],
358            });
359        }
360
361        Ok(cameras)
362    }
363
364    /// Parses the points block.
365    ///
366    /// Each point has 3 coordinates on sequential lines (x, y, z).
367    fn parse_points<'a>(
368        lines: &mut impl Iterator<Item = (usize, &'a str)>,
369        num_points: usize,
370    ) -> Result<Vec<BalPoint>, IoError> {
371        let mut points = Vec::with_capacity(num_points);
372
373        for point_idx in 0..num_points {
374            let mut coords = Vec::with_capacity(3);
375
376            // Read 3 consecutive lines for point coordinates
377            for coord_idx in 0..3 {
378                let (line_num, line) = lines.next().ok_or(IoError::Parse {
379                    line: 0,
380                    message: format!(
381                        "Unexpected end of file in point {} coordinate {}",
382                        point_idx, coord_idx
383                    ),
384                })?;
385
386                let value = line
387                    .trim()
388                    .parse::<f64>()
389                    .map_err(|_| IoError::InvalidNumber {
390                        line: line_num,
391                        value: line.to_string(),
392                    })?;
393
394                coords.push(value);
395            }
396
397            points.push(BalPoint {
398                position: Vector3::new(coords[0], coords[1], coords[2]),
399            });
400        }
401
402        Ok(points)
403    }
404}
405
406#[cfg(test)]
407mod tests {
408    use super::*;
409    use std::io::Write;
410    use tempfile::NamedTempFile;
411
412    type TestResult = Result<(), Box<dyn std::error::Error>>;
413
414    /// Writes a minimal BAL file: 1 camera, 1 point, 1 observation.
415    fn write_minimal_bal() -> Result<NamedTempFile, Box<dyn std::error::Error>> {
416        let mut f = NamedTempFile::new()?;
417        writeln!(f, "1 1 1")?; // header
418        writeln!(f, "0 0 -123.456 456.789")?; // observation
419        // Camera params (9 values, one per line): rx ry rz tx ty tz f k1 k2
420        for v in [0.1f64, 0.2, 0.3, 0.4, 0.5, 0.6, 500.0, -0.1, 0.05] {
421            writeln!(f, "{v}")?;
422        }
423        // Point coords (3 values, one per line): x y z
424        for v in [1.0f64, 2.0, 3.0] {
425            writeln!(f, "{v}")?;
426        }
427        f.flush()?;
428        Ok(f)
429    }
430
431    /// Writes a BAL file with a custom focal length value (all other params are zeros).
432    fn write_bal_with_focal(focal: f64) -> Result<NamedTempFile, Box<dyn std::error::Error>> {
433        let mut f = NamedTempFile::new()?;
434        writeln!(f, "1 1 1")?;
435        writeln!(f, "0 0 0.0 0.0")?; // observation
436        // Camera params: rx ry rz tx ty tz f k1 k2
437        for v in [0.0f64, 0.0, 0.0, 0.0, 0.0, 0.0, focal, 0.0, 0.0] {
438            writeln!(f, "{v}")?;
439        }
440        // Point coords
441        for v in [0.0f64, 0.0, 0.0] {
442            writeln!(f, "{v}")?;
443        }
444        f.flush()?;
445        Ok(f)
446    }
447
448    #[test]
449    fn test_load_minimal_dataset() -> TestResult {
450        let f = write_minimal_bal()?;
451        let ds = BalLoader::load(f.path())?;
452        assert_eq!(ds.cameras.len(), 1);
453        assert_eq!(ds.points.len(), 1);
454        assert_eq!(ds.observations.len(), 1);
455        Ok(())
456    }
457
458    #[test]
459    fn test_load_camera_values() -> TestResult {
460        let f = write_minimal_bal()?;
461        let ds = BalLoader::load(f.path())?;
462        let cam = &ds.cameras[0];
463        assert!((cam.rotation.x - 0.1).abs() < 1e-12);
464        assert!((cam.rotation.y - 0.2).abs() < 1e-12);
465        assert!((cam.rotation.z - 0.3).abs() < 1e-12);
466        assert!((cam.translation.x - 0.4).abs() < 1e-12);
467        assert!((cam.translation.y - 0.5).abs() < 1e-12);
468        assert!((cam.translation.z - 0.6).abs() < 1e-12);
469        assert!((cam.focal_length - 500.0).abs() < 1e-12);
470        assert!((cam.k1 - (-0.1)).abs() < 1e-12);
471        assert!((cam.k2 - 0.05).abs() < 1e-12);
472        Ok(())
473    }
474
475    #[test]
476    fn test_load_observation_values() -> TestResult {
477        let f = write_minimal_bal()?;
478        let ds = BalLoader::load(f.path())?;
479        let obs = &ds.observations[0];
480        assert_eq!(obs.camera_index, 0);
481        assert_eq!(obs.point_index, 0);
482        assert!((obs.x - (-123.456)).abs() < 1e-10);
483        assert!((obs.y - 456.789).abs() < 1e-10);
484        Ok(())
485    }
486
487    #[test]
488    fn test_load_point_values() -> TestResult {
489        let f = write_minimal_bal()?;
490        let ds = BalLoader::load(f.path())?;
491        let pt = &ds.points[0];
492        assert!((pt.position.x - 1.0).abs() < 1e-12);
493        assert!((pt.position.y - 2.0).abs() < 1e-12);
494        assert!((pt.position.z - 3.0).abs() < 1e-12);
495        Ok(())
496    }
497
498    #[test]
499    fn test_normalize_focal_length_negative_uses_default() -> TestResult {
500        let f = write_bal_with_focal(-100.0)?;
501        let ds = BalLoader::load(f.path())?;
502        assert!(
503            (ds.cameras[0].focal_length - DEFAULT_FOCAL_LENGTH).abs() < 1e-12,
504            "negative focal length should be replaced with DEFAULT_FOCAL_LENGTH"
505        );
506        Ok(())
507    }
508
509    #[test]
510    fn test_normalize_focal_length_zero_uses_default() -> TestResult {
511        let f = write_bal_with_focal(0.0)?;
512        let ds = BalLoader::load(f.path())?;
513        assert!(
514            (ds.cameras[0].focal_length - DEFAULT_FOCAL_LENGTH).abs() < 1e-12,
515            "zero focal length should be replaced with DEFAULT_FOCAL_LENGTH"
516        );
517        Ok(())
518    }
519
520    #[test]
521    fn test_normalize_focal_length_positive_preserved() -> TestResult {
522        let f = write_bal_with_focal(300.0)?;
523        let ds = BalLoader::load(f.path())?;
524        assert!(
525            (ds.cameras[0].focal_length - 300.0).abs() < 1e-12,
526            "positive focal length should be preserved"
527        );
528        Ok(())
529    }
530
531    #[test]
532    fn test_load_nonexistent_file() {
533        let result = BalLoader::load("/nonexistent/path/file.bal");
534        assert!(result.is_err(), "loading a missing file should return Err");
535    }
536
537    #[test]
538    fn test_load_empty_file() -> TestResult {
539        let f = NamedTempFile::new()?;
540        let result = BalLoader::load(f.path());
541        assert!(result.is_err(), "empty file should fail (missing header)");
542        Ok(())
543    }
544
545    #[test]
546    fn test_load_header_wrong_field_count() -> TestResult {
547        let mut f = NamedTempFile::new()?;
548        writeln!(f, "1 1")?; // only 2 fields, need 3
549        f.flush()?;
550        let result = BalLoader::load(f.path());
551        assert!(result.is_err(), "header with 2 fields should fail");
552        Ok(())
553    }
554
555    #[test]
556    fn test_load_header_invalid_number() -> TestResult {
557        let mut f = NamedTempFile::new()?;
558        writeln!(f, "1 abc 1")?;
559        f.flush()?;
560        let result = BalLoader::load(f.path());
561        assert!(result.is_err(), "non-numeric header field should fail");
562        Ok(())
563    }
564
565    #[test]
566    fn test_load_truncated_observations() -> TestResult {
567        let mut f = NamedTempFile::new()?;
568        writeln!(f, "1 1 2")?; // claims 2 observations
569        writeln!(f, "0 0 1.0 1.0")?; // only 1 provided
570        f.flush()?;
571        let result = BalLoader::load(f.path());
572        assert!(result.is_err(), "truncated observation block should fail");
573        Ok(())
574    }
575
576    #[test]
577    fn test_load_truncated_cameras() -> TestResult {
578        let mut f = NamedTempFile::new()?;
579        writeln!(f, "1 1 1")?;
580        writeln!(f, "0 0 1.0 1.0")?; // observation
581        // Only 5 of the 9 required camera params
582        for v in [0.0f64, 0.0, 0.0, 0.0, 0.0] {
583            writeln!(f, "{v}")?;
584        }
585        f.flush()?;
586        let result = BalLoader::load(f.path());
587        assert!(result.is_err(), "truncated camera block should fail");
588        Ok(())
589    }
590
591    #[test]
592    fn test_load_multiple_cameras_and_points() -> TestResult {
593        let mut f = NamedTempFile::new()?;
594        writeln!(f, "2 2 3")?; // 2 cameras, 2 points, 3 observations
595        writeln!(f, "0 0 1.0 1.0")?;
596        writeln!(f, "0 1 2.0 2.0")?;
597        writeln!(f, "1 0 3.0 3.0")?;
598        // Camera 0
599        for v in [0.0f64; 9] {
600            writeln!(f, "{v}")?;
601        }
602        // Camera 1
603        for _ in 0..8 {
604            writeln!(f, "0.0")?;
605        }
606        writeln!(f, "200.0")?; // focal_length = 200
607        // Point 0
608        for v in [1.0f64, 2.0, 3.0] {
609            writeln!(f, "{v}")?;
610        }
611        // Point 1
612        for v in [4.0f64, 5.0, 6.0] {
613            writeln!(f, "{v}")?;
614        }
615        f.flush()?;
616        let ds = BalLoader::load(f.path())?;
617        assert_eq!(ds.cameras.len(), 2);
618        assert_eq!(ds.points.len(), 2);
619        assert_eq!(ds.observations.len(), 3);
620        Ok(())
621    }
622
623    #[test]
624    fn test_load_observation_invalid_number() -> TestResult {
625        let mut f = NamedTempFile::new()?;
626        writeln!(f, "1 1 1")?;
627        writeln!(f, "0 0 bad_x 1.0")?; // bad x coordinate
628        f.flush()?;
629        let result = BalLoader::load(f.path());
630        assert!(
631            result.is_err(),
632            "invalid observation coordinate should fail"
633        );
634        Ok(())
635    }
636
637    // -------------------------------------------------------------------------
638    // parse_header additional error paths
639    // -------------------------------------------------------------------------
640
641    #[test]
642    fn test_load_header_invalid_num_cameras() -> TestResult {
643        let mut f = NamedTempFile::new()?;
644        writeln!(f, "bad 1 1")?;
645        f.flush()?;
646        let result = BalLoader::load(f.path());
647        assert!(
648            matches!(result, Err(IoError::InvalidNumber { .. })),
649            "invalid num_cameras should return InvalidNumber"
650        );
651        Ok(())
652    }
653
654    #[test]
655    fn test_load_header_invalid_num_observations() -> TestResult {
656        let mut f = NamedTempFile::new()?;
657        writeln!(f, "1 1 bad")?;
658        f.flush()?;
659        let result = BalLoader::load(f.path());
660        assert!(
661            matches!(result, Err(IoError::InvalidNumber { .. })),
662            "invalid num_observations should return InvalidNumber"
663        );
664        Ok(())
665    }
666
667    // -------------------------------------------------------------------------
668    // parse_observations additional error paths
669    // -------------------------------------------------------------------------
670
671    #[test]
672    fn test_load_observation_missing_fields() -> TestResult {
673        let mut f = NamedTempFile::new()?;
674        writeln!(f, "1 1 1")?;
675        writeln!(f, "0 1.0")?; // only 2 fields, need 4
676        f.flush()?;
677        let result = BalLoader::load(f.path());
678        assert!(
679            matches!(result, Err(IoError::MissingFields { .. })),
680            "observation with too few fields should return MissingFields"
681        );
682        Ok(())
683    }
684
685    #[test]
686    fn test_load_observation_invalid_camera_index() -> TestResult {
687        let mut f = NamedTempFile::new()?;
688        writeln!(f, "1 1 1")?;
689        writeln!(f, "bad 0 1.0 2.0")?;
690        f.flush()?;
691        let result = BalLoader::load(f.path());
692        assert!(
693            matches!(result, Err(IoError::InvalidNumber { .. })),
694            "invalid camera_index in observation should return InvalidNumber"
695        );
696        Ok(())
697    }
698
699    #[test]
700    fn test_load_observation_invalid_point_index() -> TestResult {
701        let mut f = NamedTempFile::new()?;
702        writeln!(f, "1 1 1")?;
703        writeln!(f, "0 bad 1.0 2.0")?;
704        f.flush()?;
705        let result = BalLoader::load(f.path());
706        assert!(
707            matches!(result, Err(IoError::InvalidNumber { .. })),
708            "invalid point_index in observation should return InvalidNumber"
709        );
710        Ok(())
711    }
712
713    #[test]
714    fn test_load_observation_invalid_y() -> TestResult {
715        let mut f = NamedTempFile::new()?;
716        writeln!(f, "1 1 1")?;
717        writeln!(f, "0 0 1.0 bad")?;
718        f.flush()?;
719        let result = BalLoader::load(f.path());
720        assert!(
721            matches!(result, Err(IoError::InvalidNumber { .. })),
722            "invalid y in observation should return InvalidNumber"
723        );
724        Ok(())
725    }
726
727    // -------------------------------------------------------------------------
728    // parse_cameras and parse_points additional error paths
729    // -------------------------------------------------------------------------
730
731    #[test]
732    fn test_load_camera_invalid_parameter() -> TestResult {
733        let mut f = NamedTempFile::new()?;
734        writeln!(f, "1 1 1")?;
735        writeln!(f, "0 0 1.0 1.0")?; // observation
736        writeln!(f, "bad")?; // invalid first camera parameter (rx)
737        f.flush()?;
738        let result = BalLoader::load(f.path());
739        assert!(
740            matches!(result, Err(IoError::InvalidNumber { .. })),
741            "invalid camera parameter should return InvalidNumber"
742        );
743        Ok(())
744    }
745
746    #[test]
747    fn test_load_truncated_points() -> TestResult {
748        let mut f = NamedTempFile::new()?;
749        writeln!(f, "1 1 1")?;
750        writeln!(f, "0 0 1.0 1.0")?; // observation
751        // Full camera block
752        for v in [0.0f64, 0.0, 0.0, 0.0, 0.0, 0.0, 500.0, 0.0, 0.0] {
753            writeln!(f, "{v}")?;
754        }
755        // Only 2 of 3 point coordinates
756        writeln!(f, "1.0")?;
757        writeln!(f, "2.0")?;
758        // missing z
759        f.flush()?;
760        let result = BalLoader::load(f.path());
761        assert!(result.is_err(), "truncated point block should fail");
762        Ok(())
763    }
764
765    #[test]
766    fn test_load_point_invalid_coordinate() -> TestResult {
767        let mut f = NamedTempFile::new()?;
768        writeln!(f, "1 1 1")?;
769        writeln!(f, "0 0 1.0 1.0")?; // observation
770        // Full camera block
771        for v in [0.0f64, 0.0, 0.0, 0.0, 0.0, 0.0, 500.0, 0.0, 0.0] {
772            writeln!(f, "{v}")?;
773        }
774        writeln!(f, "bad")?; // invalid point x
775        f.flush()?;
776        let result = BalLoader::load(f.path());
777        assert!(
778            matches!(result, Err(IoError::InvalidNumber { .. })),
779            "invalid point coordinate should return InvalidNumber"
780        );
781        Ok(())
782    }
783}