strapdown/
strapdown.rs

1//! Strapdown navigation toolbox for various navigation filters
2//!
3//! This crate provides a set of tools for implementing navigation filters in Rust. The filters are implemented
4//! as structs that can be initialized and updated with new sensor data. The filters are designed to be used in
5//! a strapdown navigation system, where the orientation of the sensor is known and the sensor data can be used
6//! to estimate the position and velocity of the sensor. While utilities exist for IMU data, this crate does
7//! not currently support IMU output directly and should not be thought of as a full inertial navigation system
8//! (INS). This crate is designed to be used to test the filters that would be used in an INS. It does not
9//! provide utilities for reading raw output from the IMU or act as IMU firmware or driver. As such the IMU data 
10//! is assumed to be pre-filtered and contain the total accelerations and relative rotations. 
11//!
12//! This crate is primarily built off of three additional dependencies:
13//! - [`nav-types`](https://crates.io/crates/nav-types): Provides basic coordinate types and conversions.
14//! - [`nalgebra`](https://crates.io/crates/nalgebra): Provides the linear algebra tools for the filters.
15//! - [`rand`](https://crates.io/crates/rand) and [`rand_distr`](https://crates.io/crates/rand_distr): Provides random number generation for noise and simulation (primarily for particle filter methods).
16//!
17//! All other functionality is built on top of these crates or is auxiliary functionality (e.g. I/O). The primary 
18//! reference text is _Principles of GNSS, Inertial, and Multisensor Integrated Navigation Systems, 2nd Edition_ 
19//! by Paul D. Groves. Where applicable, calculations will be referenced by the appropriate equation number tied 
20//! to the book. In general, variables will be named according to the quantity they represent and not the symbol 
21//! used in the book. For example, the Earth's equatorial radius is named `EQUATORIAL_RADIUS` instead of `a`. 
22//! This style is sometimes relaxed within the body of a given function, but the general rule is to use descriptive 
23//! names for variables and not mathematical symbols.
24//!
25//! ## Strapdown mechanization data and equations
26//!
27//! This crate contains the implementation details for the strapdown navigation equations implemented in the Local
28//! Navigation Frame. The equations are based on the book _Principles of GNSS, Inertial, and Multisensor Integrated
29//! Navigation Systems, Second Edition_ by Paul D. Groves. This file corresponds to Chapter 5.4 and 5.5 of the book.
30//! Effort has been made to reproduce most of the equations following the notation from the book. However, variable
31//! and constants should generally been named for the quantity they represent rather than the symbol used in the book.
32//!
33//! ## Coordinate and state definitions
34//! The typical nine-state NED/ENU navigation state vector is used in this implementation. The state vector is defined as:
35//!
36//! $$
37//! x = [p_n, p_e, p_d, v_n, v_e, v_d, \phi, \theta, \psi]
38//! $$
39//!
40//! Where:
41//! - $p_n$, $p_e$, and $p_d$ are the WGS84 geodetic positions (degrees latitude, degrees longitude, meters relative to the ellipsoid).
42//! - $v_n$, $v_e$, and $v_d$ are the local level frame (NED/ENU) velocities (m/s) along the north axis, east axis, and vertical axis.
43//! - $\phi$, $\theta$, and $\psi$ are the Euler angles (radians) representing the orientation of the body frame relative to the local level frame (XYZ Euler rotation).
44//!
45//! The coordinate convention and order is in NED.
46//!
47//! ### Strapdown equations in the Local-Level Frame
48//! 
49//! This module implements the strapdown mechanization equations in the Local-Level Frame. These equations form the basis
50//! of the forward propagation step (motion/system/state-transition model) of all the filters implemented in this crate.
51//! The rational for this was to design and test it once, then re-use it on the various filters which really only need to
52//! act on the given probability distribution and are largely ambivalent to the actual function and use generic representations
53//! in their mathematics.
54//!
55//! The equations are based on the book _Principles of GNSS, Inertial, and Multisensor Integrated Navigation Systems, Second Edition_
56//! by Paul D. Groves. Below is a summary of the equations implemented in Chapter 5.4 implemented by this module.
57//!
58//! #### Skew-Symmetric notation
59//!
60//! Groves uses a direction cosine matrix representation of orientation (attitude, rotation). As such, to make the matrix math
61//! work out, rotational quantities need to also be represented using matrices. Groves' convention is to use a lower-case
62//! letter for vector quantities (arrays of shape (N,) Python-style, or (N,1) nalgebra/Matlab style) and capital letters for the
63//! skew-symmetric matrix representation of the same vector.
64//!
65//! $$
66//! x = \begin{bmatrix} a \\\\ b \\\\ c \end{bmatrix} \rightarrow X = \begin{bmatrix} 0 & -c & b \\\\ c & 0 & -a \\\\ -b & a & 0 \end{bmatrix}
67//! $$
68//!
69//! #### Attitude update
70//!
71//! Given a direction-cosine matrix $C_b^n$ representing the orientation (attitude, rotation) of the platform's body frame ($b$)
72//! with respect to the local level frame ($n$), the transport rate $\Omega_{en}^n$ representing the rotation of the local level frame
73//! with respect to the Earth-fixed frame ($e$), the Earth's rotation rate $\Omega_{ie}^e$, and the angular rate $\Omega_{ib}^b$
74//! representing the rotation of the body frame with respect to the inertial frame ($i$), the attitude update equation is given by:
75//!
76//! $$
77//! C_b^n(+) \approx C_b^n(-) \left( I + \Omega_{ib}^b t \right) - \left( \Omega_{ie}^e - \Omega_{en}^n \right) C_b^n(-) t
78//! $$
79//!
80//! where $t$ is the time differential and $C(-)$ is the prior attitude. These attitude matrices are then used to transform the
81//! specific forces from the IMU:
82//!
83//! $$
84//! f_{ib}^n \approx \frac{1}{2} \left( C_b^n(+) + C_b^n(-) \right) f_{ib}^b
85//! $$
86//!
87//! #### Velocity Update
88//!
89//! The velocity update equation is given by:
90//!
91//! $$
92//! v(+) \approx v(-) + \left( f_{ib}^n + g_{b}^n - \left( \Omega_{en}^n - \Omega_{ie}^e \right) v(-) \right) t
93//! $$
94//!
95//! #### Position update
96//!
97//! Finally, we update the base position states in three steps. First  we update the altitude:
98//!
99//! $$
100//! p_d(+) = p_d(-) + \frac{1}{2} \left( v_d(-) + v_d(+) \right) t
101//! $$
102//!
103//! Next we update the latitude:
104//!
105//! $$
106//! p_n(+) = p_n(-) + \frac{1}{2} \left( \frac{v_n(-)}{R_n + p_d(-)} + \frac{v_n(+)}{R_n + p_d(+) } \right) t
107//! $$
108//!
109//! Finally, we update the longitude:
110//!
111//! $$
112//! p_e = p_e(-) + \frac{1}{2} \left( \frac{v_e(-)}{R_e + p_d(-) \cos(p_n(-))} + \frac{v_e(+)}{R_e + p_d(+) \cos(p_n(+))} \right) t
113//! $$
114//!
115//! This top-level module provides a public API for each step of the forward mechanization equations, allowing users to
116//! easily pass data in and out.
117pub mod earth;
118pub mod filter;
119pub mod linalg;
120pub mod sim;
121
122use nalgebra::{Matrix3, Rotation3, Vector3, DVector};
123
124use std::convert::{From, Into, TryFrom};
125use std::fmt::{Debug, Display};
126
127/// Basic structure for holding IMU data in the form of acceleration and angular rate vectors.
128///
129/// The vectors are the body frame of the vehicle and represent relative movement. This structure and library is not intended
130/// to be a hardware driver for an IMU, thus the data is assumed to be pre-processed and ready for use in the
131/// mechanization equations (the IMU processing has already filtered out gravitational acceleration).
132#[derive(Clone, Copy, Debug, Default)]
133pub struct IMUData {
134    pub accel: Vector3<f64>, // Acceleration in m/s^2, body frame x, y, z axis
135    pub gyro: Vector3<f64>,  // Angular rate in rad/s, body frame x, y, z axis
136}
137impl Display for IMUData {
138    fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
139        write!(
140            f,
141            "IMUData {{ accel: [{:.4}, {:.4}, {:.4}], gyro: [{:.4}, {:.4}, {:.4}] }}",
142            self.accel[0], self.accel[1], self.accel[2], self.gyro[0], self.gyro[1], self.gyro[2]
143        )
144    }
145}
146impl From<Vec<f64>> for IMUData {
147    fn from(vec: Vec<f64>) -> Self {
148        if vec.len() != 6 {
149            panic!("IMUData must be initialized with a vector of length 6 (3 for accel, 3 for gyro)");
150        }
151        IMUData {
152            accel: Vector3::new(vec[0], vec[1], vec[2]),
153            gyro: Vector3::new(vec[3], vec[4], vec[5]),
154        }
155    }
156}
157impl Into<Vec<f64>> for IMUData {
158    fn into(self) -> Vec<f64> {
159        vec![
160            self.accel[0],
161            self.accel[1],
162            self.accel[2],
163            self.gyro[0],
164            self.gyro[1],
165            self.gyro[2],
166        ]
167    }
168}
169/// Basic structure for holding the strapdown mechanization state in the form of position, velocity, and attitude.
170///
171/// Attitude is stored in matrix form (rotation or direction cosine matrix) and position and velocity are stored as
172/// vectors. The order or the states depends on the coordinate system used. The struct does not care, but the
173/// coordinate system used will determine which functions you should use. Default is NED but nonetheless must be
174/// assigned. For computational simplicity, latitude and longitude are stored as radians.
175#[derive(Clone, Copy)]
176pub struct StrapdownState {
177    /// Latitude in radians
178    pub latitude: f64,
179    /// Longitude in radians
180    pub longitude: f64,
181    /// Altitude in meters
182    pub altitude: f64,
183    /// Velocity north in m/s (NED frame)
184    pub velocity_north: f64,
185    /// Velocity east in m/s (NED frame)
186    pub velocity_east: f64,
187    /// Velocity down in m/s (NED frame)
188    pub velocity_down: f64,
189    /// Attitude as a rotation matrix (unchanged)
190    pub attitude: Rotation3<f64>,
191    /// Coordinate convention used for the state vector (NED or ENU; NED is true by default)
192    pub coordinate_convention: bool, // true for NED, false for ENU
193}
194
195impl Debug for StrapdownState {
196    fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
197        let (roll, pitch, yaw) = self.attitude.euler_angles();
198        write!(
199            f,
200            "StrapdownState {{ lat: {:.4} deg, lon: {:.4} deg, alt: {:.2} m, v_n: {:.3} m/s, v_e: {:.3} m/s, v_d: {:.3} m/s, attitude: [{:.2} deg, {:.2} deg, {:.2} deg] }}",
201            self.latitude.to_degrees(),
202            self.longitude.to_degrees(),
203            self.altitude,
204            self.velocity_north,
205            self.velocity_east,
206            self.velocity_down,
207            roll.to_degrees(),
208            pitch.to_degrees(),
209            yaw.to_degrees()
210        )
211    }
212}
213impl Default for StrapdownState {
214    fn default() -> Self {
215        StrapdownState {
216            latitude: 0.0,
217            longitude: 0.0,
218            altitude: 0.0,
219            velocity_north: 0.0,
220            velocity_east: 0.0,
221            velocity_down: 0.0,
222            attitude: Rotation3::identity(),
223            coordinate_convention: true, // NED by default
224        }
225    }
226}
227impl StrapdownState {
228    /// Create a new StrapdownState from explicit position and velocity components, and attitude
229    ///
230    /// # Arguments
231    /// * `latitude` - Latitude in radians or degrees (see `in_degrees`).
232    /// * `longitude` - Longitude in radians or degrees (see `in_degrees`).
233    /// * `altitude` - Altitude in meters.
234    /// * `velocity_north` - North velocity in m/s.
235    /// * `velocity_east` - East velocity in m/s.
236    /// * `velocity_down` - Down velocity in m/s.
237    /// * `attitude` - Rotation3<f64> attitude matrix.
238    /// * `in_degrees` - If true, angles are provided in degrees and will be converted to radians.
239    /// * `ned` - If true, the coordinate convention is NED (North, East, Down), otherwise ENU (East, North, Up).
240    pub fn new(
241        latitude: f64,
242        longitude: f64,
243        altitude: f64,
244        velocity_north: f64,
245        velocity_east: f64,
246        velocity_down: f64,
247        attitude: Rotation3<f64>,
248        in_degrees: bool,
249        ned: bool,
250    ) -> StrapdownState {
251        let latitude = if in_degrees {
252            latitude.to_radians()
253        } else {
254            latitude
255        };
256        let longitude =  if in_degrees {
257            longitude.to_radians()
258        } else {
259            longitude
260        };
261        assert!(latitude >= -std::f64::consts::PI && latitude <= std::f64::consts::PI, "Latitude must be in the range [-π, π]");
262        assert!(longitude >= -std::f64::consts::PI && longitude <= std::f64::consts::PI, "Longitude must be in the range [-π, π]");
263        assert!(altitude >= -10_000.0, "Altitude must be greater than -10,000 meters (to avoid unrealistic values)");
264
265        StrapdownState {
266            latitude,
267            longitude,
268            altitude,
269            velocity_north,
270            velocity_east,
271            velocity_down,
272            attitude,
273            coordinate_convention: ned,
274        }
275    }
276    // --- From/Into trait implementations for StrapdownState <-> Vec<f64> and &[f64] ---
277}
278impl From<StrapdownState> for Vec<f64> {
279    /// Converts a StrapdownState to a Vec<f64> in NED order, angles in radians.
280    fn from(state: StrapdownState) -> Self {
281        let (roll, pitch, yaw) = state.attitude.euler_angles();
282        vec![
283            state.latitude,
284            state.longitude,
285            state.altitude,
286            state.velocity_north,
287            state.velocity_east,
288            state.velocity_down,
289            roll,
290            pitch,
291            yaw,
292        ]
293    }
294}
295impl From<&StrapdownState> for Vec<f64> {
296    /// Converts a reference to StrapdownState to a Vec<f64> in NED order, angles in radians.
297    fn from(state: &StrapdownState) -> Self {
298        let (roll, pitch, yaw) = state.attitude.euler_angles();
299        vec![
300            state.latitude,
301            state.longitude,
302            state.altitude,
303            state.velocity_north,
304            state.velocity_east,
305            state.velocity_down,
306            roll,
307            pitch,
308            yaw,
309        ]
310    }
311}
312impl TryFrom<&[f64]> for StrapdownState {
313    type Error = &'static str;
314    /// Attempts to create a StrapdownState from a slice of 9 elements (NED order, radians).
315    fn try_from(slice: &[f64]) -> Result<Self, Self::Error> {
316        if slice.len() != 9 {
317            return Err("Slice must have length 9 for StrapdownState");
318        }
319        let attitude = Rotation3::from_euler_angles(slice[6], slice[7], slice[8]);
320        Ok(StrapdownState::new(
321            slice[0],
322            slice[1],
323            slice[2],
324            slice[3],
325            slice[4],
326            slice[5],
327            attitude,
328            false, // angles are in radians
329            true,  // NED convention
330        ))
331    }
332}
333impl TryFrom<Vec<f64>> for StrapdownState {
334    type Error = &'static str;
335    /// Attempts to create a StrapdownState from a Vec<f64> of length 9 (NED order, radians).
336    fn try_from(vec: Vec<f64>) -> Result<Self, Self::Error> {
337        Self::try_from(vec.as_slice())
338    }
339}
340impl From<StrapdownState> for DVector<f64> {
341    /// Converts a StrapdownState to a DVector<f64> in NED order, angles in radians.
342    fn from(state: StrapdownState) -> Self {
343        DVector::from_vec(state.into())
344    }
345}
346impl From<&StrapdownState> for DVector<f64> {
347    /// Converts a reference to StrapdownState to a DVector<f64> in NED order, angles in radians.
348    fn from(state: &StrapdownState) -> Self {
349        DVector::from_vec(state.into())
350    }
351}
352
353/// NED form of the forward kinematics equations. Corresponds to section 5.4 Local-Navigation Frame Equations
354/// from the book _Principles of GNSS, Inertial, and Multisensor Integrated Navigation Systems, Second Edition_
355/// by Paul D. Groves; Second Edition.
356///
357/// This function implements the forward kinematics equations for the strapdown navigation system. It takes
358/// the IMU data and the time step as inputs and updates the position, velocity, and attitude of the system.
359/// The IMU data is assumed to be pre-processed and ready for use in the mechanization equations (i.e. the
360/// gravity vector has already been filtered out and the data represents relative motion).
361///
362/// # Arguments
363/// * `imu_data` - A reference to an IMUData instance containing the acceleration and gyro data in the body frame.
364/// * `dt` - A f64 representing the time step in seconds.
365///
366/// # Example
367/// ```rust
368/// use strapdown::{StrapdownState, IMUData, forward};
369/// use nalgebra::Vector3;
370/// let mut state = StrapdownState::default();
371/// let imu_data = IMUData {
372///    accel: Vector3::new(0.0, 0.0, -9.81), // free fall acceleration in m/s^2
373///    gyro: Vector3::new(0.0, 0.0, 0.0) // No rotation
374/// };
375/// let dt = 0.1; // Example time step in seconds
376/// forward(&mut state, imu_data, dt);
377/// ```
378pub fn forward(state: &mut StrapdownState, imu_data: IMUData, dt: f64) {
379    // Extract the attitude matrix from the current state
380    let c_0: Rotation3<f64> = state.attitude;
381    // Attitude update; Equation 5.46
382    let c_1: Matrix3<f64> = attitude_update(state, imu_data.gyro, dt);
383    // Specific force transformation; Equation 5.47
384    let f: Vector3<f64> = 0.5 * (c_0.matrix() + c_1) * imu_data.accel;
385    // Velocity update; Equation 5.54
386    let velocity = velocity_update(state, f, dt);
387    // Position update; Equation 5.56
388    let (lat_1, lon_1, alt_1) = position_update(state, velocity, dt);
389    // Save updated attitude as rotation
390    state.attitude = Rotation3::from_matrix(&c_1);
391    // Save update velocity
392    state.velocity_north = velocity[0];
393    state.velocity_east = velocity[1];
394    state.velocity_down = velocity[2];
395    // Save updated position
396    state.latitude = lat_1;
397    state.longitude = lon_1;
398    state.altitude = alt_1;
399}
400/// NED Attitude update equation
401///
402/// This function implements the attitude update equation for the strapdown navigation system. It takes the gyroscope
403/// data and the time step as inputs and returns the updated attitude matrix. The attitude update equation is based
404/// on the book _Principles of GNSS, Inertial, and Multisensor Integrated Navigation Systems, Second Edition_ by Paul D. Groves.
405///
406/// # Arguments
407/// * `gyros` - A Vector3 representing the gyroscope data in rad/s in the body frame x, y, z axis.
408/// * `dt` - A f64 representing the time step in seconds.
409///
410/// # Returns
411/// * A Matrix3 representing the updated attitude matrix in the NED frame.
412fn attitude_update(state: &StrapdownState, gyros: Vector3<f64>, dt: f64) -> Matrix3<f64> {
413    let transport_rate: Matrix3<f64> = earth::vector_to_skew_symmetric(&earth::transport_rate(
414        &state.latitude.to_degrees(),
415        &state.altitude,
416        &Vector3::from_vec(vec![
417            state.velocity_north,
418            state.velocity_east,
419            state.velocity_down,
420        ]),
421    ));
422    let rotation_rate: Matrix3<f64> =
423        earth::vector_to_skew_symmetric(&earth::earth_rate_lla(&state.latitude.to_degrees()));
424    let omega_ib: Matrix3<f64> = earth::vector_to_skew_symmetric(&gyros);
425    let c_1: Matrix3<f64> = state.attitude * (Matrix3::identity() + omega_ib * dt)
426        - (rotation_rate + transport_rate) * state.attitude * dt;
427    c_1
428}
429/// Velocity update in NED
430///
431/// This function implements the velocity update equation for the strapdown navigation system. It takes the specific force
432/// vector and the time step as inputs and returns the updated velocity vector. The velocity update equation is based
433/// on the book _Principles of GNSS, Inertial, and Multisensor Integrated Navigation Systems, Second Edition_ by Paul D. Groves.
434///
435/// # Arguments
436/// * `f` - A Vector3 representing the specific force vector in m/s^2 in the NED frame.
437/// * `dt` - A f64 representing the time step in seconds.
438///
439/// # Returns
440/// * A Vector3 representing the updated velocity vector in the NED frame.
441fn velocity_update(state: &StrapdownState, specific_force: Vector3<f64>, dt: f64) -> Vector3<f64> {
442    let transport_rate: Matrix3<f64> = earth::vector_to_skew_symmetric(&earth::transport_rate(
443        &state.latitude.to_degrees(),
444        &state.altitude,
445        &Vector3::from_vec(vec![
446            state.velocity_north,
447            state.velocity_east,
448            state.velocity_down,
449        ]),
450    ));
451    let rotation_rate: Matrix3<f64> =
452        earth::vector_to_skew_symmetric(&earth::earth_rate_lla(&state.latitude.to_degrees()));
453    let r = earth::ecef_to_lla(&state.latitude.to_degrees(), &state.longitude.to_degrees());
454    let velocity: Vector3<f64> = Vector3::new(
455        state.velocity_north,
456        state.velocity_east,
457        state.velocity_down,
458    );
459    let gravity = Vector3::new(
460        0.0,
461        0.0,
462        earth::gravity(&state.latitude.to_degrees(), &state.altitude),
463    );
464    velocity
465        + (specific_force - gravity - r * (transport_rate + 2.0 * rotation_rate) * velocity) * dt
466}
467/// Position update in NED
468///
469/// This function implements the position update equation for the strapdown navigation system. It takes the current state,
470/// the velocity vector, and the time step as inputs and returns the updated position (latitude, longitude, altitude).
471///
472/// # Arguments
473/// * `state` - A reference to the current StrapdownState containing the position and velocity.
474/// * `velocity` - A Vector3 representing the velocity vector in m/s in the NED frame.
475/// * `dt` - A f64 representing the time step in seconds.
476///
477/// # Returns
478/// * A tuple (latitude, longitude, altitude) representing the updated position in radians and meters.
479pub fn position_update(state: &StrapdownState, velocity: Vector3<f64>, dt: f64) -> (f64, f64, f64) {
480    let (r_n, r_e_0, _) = earth::principal_radii(&state.latitude, &state.altitude);
481    let lat_0 = state.latitude;
482    let alt_0 = state.altitude;
483    // Altitude update
484    let alt_1 = alt_0 + 0.5 * (state.velocity_down + velocity[2]) * dt;
485    // Latitude update
486    let lat_1: f64 = state.latitude
487        + 0.5 * (state.velocity_north / (r_n + alt_0) + velocity[1] / (r_n + state.altitude)) * dt;
488    // Longitude update
489    let (_, r_e_1, _) = earth::principal_radii(&lat_1, &state.altitude);
490    let lon_1: f64 = state.longitude
491        + 0.5
492            * (state.velocity_east / ((r_e_0 + alt_0) * lat_0.cos())
493                + velocity[1] / ((r_e_1 + state.altitude) * lat_1.cos()))
494            * dt;
495    // Save updated position
496    (
497        wrap_latitude(lat_1.to_degrees()).to_radians(),
498        wrap_to_pi(lon_1),
499        alt_1,
500    )
501}
502// --- Miscellaneous functions for wrapping angles ---
503/// Wrap an angle to the range -180 to 180 degrees
504///
505/// This function is generic and can be used with any type that implements the necessary traits.
506///
507/// # Arguments
508/// * `angle` - The angle to be wrapped, which can be of any type that implements the necessary traits.
509/// # Returns
510/// * The wrapped angle, which will be in the range -180 to 180 degrees.
511/// # Example
512/// ```rust
513/// use strapdown::wrap_to_180;
514/// let angle = 190.0;
515/// let wrapped_angle = wrap_to_180(angle);
516/// assert_eq!(wrapped_angle, -170.0); // 190 degrees wrapped to -170 degrees
517/// ```
518pub fn wrap_to_180<T>(angle: T) -> T
519where
520    T: PartialOrd + Copy + std::ops::SubAssign + std::ops::AddAssign + From<f64>,
521{
522    let mut wrapped: T = angle;
523    while wrapped > T::from(180.0) {
524        wrapped -= T::from(360.0);
525    }
526    while wrapped < T::from(-180.0) {
527        wrapped += T::from(360.0);
528    }
529    wrapped
530}
531/// Wrap an angle to the range 0 to 360 degrees
532///
533/// This function is generic and can be used with any type that implements the necessary traits.
534///
535/// # Arguments
536/// * `angle` - The angle to be wrapped, which can be of any type that implements the necessary traits.
537/// # Returns
538/// * The wrapped angle, which will be in the range 0 to 360 degrees.
539/// # Example
540/// ```rust
541/// use strapdown::wrap_to_360;
542/// let angle = 370.0;
543/// let wrapped_angle = wrap_to_360(angle);
544/// assert_eq!(wrapped_angle, 10.0); // 370 degrees wrapped to 10 degrees
545/// ```
546pub fn wrap_to_360<T>(angle: T) -> T
547where
548    T: PartialOrd + Copy + std::ops::SubAssign + std::ops::AddAssign + From<f64>,
549{
550    let mut wrapped: T = angle;
551    while wrapped > T::from(360.0) {
552        wrapped -= T::from(360.0);
553    }
554    while wrapped < T::from(0.0) {
555        wrapped += T::from(360.0);
556    }
557    wrapped
558}
559/// Wrap an angle to the range 0 to $\pm\pi$ radians
560///
561/// This function is generic and can be used with any type that implements the necessary traits.
562///
563/// # Arguments
564/// * `angle` - The angle to be wrapped, which can be of any type that implements the necessary traits.
565/// # Returns
566/// * The wrapped angle, which will be in the range -π to π radians.
567/// # Example
568/// ```rust
569/// use strapdown::wrap_to_pi;
570/// use std::f64::consts::PI;
571/// let angle = 3.0 * PI / 2.0; // radians
572/// let wrapped_angle = wrap_to_pi(angle);
573/// assert_eq!(wrapped_angle, -PI / 2.0); // 3π/4 radians wrapped to -π/4 radians
574/// ```
575pub fn wrap_to_pi<T>(angle: T) -> T
576where
577    T: PartialOrd + Copy + std::ops::SubAssign + std::ops::AddAssign + From<f64>,
578{
579    let mut wrapped: T = angle;
580    while wrapped > T::from(std::f64::consts::PI) {
581        wrapped -= T::from(2.0 * std::f64::consts::PI);
582    }
583    while wrapped < T::from(-std::f64::consts::PI) {
584        wrapped += T::from(2.0 * std::f64::consts::PI);
585    }
586    wrapped
587}
588/// Wrap an angle to the range 0 to $2 \pi$ radians
589///
590/// This function is generic and can be used with any type that implements the necessary traits.
591///
592/// # Arguments
593/// * `angle` - The angle to be wrapped, which can be of any type that implements the necessary traits.
594/// # Returns
595/// * The wrapped angle, which will be in the range -π to π radians.
596/// # Example
597/// ```rust
598/// use strapdown::wrap_to_2pi;
599/// use std::f64::consts::PI;
600/// let angle = 5.0 * PI; // radians
601/// let wrapped_angle = wrap_to_2pi(angle);
602/// assert_eq!(wrapped_angle, PI); // 5π radians wrapped to π radians
603/// ```
604pub fn wrap_to_2pi<T>(angle: T) -> T
605where
606    T: PartialOrd + Copy + std::ops::SubAssign + std::ops::AddAssign + From<f64>,
607    T: PartialOrd + Copy + std::ops::SubAssign + std::ops::AddAssign + From<i32>,
608{
609    let mut wrapped: T = angle;
610    while wrapped > T::from(2.0 * std::f64::consts::PI) {
611        wrapped -= T::from(2.0 * std::f64::consts::PI);
612    }
613    while wrapped < T::from(0.0) {
614        wrapped += T::from(2.0 * std::f64::consts::PI);
615    }
616    wrapped
617}
618/// Wrap latitude to the range -90 to 90 degrees
619///
620/// This function is generic and can be used with any type that implements the necessary traits.
621/// This function is useful for ensuring that latitude values remain within the valid range for
622/// WGS84 coordinates. Keep in mind that the local level frame (NED/ENU) is typically used for
623/// navigation and positioning in middling latitudes.
624///
625/// # Arguments
626/// * `latitude` - The latitude to be wrapped, which can be of any type that implements the necessary traits.
627/// # Returns
628/// * The wrapped latitude, which will be in the range -90 to 90 degrees.
629/// # Example
630/// ```rust
631/// use strapdown::wrap_latitude;
632/// let latitude = 95.0; // degrees
633/// let wrapped_latitude = wrap_latitude(latitude);
634/// assert_eq!(wrapped_latitude, -85.0); // 95 degrees wrapped to -85 degrees
635/// ```
636pub fn wrap_latitude<T>(latitude: T) -> T
637where
638    T: PartialOrd + Copy + std::ops::SubAssign + std::ops::AddAssign + From<f64>,
639{
640    let mut wrapped: T = latitude;
641    while wrapped > T::from(90.0) {
642        wrapped -= T::from(180.0);
643    }
644    while wrapped < T::from(-90.0) {
645        wrapped += T::from(180.0);
646    }
647    wrapped
648}
649// Note: nalgebra does not yet have a well developed testing framework for directly comparing
650// nalgebra data structures. Rather than directly comparing, check the individual items.
651#[cfg(test)]
652mod tests {
653    use super::*;
654    use assert_approx_eq::assert_approx_eq;
655
656    #[test]
657    fn test_strapdown_state_new() {
658        let state = StrapdownState::default();
659        assert_eq!(state.latitude, 0.0);
660        assert_eq!(state.longitude, 0.0);
661        assert_eq!(state.altitude, 0.0);
662        assert_eq!(state.velocity_north, 0.0);
663        assert_eq!(state.velocity_east, 0.0);
664        assert_eq!(state.velocity_down, 0.0);
665        assert_eq!(state.attitude, Rotation3::identity());
666    }
667    #[test]
668    fn test_to_vector_zeros() {
669        let state = StrapdownState::default();
670        let state_vector: Vec<f64> = state.into();
671        let zeros = vec![0.0; 9];
672        assert_eq!(state_vector, zeros);
673    }
674    #[test]
675    fn test_new_from_vector() {
676        let roll: f64 = 15.0;
677        let pitch: f64 = 45.0;
678        let yaw: f64 = 90.0;
679        let state_vector = vec![0.0, 0.0, 0.0, 0.0, 0.0, 0.0, roll, pitch, yaw];
680        let state = StrapdownState::try_from(state_vector).unwrap();
681        assert_eq!(state.latitude, 0.0);
682        assert_eq!(state.longitude, 0.0);
683        assert_eq!(state.altitude, 0.0);
684        assert_eq!(state.velocity_north, 0.0);
685    }
686    #[test]
687    fn test_dcm_to_vector() {
688        let state = StrapdownState::default();
689        let state_vector: Vec<f64> = (&state).into();
690        assert_eq!(state_vector.len(), 9);
691        assert_eq!(state_vector, vec![0.0; 9]);
692    }
693    #[test]
694    fn test_attitude_matrix_euler_consistency() {
695        let state = StrapdownState::default();
696        let (roll, pitch, yaw) = state.attitude.euler_angles();
697        let state_vector: Vec<f64> = state.into();
698        assert_eq!(state_vector[6], roll);
699        assert_eq!(state_vector[7], pitch);
700        assert_eq!(state_vector[8], yaw);
701    }
702
703    #[test]
704    // Test the forward mechanization (basic structure, not full dynamics)
705    fn test_forward_freefall_stub() {
706        let attitude = Rotation3::identity();
707        let state = StrapdownState::new(
708            0.0, 0.0, 0.0, 0.0, 0.0, 0.0, attitude, false, true, // NED convention
709        );
710        // This is a stub: actual forward propagation logic should be tested in integration with the mechanization equations.
711        assert_eq!(state.latitude, 0.0);
712        assert_eq!(state.longitude, 0.0);
713        assert_eq!(state.altitude, 0.0);
714        assert_eq!(state.velocity_north, 0.0);
715        assert_eq!(state.velocity_east, 0.0);
716        assert_eq!(state.velocity_down, 0.0);
717        assert_eq!(state.attitude, Rotation3::identity());
718    }
719    #[test]
720    fn rest() {
721        // Test the forward mechanization with a state at rest
722        let attitude = Rotation3::identity();
723        let mut state = StrapdownState::new(
724            0.0, 0.0, 0.0, 0.0, 0.0, 0.0, attitude, false, true, // NED convention
725        );
726        assert_eq!(state.velocity_north, 0.0);
727        assert_eq!(state.velocity_east, 0.0);
728        assert_eq!(state.velocity_down, 0.0);
729        let imu_data = IMUData{ 
730            accel: Vector3::new(0.0, 0.0, earth::gravity(&0.0, &0.0)),
731            gyro: Vector3::new(0.0, 0.0, 0.0), // No rotation
732        };
733        let dt = 1.0; // Example time step in seconds
734        forward(&mut state, imu_data, dt);
735        // After a forward step, the state should still be at rest
736        assert_approx_eq!(state.latitude, 0.0, 1e-6);
737        assert_approx_eq!(state.longitude, 0.0, 1e-6);
738        assert_approx_eq!(state.altitude, 0.0, 0.1);
739        assert_approx_eq!(state.velocity_north, 0.0, 1e-3);
740        assert_approx_eq!(state.velocity_east, 0.0, 1e-3);
741        assert_approx_eq!(state.velocity_down, 0.0, 0.1);
742        //assert_approx_eq!(state.attitude, Rotation3::identity(), 1e-3);
743        let attitude = state.attitude.matrix() - Rotation3::identity().matrix();
744        assert_approx_eq!(attitude[(0, 0)], 0.0, 1e-3);
745        assert_approx_eq!(attitude[(0, 1)], 0.0, 1e-3);
746        assert_approx_eq!(attitude[(0, 2)], 0.0, 1e-3);
747        assert_approx_eq!(attitude[(1, 0)], 0.0, 1e-3);
748        assert_approx_eq!(attitude[(1, 1)], 0.0, 1e-3);
749        assert_approx_eq!(attitude[(1, 2)], 0.0, 1e-3);
750        assert_approx_eq!(attitude[(2, 0)], 0.0, 1e-3);
751        assert_approx_eq!(attitude[(2, 1)], 0.0, 1e-3);
752        assert_approx_eq!(attitude[(2, 2)], 0.0, 1e-3);
753    }
754    #[test]
755    fn yawing() {
756        // Testing the forward mechanization with a state that is yawing
757        let attitude = Rotation3::from_euler_angles(0.0, 0.0, 0.1); // 0.1 rad yaw
758        let state = StrapdownState::new(
759            0.0, 0.0, 0.0, 0.0, 0.0, 0.0, attitude, false, // angles provided in radians
760            true,  // NED convention
761        );
762        assert_approx_eq!(state.attitude.euler_angles().2, 0.1, 1e-6); // Check initial yaw
763        let gyros = Vector3::new(0.0, 0.0, 0.1); // Gyro data for yawing
764        let dt = 1.0; // Example time step in seconds
765        let new_attitude = Rotation3::from_matrix(&attitude_update(&state, gyros, dt));
766        // Check if the yaw has changed
767        let new_yaw = new_attitude.euler_angles().2;
768        assert_approx_eq!(new_yaw, 0.1 + 0.1, 1e-3); // 0.1 rad initial + 0.1 rad
769    }
770    #[test]
771    fn rolling() {
772        // Testing the forward mechanization with a state that is yawing
773        let attitude = Rotation3::from_euler_angles(0.1, 0.0, 0.0); // 0.1 rad yaw
774        let state = StrapdownState::new(
775            0.0, 0.0, 0.0, 0.0, 0.0, 0.0, attitude, false, // angles provided in radians
776            true,  // NED convention
777        );
778        assert_approx_eq!(state.attitude.euler_angles().0, 0.1, 1e-6); // Check initial roll
779        let gyros = Vector3::new(0.10, 0.0, 0.0); // Gyro data for yawing
780        let dt = 1.0; // Example time step in seconds
781        let new_attitude = Rotation3::from_matrix(&attitude_update(&state, gyros, dt));
782        // Check if the yaw has changed
783        let new_roll = new_attitude.euler_angles().0;
784        assert_approx_eq!(new_roll, 0.1 + 0.1, 1e-3); // 0.1 rad initial + 0.1 rad
785    }
786    #[test]
787    fn pitching() {
788        // Testing the forward mechanization with a state that is yawing
789        let attitude = Rotation3::from_euler_angles(0.0, 0.1, 0.0); // 0.1 rad yaw
790        let state = StrapdownState::new(
791            0.0, 0.0, 0.0, 0.0, 0.0, 0.0, attitude, false, // angles provided in radians
792            true,  // NED convention
793        );
794        assert_approx_eq!(state.attitude.euler_angles().1, 0.1, 1e-6); // Check initial yaw
795        let gyros = Vector3::new(0.0, 0.1, 0.0); // Gyro data for yawing
796        let dt = 1.0; // Example time step in seconds
797        let new_attitude = Rotation3::from_matrix(&attitude_update(&state, gyros, dt));
798        // Check if the yaw has changed
799        let new_pitch = new_attitude.euler_angles().1;
800        assert_approx_eq!(new_pitch, 0.1 + 0.1, 1e-3); // 0.1 rad initial + 0.1 rad
801    }
802    #[test]
803    fn test_wrap_to_180() {
804        assert_eq!(super::wrap_to_180(190.0), -170.0);
805        assert_eq!(super::wrap_to_180(-190.0), 170.0);
806        assert_eq!(super::wrap_to_180(0.0), 0.0);
807        assert_eq!(super::wrap_to_180(180.0), 180.0);
808        assert_eq!(super::wrap_to_180(-180.0), -180.0);
809    }
810    #[test]
811    fn test_wrap_to_360() {
812        assert_eq!(super::wrap_to_360(370.0), 10.0);
813        assert_eq!(super::wrap_to_360(-10.0), 350.0);
814        assert_eq!(super::wrap_to_360(0.0), 0.0);
815    }
816    #[test]
817    fn test_wrap_to_pi() {
818        assert_eq!(
819            super::wrap_to_pi(3.0 * std::f64::consts::PI),
820            std::f64::consts::PI
821        );
822        assert_eq!(
823            super::wrap_to_pi(-3.0 * std::f64::consts::PI),
824            -std::f64::consts::PI
825        );
826        assert_eq!(super::wrap_to_pi(0.0), 0.0);
827        assert_eq!(
828            super::wrap_to_pi(std::f64::consts::PI),
829            std::f64::consts::PI
830        );
831        assert_eq!(
832            super::wrap_to_pi(-std::f64::consts::PI),
833            -std::f64::consts::PI
834        );
835    }
836    #[test]
837    fn test_wrap_to_2pi() {
838        assert_eq!(
839            super::wrap_to_2pi(7.0 * std::f64::consts::PI),
840            std::f64::consts::PI
841        );
842        assert_eq!(
843            super::wrap_to_2pi(-5.0 * std::f64::consts::PI),
844            std::f64::consts::PI
845        );
846        assert_eq!(super::wrap_to_2pi(0.0), 0.0);
847        assert_eq!(
848            super::wrap_to_2pi(std::f64::consts::PI),
849            std::f64::consts::PI
850        );
851        assert_eq!(
852            super::wrap_to_2pi(-std::f64::consts::PI),
853            std::f64::consts::PI
854        );
855    }
856    #[test]
857    fn test_velocity_update_zero_force() {
858        // Zero specific force, velocity should remain unchanged
859        let state = StrapdownState::default();
860        let f = nalgebra::Vector3::new(
861            0.0,
862            0.0,
863            earth::gravity(&0.0, &0.0), // Gravity vector in NED
864        );
865        let dt = 1.0;
866        let v_new = velocity_update(&state, f, dt);
867        assert_eq!(v_new[0], 0.0);
868        assert_eq!(v_new[1], 0.0);
869        assert_eq!(v_new[2], 0.0);
870    }
871    #[test]
872    fn test_velocity_update_constant_force() {
873        // Constant specific force in north direction, expect velocity to increase linearly
874        let state = StrapdownState::default();
875        let f = nalgebra::Vector3::new(1.0, 0.0, earth::gravity(&0.0, &0.0)); // 1 m/s^2 north
876        let dt = 2.0;
877        let v_new = velocity_update(&state, f, dt);
878        // Should be v = a * dt
879        assert!((v_new[0] - 2.0).abs() < 1e-6);
880        assert!((v_new[1]).abs() < 1e-6);
881        assert!((v_new[2]).abs() < 1e-6);
882    }
883    #[test]
884    fn test_velocity_update_initial_velocity() {
885        // Initial velocity, zero force, should remain unchanged
886        let mut state = StrapdownState::default();
887        state.velocity_north = 5.0;
888        state.velocity_east = -3.0;
889        state.velocity_down = 2.0;
890        let f = Vector3::from_vec(vec![0.0, 0.0, earth::gravity(&0.0, &0.0)]);
891        let dt = 1.0;
892        let v_new = velocity_update(&state, f, dt);
893        assert_approx_eq!(v_new[0], 5.0, 1e-3);
894        assert_approx_eq!(v_new[1], -3.0, 1e-3);
895        assert_approx_eq!(v_new[2], 2.0, 1e-3);
896    }
897    #[test]
898    fn vertical_acceleration() {
899        // Test vertical acceleration
900        let mut state = StrapdownState::default();
901        state.velocity_north = 0.0;
902        state.velocity_east = 0.0;
903        state.velocity_down = 0.0;
904        let f = Vector3::from_vec(vec![0.0, 0.0, 2.0 * earth::gravity(&0.0, &0.0)]); // Downward acceleration
905        let dt = 1.0;
906        let v_new = velocity_update(&state, f, dt);
907        assert_approx_eq!(v_new[2], earth::gravity(&0.0, &0.0), 1e-3);
908    }
909    #[test]
910    fn test_forward_yawing() {
911        // Yaw rate only, expect yaw to increase by gyro_z * dt
912        let attitude = nalgebra::Rotation3::identity();
913        let mut state = StrapdownState::new(
914            0.0, 0.0, 0.0, 0.0, 0.0, 0.0, attitude, false, true,
915        );
916        let imu_data = IMUData{
917            accel: Vector3::new(0.0, 0.0, 0.0), 
918            gyro: Vector3::new(0.0, 0.0, 0.1), // Gyro data for yawing
919        };
920        let dt = 1.0;
921        forward(&mut state, imu_data, dt);
922        let (_, _, yaw) = state.attitude.euler_angles();
923        assert!((yaw - 0.1).abs() < 1e-3);
924    }
925
926    #[test]
927    fn test_forward_rolling() {
928        // Roll rate only, expect roll to increase by gyro_x * dt
929        let attitude = nalgebra::Rotation3::identity();
930        let mut state = StrapdownState::new(
931            0.0, 0.0, 0.0, 0.0, 0.0, 0.0, attitude, false, true,
932        );
933        let imu_data = IMUData {
934            accel: Vector3::new(0.0, 0.0, 0.0), 
935            gyro: Vector3::new(0.1, 0.0, 0.0), // Gyro data for rolling
936        };
937        let dt = 1.0;
938        forward(&mut state, imu_data, dt);
939
940        //let (roll, _, _) = state.attitude.euler_angles();
941        let roll = state.attitude.euler_angles().0;
942        assert_approx_eq!(roll, 0.1, 1e-3);
943    }
944
945    #[test]
946    fn test_forward_pitching() {
947        // Pitch rate only, expect pitch to increase by gyro_y * dt
948        let attitude = nalgebra::Rotation3::identity();
949        let mut state = StrapdownState::new(
950            0.0, 0.0, 0.0, 0.0, 0.0, 0.0, attitude, false, true,
951        );
952        let imu_data = IMUData {
953            accel: Vector3::new(0.0, 0.0, 0.0), 
954            gyro: Vector3::new(0.0, 0.1, 0.0), // Gyro data for pitching
955        };
956        let dt = 1.0;
957        forward(&mut state, imu_data, dt);
958        let (_, pitch, _) = state.attitude.euler_angles();
959        assert_approx_eq!(pitch, 0.1, 1e-3); // 0.1 rad initial + 0.1 rad
960    }
961}