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 let mmap = unsafe {
147 memmap2::Mmap::map(&file).map_err(|e| {
148 IoError::Io(e).log_with_source("Failed to memory-map BAL file".to_string())
149 })?
150 };
151
152 // Convert to UTF-8 string
153 let content = std::str::from_utf8(&mmap).map_err(|_| IoError::Parse {
154 line: 0,
155 message: "File is not valid UTF-8".to_string(),
156 })?;
157
158 // Create line iterator (skip empty lines, trim whitespace)
159 let mut lines = content
160 .lines()
161 .enumerate()
162 .map(|(idx, line)| (idx + 1, line.trim()))
163 .filter(|(_, line)| !line.is_empty());
164
165 // Parse header
166 let (num_cameras, num_points, num_observations) = Self::parse_header(&mut lines)?;
167
168 // Parse observations
169 let observations = Self::parse_observations(&mut lines, num_observations)?;
170
171 // Parse cameras
172 let cameras = Self::parse_cameras(&mut lines, num_cameras)?;
173
174 // Parse points
175 let points = Self::parse_points(&mut lines, num_points)?;
176
177 // Validate counts match header
178 if cameras.len() != num_cameras {
179 return Err(IoError::Parse {
180 line: 0,
181 message: format!(
182 "Camera count mismatch: header says {}, got {}",
183 num_cameras,
184 cameras.len()
185 ),
186 });
187 }
188
189 if points.len() != num_points {
190 return Err(IoError::Parse {
191 line: 0,
192 message: format!(
193 "Point count mismatch: header says {}, got {}",
194 num_points,
195 points.len()
196 ),
197 });
198 }
199
200 if observations.len() != num_observations {
201 return Err(IoError::Parse {
202 line: 0,
203 message: format!(
204 "Observation count mismatch: header says {}, got {}",
205 num_observations,
206 observations.len()
207 ),
208 });
209 }
210
211 Ok(BalDataset {
212 cameras,
213 points,
214 observations,
215 })
216 }
217
218 /// Parses the header line containing dataset dimensions.
219 fn parse_header<'a>(
220 lines: &mut impl Iterator<Item = (usize, &'a str)>,
221 ) -> Result<(usize, usize, usize), IoError> {
222 let (line_num, header_line) = lines.next().ok_or(IoError::Parse {
223 line: 1,
224 message: "Missing header line".to_string(),
225 })?;
226
227 let parts: Vec<&str> = header_line.split_whitespace().collect();
228 if parts.len() != 3 {
229 return Err(IoError::MissingFields { line: line_num });
230 }
231
232 let num_cameras = parts[0]
233 .parse::<usize>()
234 .map_err(|_| IoError::InvalidNumber {
235 line: line_num,
236 value: parts[0].to_string(),
237 })?;
238
239 let num_points = parts[1]
240 .parse::<usize>()
241 .map_err(|_| IoError::InvalidNumber {
242 line: line_num,
243 value: parts[1].to_string(),
244 })?;
245
246 let num_observations = parts[2]
247 .parse::<usize>()
248 .map_err(|_| IoError::InvalidNumber {
249 line: line_num,
250 value: parts[2].to_string(),
251 })?;
252
253 Ok((num_cameras, num_points, num_observations))
254 }
255
256 /// Parses the observations block.
257 fn parse_observations<'a>(
258 lines: &mut impl Iterator<Item = (usize, &'a str)>,
259 num_observations: usize,
260 ) -> Result<Vec<BalObservation>, IoError> {
261 let mut observations = Vec::with_capacity(num_observations);
262
263 for _ in 0..num_observations {
264 let (line_num, line) = lines.next().ok_or(IoError::Parse {
265 line: 0,
266 message: "Unexpected end of file in observations section".to_string(),
267 })?;
268
269 let parts: Vec<&str> = line.split_whitespace().collect();
270 if parts.len() != 4 {
271 return Err(IoError::MissingFields { line: line_num });
272 }
273
274 let camera_index = parts[0]
275 .parse::<usize>()
276 .map_err(|_| IoError::InvalidNumber {
277 line: line_num,
278 value: parts[0].to_string(),
279 })?;
280
281 let point_index = parts[1]
282 .parse::<usize>()
283 .map_err(|_| IoError::InvalidNumber {
284 line: line_num,
285 value: parts[1].to_string(),
286 })?;
287
288 let x = parts[2]
289 .parse::<f64>()
290 .map_err(|_| IoError::InvalidNumber {
291 line: line_num,
292 value: parts[2].to_string(),
293 })?;
294
295 let y = parts[3]
296 .parse::<f64>()
297 .map_err(|_| IoError::InvalidNumber {
298 line: line_num,
299 value: parts[3].to_string(),
300 })?;
301
302 observations.push(BalObservation {
303 camera_index,
304 point_index,
305 x,
306 y,
307 });
308 }
309
310 Ok(observations)
311 }
312
313 /// Parses the cameras block.
314 ///
315 /// Each camera has 9 parameters on sequential lines:
316 /// - 3 lines for rotation (rx, ry, rz)
317 /// - 3 lines for translation (tx, ty, tz)
318 /// - 1 line for focal length (f)
319 /// - 2 lines for radial distortion (k1, k2)
320 fn parse_cameras<'a>(
321 lines: &mut impl Iterator<Item = (usize, &'a str)>,
322 num_cameras: usize,
323 ) -> Result<Vec<BalCamera>, IoError> {
324 let mut cameras = Vec::with_capacity(num_cameras);
325
326 for camera_idx in 0..num_cameras {
327 let mut params = Vec::with_capacity(9);
328
329 // Read 9 consecutive lines for camera parameters
330 for param_idx in 0..9 {
331 let (line_num, line) = lines.next().ok_or(IoError::Parse {
332 line: 0,
333 message: format!(
334 "Unexpected end of file in camera {} parameter {}",
335 camera_idx, param_idx
336 ),
337 })?;
338
339 let value = line
340 .trim()
341 .parse::<f64>()
342 .map_err(|_| IoError::InvalidNumber {
343 line: line_num,
344 value: line.to_string(),
345 })?;
346
347 params.push(value);
348 }
349
350 cameras.push(BalCamera {
351 rotation: Vector3::new(params[0], params[1], params[2]),
352 translation: Vector3::new(params[3], params[4], params[5]),
353 focal_length: BalCamera::normalize_focal_length(params[6]),
354 k1: params[7],
355 k2: params[8],
356 });
357 }
358
359 Ok(cameras)
360 }
361
362 /// Parses the points block.
363 ///
364 /// Each point has 3 coordinates on sequential lines (x, y, z).
365 fn parse_points<'a>(
366 lines: &mut impl Iterator<Item = (usize, &'a str)>,
367 num_points: usize,
368 ) -> Result<Vec<BalPoint>, IoError> {
369 let mut points = Vec::with_capacity(num_points);
370
371 for point_idx in 0..num_points {
372 let mut coords = Vec::with_capacity(3);
373
374 // Read 3 consecutive lines for point coordinates
375 for coord_idx in 0..3 {
376 let (line_num, line) = lines.next().ok_or(IoError::Parse {
377 line: 0,
378 message: format!(
379 "Unexpected end of file in point {} coordinate {}",
380 point_idx, coord_idx
381 ),
382 })?;
383
384 let value = line
385 .trim()
386 .parse::<f64>()
387 .map_err(|_| IoError::InvalidNumber {
388 line: line_num,
389 value: line.to_string(),
390 })?;
391
392 coords.push(value);
393 }
394
395 points.push(BalPoint {
396 position: Vector3::new(coords[0], coords[1], coords[2]),
397 });
398 }
399
400 Ok(points)
401 }
402}