pub mod earth;
pub mod filter;
pub mod linalg;
pub mod messages;
pub mod sim;
use nalgebra::{DVector, Matrix3, Rotation3, Vector3};
use std::convert::{From, Into, TryFrom};
use std::fmt::{Debug, Display};
#[derive(Clone, Copy, Debug, Default)]
pub struct IMUData {
pub accel: Vector3<f64>, pub gyro: Vector3<f64>, }
impl Display for IMUData {
fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
write!(
f,
"IMUData {{ accel: [{:.4}, {:.4}, {:.4}], gyro: [{:.4}, {:.4}, {:.4}] }}",
self.accel[0], self.accel[1], self.accel[2], self.gyro[0], self.gyro[1], self.gyro[2]
)
}
}
impl From<Vec<f64>> for IMUData {
fn from(vec: Vec<f64>) -> Self {
if vec.len() != 6 {
panic!(
"IMUData must be initialized with a vector of length 6 (3 for accel, 3 for gyro)"
);
}
IMUData {
accel: Vector3::new(vec[0], vec[1], vec[2]),
gyro: Vector3::new(vec[3], vec[4], vec[5]),
}
}
}
impl Into<Vec<f64>> for IMUData {
fn into(self) -> Vec<f64> {
vec![
self.accel[0],
self.accel[1],
self.accel[2],
self.gyro[0],
self.gyro[1],
self.gyro[2],
]
}
}
#[derive(Clone, Copy)]
pub struct StrapdownState {
pub latitude: f64,
pub longitude: f64,
pub altitude: f64,
pub velocity_north: f64,
pub velocity_east: f64,
pub velocity_down: f64,
pub attitude: Rotation3<f64>,
pub coordinate_convention: bool, }
impl Debug for StrapdownState {
fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
let (roll, pitch, yaw) = self.attitude.euler_angles();
write!(
f,
"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] }}",
self.latitude.to_degrees(),
self.longitude.to_degrees(),
self.altitude,
self.velocity_north,
self.velocity_east,
self.velocity_down,
roll.to_degrees(),
pitch.to_degrees(),
yaw.to_degrees()
)
}
}
impl Default for StrapdownState {
fn default() -> Self {
StrapdownState {
latitude: 0.0,
longitude: 0.0,
altitude: 0.0,
velocity_north: 0.0,
velocity_east: 0.0,
velocity_down: 0.0,
attitude: Rotation3::identity(),
coordinate_convention: true, }
}
}
impl StrapdownState {
pub fn new(
latitude: f64,
longitude: f64,
altitude: f64,
velocity_north: f64,
velocity_east: f64,
velocity_down: f64,
attitude: Rotation3<f64>,
in_degrees: bool,
ned: bool,
) -> StrapdownState {
let latitude = if in_degrees {
latitude.to_radians()
} else {
latitude
};
let longitude = if in_degrees {
longitude.to_radians()
} else {
longitude
};
assert!(
latitude >= -std::f64::consts::PI && latitude <= std::f64::consts::PI,
"Latitude must be in the range [-π, π]"
);
assert!(
longitude >= -std::f64::consts::PI && longitude <= std::f64::consts::PI,
"Longitude must be in the range [-π, π]"
);
assert!(
altitude >= -10_000.0,
"Altitude must be greater than -10,000 meters (to avoid unrealistic values)"
);
StrapdownState {
latitude,
longitude,
altitude,
velocity_north,
velocity_east,
velocity_down,
attitude,
coordinate_convention: ned,
}
}
}
impl From<StrapdownState> for Vec<f64> {
fn from(state: StrapdownState) -> Self {
let (roll, pitch, yaw) = state.attitude.euler_angles();
vec![
state.latitude,
state.longitude,
state.altitude,
state.velocity_north,
state.velocity_east,
state.velocity_down,
roll,
pitch,
yaw,
]
}
}
impl From<&StrapdownState> for Vec<f64> {
fn from(state: &StrapdownState) -> Self {
let (roll, pitch, yaw) = state.attitude.euler_angles();
vec![
state.latitude,
state.longitude,
state.altitude,
state.velocity_north,
state.velocity_east,
state.velocity_down,
roll,
pitch,
yaw,
]
}
}
impl TryFrom<&[f64]> for StrapdownState {
type Error = &'static str;
fn try_from(slice: &[f64]) -> Result<Self, Self::Error> {
if slice.len() != 9 {
return Err("Slice must have length 9 for StrapdownState");
}
let attitude = Rotation3::from_euler_angles(slice[6], slice[7], slice[8]);
Ok(StrapdownState::new(
slice[0], slice[1], slice[2], slice[3], slice[4], slice[5], attitude,
false, true, ))
}
}
impl TryFrom<Vec<f64>> for StrapdownState {
type Error = &'static str;
fn try_from(vec: Vec<f64>) -> Result<Self, Self::Error> {
Self::try_from(vec.as_slice())
}
}
impl From<StrapdownState> for DVector<f64> {
fn from(state: StrapdownState) -> Self {
DVector::from_vec(state.into())
}
}
impl From<&StrapdownState> for DVector<f64> {
fn from(state: &StrapdownState) -> Self {
DVector::from_vec(state.into())
}
}
pub fn forward(state: &mut StrapdownState, imu_data: IMUData, dt: f64) {
let c_0: Rotation3<f64> = state.attitude;
let c_1: Matrix3<f64> = attitude_update(state, imu_data.gyro, dt);
let f: Vector3<f64> = 0.5 * (c_0.matrix() + c_1) * imu_data.accel;
let velocity = velocity_update(state, f, dt);
let (lat_1, lon_1, alt_1) = position_update(state, velocity, dt);
state.attitude = Rotation3::from_matrix(&c_1);
state.velocity_north = velocity[0];
state.velocity_east = velocity[1];
state.velocity_down = velocity[2];
state.latitude = lat_1;
state.longitude = lon_1;
state.altitude = alt_1;
}
fn attitude_update(state: &StrapdownState, gyros: Vector3<f64>, dt: f64) -> Matrix3<f64> {
let transport_rate: Matrix3<f64> = earth::vector_to_skew_symmetric(&earth::transport_rate(
&state.latitude.to_degrees(),
&state.altitude,
&Vector3::from_vec(vec![
state.velocity_north,
state.velocity_east,
state.velocity_down,
]),
));
let rotation_rate: Matrix3<f64> =
earth::vector_to_skew_symmetric(&earth::earth_rate_lla(&state.latitude.to_degrees()));
let omega_ib: Matrix3<f64> = earth::vector_to_skew_symmetric(&gyros);
let c_1: Matrix3<f64> = state.attitude * (Matrix3::identity() + omega_ib * dt)
- (rotation_rate + transport_rate) * state.attitude * dt;
c_1
}
fn velocity_update(state: &StrapdownState, specific_force: Vector3<f64>, dt: f64) -> Vector3<f64> {
let transport_rate: Matrix3<f64> = earth::vector_to_skew_symmetric(&earth::transport_rate(
&state.latitude.to_degrees(),
&state.altitude,
&Vector3::from_vec(vec![
state.velocity_north,
state.velocity_east,
state.velocity_down,
]),
));
let rotation_rate: Matrix3<f64> =
earth::vector_to_skew_symmetric(&earth::earth_rate_lla(&state.latitude.to_degrees()));
let r = earth::ecef_to_lla(&state.latitude.to_degrees(), &state.longitude.to_degrees());
let velocity: Vector3<f64> = Vector3::new(
state.velocity_north,
state.velocity_east,
state.velocity_down,
);
let gravity = Vector3::new(
0.0,
0.0,
earth::gravity(&state.latitude.to_degrees(), &state.altitude),
);
velocity
+ (specific_force - gravity - r * (transport_rate + 2.0 * rotation_rate) * velocity) * dt
}
pub fn position_update(state: &StrapdownState, velocity: Vector3<f64>, dt: f64) -> (f64, f64, f64) {
let (r_n, r_e_0, _) = earth::principal_radii(&state.latitude, &state.altitude);
let lat_0 = state.latitude;
let alt_0 = state.altitude;
let alt_1 = alt_0 + 0.5 * (state.velocity_down + velocity[2]) * dt;
let lat_1: f64 = state.latitude
+ 0.5 * (state.velocity_north / (r_n + alt_0) + velocity[0] / (r_n + state.altitude)) * dt;
let (_, r_e_1, _) = earth::principal_radii(&lat_1, &state.altitude);
let cos_lat0 = lat_0.cos().max(1e-6); let cos_lat1 = lat_1.cos().max(1e-6);
let lon_1: f64 = state.longitude
+ 0.5
* (state.velocity_east / ((r_e_0 + alt_0) * cos_lat0)
+ velocity[1] / ((r_e_1 + state.altitude) * cos_lat1))
* dt;
(
wrap_latitude(lat_1.to_degrees()).to_radians(),
wrap_to_pi(lon_1),
alt_1,
)
}
pub fn wrap_to_180<T>(angle: T) -> T
where
T: PartialOrd + Copy + std::ops::SubAssign + std::ops::AddAssign + From<f64>,
{
let mut wrapped: T = angle;
while wrapped > T::from(180.0) {
wrapped -= T::from(360.0);
}
while wrapped < T::from(-180.0) {
wrapped += T::from(360.0);
}
wrapped
}
pub fn wrap_to_360<T>(angle: T) -> T
where
T: PartialOrd + Copy + std::ops::SubAssign + std::ops::AddAssign + From<f64>,
{
let mut wrapped: T = angle;
while wrapped > T::from(360.0) {
wrapped -= T::from(360.0);
}
while wrapped < T::from(0.0) {
wrapped += T::from(360.0);
}
wrapped
}
pub fn wrap_to_pi<T>(angle: T) -> T
where
T: PartialOrd + Copy + std::ops::SubAssign + std::ops::AddAssign + From<f64>,
{
let mut wrapped: T = angle;
while wrapped > T::from(std::f64::consts::PI) {
wrapped -= T::from(2.0 * std::f64::consts::PI);
}
while wrapped < T::from(-std::f64::consts::PI) {
wrapped += T::from(2.0 * std::f64::consts::PI);
}
wrapped
}
pub fn wrap_to_2pi<T>(angle: T) -> T
where
T: PartialOrd + Copy + std::ops::SubAssign + std::ops::AddAssign + From<f64>,
T: PartialOrd + Copy + std::ops::SubAssign + std::ops::AddAssign + From<i32>,
{
let mut wrapped: T = angle;
while wrapped > T::from(2.0 * std::f64::consts::PI) {
wrapped -= T::from(2.0 * std::f64::consts::PI);
}
while wrapped < T::from(0.0) {
wrapped += T::from(2.0 * std::f64::consts::PI);
}
wrapped
}
pub fn wrap_latitude<T>(latitude: T) -> T
where
T: PartialOrd + Copy + std::ops::SubAssign + std::ops::AddAssign + From<f64>,
{
let mut wrapped: T = latitude;
while wrapped > T::from(90.0) {
wrapped -= T::from(180.0);
}
while wrapped < T::from(-90.0) {
wrapped += T::from(180.0);
}
wrapped
}
#[cfg(test)]
mod tests {
use super::*;
use assert_approx_eq::assert_approx_eq;
#[test]
fn test_strapdown_state_new() {
let state = StrapdownState::default();
assert_eq!(state.latitude, 0.0);
assert_eq!(state.longitude, 0.0);
assert_eq!(state.altitude, 0.0);
assert_eq!(state.velocity_north, 0.0);
assert_eq!(state.velocity_east, 0.0);
assert_eq!(state.velocity_down, 0.0);
assert_eq!(state.attitude, Rotation3::identity());
}
#[test]
fn test_to_vector_zeros() {
let state = StrapdownState::default();
let state_vector: Vec<f64> = state.into();
let zeros = vec![0.0; 9];
assert_eq!(state_vector, zeros);
}
#[test]
fn test_new_from_vector() {
let roll: f64 = 15.0;
let pitch: f64 = 45.0;
let yaw: f64 = 90.0;
let state_vector = vec![0.0, 0.0, 0.0, 0.0, 0.0, 0.0, roll, pitch, yaw];
let state = StrapdownState::try_from(state_vector).unwrap();
assert_eq!(state.latitude, 0.0);
assert_eq!(state.longitude, 0.0);
assert_eq!(state.altitude, 0.0);
assert_eq!(state.velocity_north, 0.0);
}
#[test]
fn test_dcm_to_vector() {
let state = StrapdownState::default();
let state_vector: Vec<f64> = (&state).into();
assert_eq!(state_vector.len(), 9);
assert_eq!(state_vector, vec![0.0; 9]);
}
#[test]
fn test_attitude_matrix_euler_consistency() {
let state = StrapdownState::default();
let (roll, pitch, yaw) = state.attitude.euler_angles();
let state_vector: Vec<f64> = state.into();
assert_eq!(state_vector[6], roll);
assert_eq!(state_vector[7], pitch);
assert_eq!(state_vector[8], yaw);
}
#[test]
fn test_forward_freefall_stub() {
let attitude = Rotation3::identity();
let state = StrapdownState::new(
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, attitude, false, true, );
assert_eq!(state.latitude, 0.0);
assert_eq!(state.longitude, 0.0);
assert_eq!(state.altitude, 0.0);
assert_eq!(state.velocity_north, 0.0);
assert_eq!(state.velocity_east, 0.0);
assert_eq!(state.velocity_down, 0.0);
assert_eq!(state.attitude, Rotation3::identity());
}
#[test]
fn rest() {
let attitude = Rotation3::identity();
let mut state = StrapdownState::new(
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, attitude, false, true, );
assert_eq!(state.velocity_north, 0.0);
assert_eq!(state.velocity_east, 0.0);
assert_eq!(state.velocity_down, 0.0);
let imu_data = IMUData {
accel: Vector3::new(0.0, 0.0, earth::gravity(&0.0, &0.0)),
gyro: Vector3::new(0.0, 0.0, 0.0), };
let dt = 1.0; forward(&mut state, imu_data, dt);
assert_approx_eq!(state.latitude, 0.0, 1e-6);
assert_approx_eq!(state.longitude, 0.0, 1e-6);
assert_approx_eq!(state.altitude, 0.0, 0.1);
assert_approx_eq!(state.velocity_north, 0.0, 1e-3);
assert_approx_eq!(state.velocity_east, 0.0, 1e-3);
assert_approx_eq!(state.velocity_down, 0.0, 0.1);
let attitude = state.attitude.matrix() - Rotation3::identity().matrix();
assert_approx_eq!(attitude[(0, 0)], 0.0, 1e-3);
assert_approx_eq!(attitude[(0, 1)], 0.0, 1e-3);
assert_approx_eq!(attitude[(0, 2)], 0.0, 1e-3);
assert_approx_eq!(attitude[(1, 0)], 0.0, 1e-3);
assert_approx_eq!(attitude[(1, 1)], 0.0, 1e-3);
assert_approx_eq!(attitude[(1, 2)], 0.0, 1e-3);
assert_approx_eq!(attitude[(2, 0)], 0.0, 1e-3);
assert_approx_eq!(attitude[(2, 1)], 0.0, 1e-3);
assert_approx_eq!(attitude[(2, 2)], 0.0, 1e-3);
}
#[test]
fn yawing() {
let attitude = Rotation3::from_euler_angles(0.0, 0.0, 0.1); let state = StrapdownState::new(
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, attitude, false, true, );
assert_approx_eq!(state.attitude.euler_angles().2, 0.1, 1e-6); let gyros = Vector3::new(0.0, 0.0, 0.1); let dt = 1.0; let new_attitude = Rotation3::from_matrix(&attitude_update(&state, gyros, dt));
let new_yaw = new_attitude.euler_angles().2;
assert_approx_eq!(new_yaw, 0.1 + 0.1, 1e-3); }
#[test]
fn rolling() {
let attitude = Rotation3::from_euler_angles(0.1, 0.0, 0.0); let state = StrapdownState::new(
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, attitude, false, true, );
assert_approx_eq!(state.attitude.euler_angles().0, 0.1, 1e-6); let gyros = Vector3::new(0.10, 0.0, 0.0); let dt = 1.0; let new_attitude = Rotation3::from_matrix(&attitude_update(&state, gyros, dt));
let new_roll = new_attitude.euler_angles().0;
assert_approx_eq!(new_roll, 0.1 + 0.1, 1e-3); }
#[test]
fn pitching() {
let attitude = Rotation3::from_euler_angles(0.0, 0.1, 0.0); let state = StrapdownState::new(
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, attitude, false, true, );
assert_approx_eq!(state.attitude.euler_angles().1, 0.1, 1e-6); let gyros = Vector3::new(0.0, 0.1, 0.0); let dt = 1.0; let new_attitude = Rotation3::from_matrix(&attitude_update(&state, gyros, dt));
let new_pitch = new_attitude.euler_angles().1;
assert_approx_eq!(new_pitch, 0.1 + 0.1, 1e-3); }
#[test]
fn test_wrap_to_180() {
assert_eq!(super::wrap_to_180(190.0), -170.0);
assert_eq!(super::wrap_to_180(-190.0), 170.0);
assert_eq!(super::wrap_to_180(0.0), 0.0);
assert_eq!(super::wrap_to_180(180.0), 180.0);
assert_eq!(super::wrap_to_180(-180.0), -180.0);
}
#[test]
fn test_wrap_to_360() {
assert_eq!(super::wrap_to_360(370.0), 10.0);
assert_eq!(super::wrap_to_360(-10.0), 350.0);
assert_eq!(super::wrap_to_360(0.0), 0.0);
}
#[test]
fn test_wrap_to_pi() {
assert_eq!(
super::wrap_to_pi(3.0 * std::f64::consts::PI),
std::f64::consts::PI
);
assert_eq!(
super::wrap_to_pi(-3.0 * std::f64::consts::PI),
-std::f64::consts::PI
);
assert_eq!(super::wrap_to_pi(0.0), 0.0);
assert_eq!(
super::wrap_to_pi(std::f64::consts::PI),
std::f64::consts::PI
);
assert_eq!(
super::wrap_to_pi(-std::f64::consts::PI),
-std::f64::consts::PI
);
}
#[test]
fn test_wrap_to_2pi() {
assert_eq!(
super::wrap_to_2pi(7.0 * std::f64::consts::PI),
std::f64::consts::PI
);
assert_eq!(
super::wrap_to_2pi(-5.0 * std::f64::consts::PI),
std::f64::consts::PI
);
assert_eq!(super::wrap_to_2pi(0.0), 0.0);
assert_eq!(
super::wrap_to_2pi(std::f64::consts::PI),
std::f64::consts::PI
);
assert_eq!(
super::wrap_to_2pi(-std::f64::consts::PI),
std::f64::consts::PI
);
}
#[test]
fn test_velocity_update_zero_force() {
let state = StrapdownState::default();
let f = nalgebra::Vector3::new(
0.0,
0.0,
earth::gravity(&0.0, &0.0), );
let dt = 1.0;
let v_new = velocity_update(&state, f, dt);
assert_eq!(v_new[0], 0.0);
assert_eq!(v_new[1], 0.0);
assert_eq!(v_new[2], 0.0);
}
#[test]
fn test_velocity_update_constant_force() {
let state = StrapdownState::default();
let f = nalgebra::Vector3::new(1.0, 0.0, earth::gravity(&0.0, &0.0)); let dt = 2.0;
let v_new = velocity_update(&state, f, dt);
assert!((v_new[0] - 2.0).abs() < 1e-6);
assert!((v_new[1]).abs() < 1e-6);
assert!((v_new[2]).abs() < 1e-6);
}
#[test]
fn test_velocity_update_initial_velocity() {
let mut state = StrapdownState::default();
state.velocity_north = 5.0;
state.velocity_east = -3.0;
state.velocity_down = 2.0;
let f = Vector3::from_vec(vec![0.0, 0.0, earth::gravity(&0.0, &0.0)]);
let dt = 1.0;
let v_new = velocity_update(&state, f, dt);
assert_approx_eq!(v_new[0], 5.0, 1e-3);
assert_approx_eq!(v_new[1], -3.0, 1e-3);
assert_approx_eq!(v_new[2], 2.0, 1e-3);
}
#[test]
fn vertical_acceleration() {
let mut state = StrapdownState::default();
state.velocity_north = 0.0;
state.velocity_east = 0.0;
state.velocity_down = 0.0;
let f = Vector3::from_vec(vec![0.0, 0.0, 2.0 * earth::gravity(&0.0, &0.0)]); let dt = 1.0;
let v_new = velocity_update(&state, f, dt);
assert_approx_eq!(v_new[2], earth::gravity(&0.0, &0.0), 1e-3);
}
#[test]
fn test_forward_yawing() {
let attitude = nalgebra::Rotation3::identity();
let mut state = StrapdownState::new(0.0, 0.0, 0.0, 0.0, 0.0, 0.0, attitude, false, true);
let imu_data = IMUData {
accel: Vector3::new(0.0, 0.0, 0.0),
gyro: Vector3::new(0.0, 0.0, 0.1), };
let dt = 1.0;
forward(&mut state, imu_data, dt);
let (_, _, yaw) = state.attitude.euler_angles();
assert!((yaw - 0.1).abs() < 1e-3);
}
#[test]
fn test_forward_rolling() {
let attitude = nalgebra::Rotation3::identity();
let mut state = StrapdownState::new(0.0, 0.0, 0.0, 0.0, 0.0, 0.0, attitude, false, true);
let imu_data = IMUData {
accel: Vector3::new(0.0, 0.0, 0.0),
gyro: Vector3::new(0.1, 0.0, 0.0), };
let dt = 1.0;
forward(&mut state, imu_data, dt);
let roll = state.attitude.euler_angles().0;
assert_approx_eq!(roll, 0.1, 1e-3);
}
#[test]
fn test_forward_pitching() {
let attitude = nalgebra::Rotation3::identity();
let mut state = StrapdownState::new(0.0, 0.0, 0.0, 0.0, 0.0, 0.0, attitude, false, true);
let imu_data = IMUData {
accel: Vector3::new(0.0, 0.0, 0.0),
gyro: Vector3::new(0.0, 0.1, 0.0), };
let dt = 1.0;
forward(&mut state, imu_data, dt);
let (_, pitch, _) = state.attitude.euler_angles();
assert_approx_eq!(pitch, 0.1, 1e-3); }
}