imu_calib/
lib.rs

1//! A Rust IMU calibration library.
2//!
3//! Calibrates Acceleration and Gyroscopes with ROS-like datastructures to ease integration into
4//! ROS Nodes.
5//!
6//! The calibration process generates a file, which can be used for into application.
7
8use std::{
9    collections::HashMap,
10    fs::File,
11    hash::Hash,
12    io::{Read, Write},
13    path::PathBuf,
14};
15
16use nalgebra as na;
17
18/// IMU Message similar to ROS.
19#[derive(Debug, Default)]
20pub struct ImuMsg {
21    pub orientation: [f64; 4],
22    pub orientation_covariance: [f64; 9],
23    pub angular_velocity: [f64; 3],
24    pub angular_velocity_covariance: [f64; 9],
25    pub linear_acceleration: [f64; 3],
26    pub linear_acceleration_covariance: [f64; 9],
27}
28
29impl ImuMsg {
30    pub fn new(linear_accel: &[f64; 3], angular_vel: &[f64; 3]) -> Self {
31        Self {
32            linear_acceleration: *linear_accel,
33            angular_velocity: *angular_vel,
34            ..Default::default()
35        }
36    }
37}
38
39#[derive(Debug, PartialEq, Eq, Hash, Clone)]
40enum Orientation {
41    Xpos,
42    Xneg,
43    Ypos,
44    Yneg,
45    Zpos,
46    Zneg,
47}
48
49#[derive(Debug)]
50struct AccelerometerCalibration {
51    pub reference_index: [usize; 6],
52    pub reference_sign: [i32; 6],
53    pub calib_ready: bool,
54
55    /// Combined scale and misalignment parameters.
56    pub sm: na::Matrix3<f64>,
57
58    /// Scaled and rotated bias parameters.
59    pub bias: na::Vector3<f64>,
60
61    /// Expected acceleration measurement (e.g. 1.0 for unit of g's, 9.80665 for unit of m/s^2)
62    pub reference_acceleration: f64,
63
64    pub calib_initialized: bool,
65    pub orientation_count: [usize; 6],
66
67    /// Least squares measurements matrix.
68    pub meas: na::DMatrix<f64>,
69
70    /// Least squares expected measurements vector.
71    pub ref_: na::DVector<f64>,
72
73    /// Number of measurements expected for this calibration.
74    pub num_measurements: usize,
75
76    /// Number of measurements received for this calibration.
77    pub measurements_received: usize,
78}
79
80impl AccelerometerCalibration {
81    /// Initialize new calibration process or load from file.
82    pub fn create(calib_file_path: Option<String>) -> anyhow::Result<Self> {
83        let reference_index = [0, 0, 1, 1, 2, 2];
84        let reference_sign = [1, -1, 1, -1, 1, -1];
85        let calib_ready = false;
86        let sm = na::Matrix3::identity();
87        let bias = na::Vector3::zeros();
88        let reference_acceleration = 1.0;
89        let calib_initialized = false;
90        let orientation_count = [0, 0, 0, 0, 0, 0];
91        let meas = na::DMatrix::zeros(0, 3);
92        let ref_ = na::DVector::zeros(0);
93        let num_measurements = 0;
94        let measurements_received = 0;
95
96        let mut s = Self {
97            reference_index,
98            reference_sign,
99            calib_ready,
100            sm,
101            bias,
102            reference_acceleration,
103            calib_initialized,
104            orientation_count,
105            meas,
106            ref_,
107            num_measurements,
108            measurements_received,
109        };
110
111        if let Some(calib_file_path) = calib_file_path {
112            s.load_calib(calib_file_path)?;
113        }
114
115        Ok(s)
116    }
117
118    fn load_calib(&mut self, calib_file: String) -> anyhow::Result<()> {
119        let mut file = File::open(calib_file)?;
120        let mut contents = String::new();
121        file.read_to_string(&mut contents)?;
122
123        let lines = contents.lines();
124        let sm_str = "SM = [";
125        let bias_str = "bias = [";
126        let mut found_sm = false;
127        let mut found_bias = false;
128
129        for line in lines {
130            if let Some(line) = line.strip_prefix(sm_str) {
131                let mut iter = line.split(", ");
132                for sm_val in self.sm.iter_mut() {
133                    *sm_val = iter.next().unwrap().parse::<f64>()?;
134                }
135                found_sm = true;
136            }
137
138            if let Some(line) = line.strip_prefix(bias_str) {
139                let mut iter = line.split(", ");
140                for bias_val in self.bias.iter_mut() {
141                    *bias_val = iter.next().unwrap().parse::<f64>()?;
142                }
143                found_bias = true;
144            }
145        }
146
147        if !found_sm || !found_bias {
148            return Err(anyhow::anyhow!("Calibration file not formatted correctly"));
149        }
150
151        self.calib_ready = true;
152
153        Ok(())
154    }
155
156    fn save_calib(&self, calib_file: &str) -> anyhow::Result<PathBuf> {
157        if !self.calib_ready {
158            return Err(anyhow::anyhow!("Calibration not ready"));
159        }
160
161        let sm = self
162            .sm
163            .iter()
164            .map(|x| x.to_string())
165            .collect::<Vec<String>>();
166        let bias = self
167            .bias
168            .iter()
169            .map(|x| x.to_string())
170            .collect::<Vec<String>>();
171
172        let mut out_str = String::new();
173        out_str.push_str("SM = [");
174        sm.iter().for_each(|x| {
175            out_str.push_str(x);
176            out_str.push_str(", ");
177        });
178        out_str.push_str("]\n");
179
180        out_str.push_str("bias = [");
181        bias.iter().for_each(|x| {
182            out_str.push_str(x);
183            out_str.push_str(", ");
184        });
185        out_str.push_str("]\n");
186
187        let mut buff = File::create(calib_file)?;
188        buff.write_all(out_str.as_bytes())?;
189        buff.flush()?;
190
191        // get the absolute path of the file
192        let path = std::fs::canonicalize(calib_file)?;
193
194        Ok(path)
195    }
196
197    fn begin_calib(&mut self, measurements: usize, reference_acceleration: f64) {
198        self.reference_acceleration = reference_acceleration;
199        self.num_measurements = measurements;
200        self.measurements_received = 0;
201        self.meas = na::DMatrix::zeros(3 * measurements, 12);
202        self.ref_ = na::DVector::zeros(3 * measurements);
203        self.orientation_count = [0, 0, 0, 0, 0, 0];
204        self.calib_initialized = true;
205    }
206
207    fn add_measurement(&mut self, orientation: &Orientation, ax: f64, ay: f64, az: f64) -> bool {
208        if !self.calib_initialized || self.measurements_received >= self.num_measurements {
209            return false;
210        }
211
212        let orientation = match orientation {
213            Orientation::Xpos => 0,
214            Orientation::Xneg => 1,
215            Orientation::Ypos => 2,
216            Orientation::Yneg => 3,
217            Orientation::Zpos => 4,
218            Orientation::Zneg => 5,
219        };
220
221        for i in 0..3 {
222            self.meas[(3 * self.measurements_received + i, 3 * i)] = ax;
223            self.meas[(3 * self.measurements_received + i, 3 * i + 1)] = ay;
224            self.meas[(3 * self.measurements_received + i, 3 * i + 2)] = az;
225
226            self.meas[(3 * self.measurements_received + i, 9 + i)] = -1.0;
227        }
228
229        self.ref_[3 * self.measurements_received + self.reference_index[orientation]] =
230            self.reference_sign[orientation] as f64 * self.reference_acceleration;
231
232        self.measurements_received += 1;
233        self.orientation_count[orientation] += 1;
234
235        true
236    }
237
238    fn compute_calib(&mut self) -> bool {
239        if self.measurements_received < 12 {
240            return false;
241        }
242
243        for i in 0..6 {
244            if self.orientation_count[i] == 0 {
245                return false;
246            }
247        }
248
249        // solve least squares
250        let xhat = self
251            .meas
252            .clone()
253            .svd(true, true)
254            .solve(&self.ref_, 1e-6)
255            .unwrap();
256
257        for i in 0..9 {
258            self.sm[(i / 3, i % 3)] = xhat[i];
259        }
260
261        for i in 0..3 {
262            self.bias[i] = xhat[9 + i];
263        }
264
265        self.calib_ready = true;
266
267        true
268    }
269
270    fn apply_calib(&self, raw: [f64; 3]) -> [f64; 3] {
271        let raw_accel = na::Vector3::new(raw[0], raw[1], raw[2]);
272        let corrected_accel = self.sm * raw_accel - self.bias;
273
274        [corrected_accel[0], corrected_accel[1], corrected_accel[2]]
275    }
276}
277
278/// Possible states in the processing Statemachine.
279#[derive(Debug)]
280pub enum CalibState {
281    START,
282    SWITCHING,
283    RECEIVING,
284    COMPUTING,
285    DONE,
286}
287
288/// Calibration Process Statemachine.
289#[derive(Debug)]
290pub struct CalibrateProcess {
291    state: CalibState,
292    measurements_per_orientation: usize,
293    measurements_received: usize,
294    reference_acceleration: f64,
295    output_file: String,
296    orientations: Vec<Orientation>,
297    current_orientation: Orientation,
298    orientation_labels: HashMap<Orientation, String>,
299    calib: AccelerometerCalibration,
300}
301
302impl CalibrateProcess {
303    /// Starting new calibration.
304    pub fn new(
305        measurements_per_orientation: usize,
306        reference_acceleration: f64,
307        output_file: String,
308    ) -> Self {
309        let state = CalibState::START;
310        let measurements_received = 0;
311        let orientations = vec![
312            Orientation::Xpos,
313            Orientation::Xneg,
314            Orientation::Ypos,
315            Orientation::Yneg,
316            Orientation::Zpos,
317            Orientation::Zneg,
318        ];
319        let current_orientation = Orientation::Xpos;
320        let orientation_labels = {
321            let mut map = HashMap::new();
322            map.insert(Orientation::Xpos, "X+".to_string());
323            map.insert(Orientation::Xneg, "X-".to_string());
324            map.insert(Orientation::Ypos, "Y+".to_string());
325            map.insert(Orientation::Yneg, "Y-".to_string());
326            map.insert(Orientation::Zpos, "Z+".to_string());
327            map.insert(Orientation::Zneg, "Z-".to_string());
328            map
329        };
330
331        Self {
332            state,
333            measurements_per_orientation,
334            measurements_received,
335            reference_acceleration,
336            output_file,
337            orientations,
338            current_orientation,
339            orientation_labels,
340            calib: AccelerometerCalibration::create(None).unwrap(),
341        }
342    }
343
344    /// Processing the incoming IMU data in respect to the current state.
345    /// Use this function inside your ROS callback.
346    pub fn imu_callback(&mut self, imu: ImuMsg) -> anyhow::Result<()> {
347        match self.state {
348            CalibState::START => {
349                self.calib.begin_calib(
350                    6 * self.measurements_per_orientation,
351                    self.reference_acceleration,
352                );
353                self.state = CalibState::SWITCHING;
354            }
355            CalibState::SWITCHING => {
356                if self.orientations.is_empty() {
357                    self.state = CalibState::COMPUTING;
358                } else {
359                    self.current_orientation = self.orientations.remove(0);
360                    self.measurements_received = 0;
361                    println!(
362                        "Orient IMU with {} axis up and press Enter",
363                        self.orientation_labels[&self.current_orientation]
364                    );
365                    let _ = std::io::stdin().read_line(&mut String::new())?;
366                    self.state = CalibState::RECEIVING;
367                }
368            }
369            CalibState::RECEIVING => {
370                let accepted = self.calib.add_measurement(
371                    &self.current_orientation,
372                    imu.linear_acceleration[0],
373                    imu.linear_acceleration[1],
374                    imu.linear_acceleration[2],
375                );
376                self.measurements_received += if accepted { 1 } else { 0 };
377                if self.measurements_received >= self.measurements_per_orientation {
378                    println!(" Done.");
379                    self.state = CalibState::SWITCHING;
380                }
381            }
382            CalibState::COMPUTING => {
383                println!("Computing calibration parameters...");
384                if self.calib.compute_calib() {
385                    println!(" Success!");
386
387                    println!("Saving calibration file...");
388                    let path = self.calib.save_calib(&self.output_file)?;
389                    println!("Calibration saved to {}", path.display());
390                } else {
391                    println!("Calibration Failed.");
392                }
393                self.state = CalibState::DONE;
394            }
395            CalibState::DONE => {}
396        }
397
398        Ok(())
399    }
400
401    /// Indication for the finished Statemachine.
402    pub fn is_done(&self) -> bool {
403        matches!(self.state, CalibState::DONE)
404    }
405}
406
407/// State for application of a given calibration.
408#[derive(Debug)]
409pub struct CalibrationApplication {
410    calibrate_gyros: bool,
411    printed_gyro_calib_warning: bool,
412    gyro_calib_samples: usize,
413    gyro_sample_count: usize,
414    gyro_bias: [f64; 3],
415    process: CalibrateProcess,
416}
417
418impl CalibrationApplication {
419    /// Initialize the state. Loading from the calibration file can fail.
420    pub fn create(
421        calibrate_gyros: bool,
422        gyro_calib_samples: usize,
423        output_file: String,
424        reference_acceleration: f64,
425    ) -> anyhow::Result<Self> {
426        let gyro_bias = [0.0, 0.0, 0.0];
427        let gyro_sample_count = 0;
428        let mut process = CalibrateProcess::new(
429            gyro_calib_samples,
430            reference_acceleration,
431            output_file.clone(),
432        );
433        process.calib.load_calib(output_file)?;
434
435        Ok(Self {
436            calibrate_gyros,
437            gyro_calib_samples,
438            gyro_sample_count,
439            gyro_bias,
440            process,
441            printed_gyro_calib_warning: false,
442        })
443    }
444
445    /// Apply calibration to the incoming IMU messages.
446    /// Use this function inside your callback from the sensor.
447    /// Returns None as long as gyros are getting initialized.
448    pub fn imu_callback(&mut self, mut imu: ImuMsg) -> Option<ImuMsg> {
449        if self.calibrate_gyros {
450            if !self.printed_gyro_calib_warning {
451                println!("Calibrating gyros - Do not move the IMU");
452                self.printed_gyro_calib_warning = true;
453            }
454
455            self.gyro_sample_count += 1;
456            self.gyro_bias[0] = ((self.gyro_sample_count - 1) as f64 * self.gyro_bias[0]
457                + imu.angular_velocity[0])
458                / self.gyro_sample_count as f64;
459            self.gyro_bias[1] = ((self.gyro_sample_count - 1) as f64 * self.gyro_bias[1]
460                + imu.angular_velocity[1])
461                / self.gyro_sample_count as f64;
462            self.gyro_bias[2] = ((self.gyro_sample_count - 1) as f64 * self.gyro_bias[2]
463                + imu.angular_velocity[2])
464                / self.gyro_sample_count as f64;
465
466            if self.gyro_sample_count >= self.gyro_calib_samples {
467                println!(
468                    "Gyro calibration complete! (bias = [{}, {}, {}])",
469                    self.gyro_bias[0], self.gyro_bias[1], self.gyro_bias[2]
470                );
471                self.calibrate_gyros = false;
472            }
473
474            return None;
475        }
476
477        let corrected_accel = self.process.calib.apply_calib(imu.linear_acceleration);
478        imu.linear_acceleration = corrected_accel;
479
480        imu.angular_velocity[0] -= self.gyro_bias[0];
481        imu.angular_velocity[1] -= self.gyro_bias[1];
482        imu.angular_velocity[2] -= self.gyro_bias[2];
483
484        Some(imu)
485    }
486}