NavigationResult

Struct NavigationResult 

Source
pub struct NavigationResult {
Show 31 fields pub timestamp: DateTime<Utc>, pub latitude: f64, pub longitude: f64, pub altitude: f64, pub velocity_north: f64, pub velocity_east: f64, pub velocity_down: f64, pub roll: f64, pub pitch: f64, pub yaw: f64, pub acc_bias_x: f64, pub acc_bias_y: f64, pub acc_bias_z: f64, pub gyro_bias_x: f64, pub gyro_bias_y: f64, pub gyro_bias_z: f64, pub latitude_cov: f64, pub longitude_cov: f64, pub altitude_cov: f64, pub velocity_n_cov: f64, pub velocity_e_cov: f64, pub velocity_d_cov: f64, pub roll_cov: f64, pub pitch_cov: f64, pub yaw_cov: f64, pub acc_bias_x_cov: f64, pub acc_bias_y_cov: f64, pub acc_bias_z_cov: f64, pub gyro_bias_x_cov: f64, pub gyro_bias_y_cov: f64, pub gyro_bias_z_cov: f64,
}
Expand description

Generic result struct for navigation simulations.

This structure contains a single row of position, velocity, and attitude vectors representing the navigation solution at a specific timestamp, along with the covariance diagonal, input IMU measurements, and derived geophysical values.

It can be used across different types of navigation simulations such as dead reckoning, Kalman filtering, or any other navigation algorithm.

Fields§

§timestamp: DateTime<Utc>

Timestamp corresponding to the state

§latitude: f64

Latitude in radians

§longitude: f64

Longitude in radians

§altitude: f64

Altitude in meters

§velocity_north: f64

Northward velocity in m/s

§velocity_east: f64

Eastward velocity in m/s

§velocity_down: f64

Downward velocity in m/s

§roll: f64

Roll angle in radians

§pitch: f64

Pitch angle in radians

§yaw: f64

Yaw angle in radians

§acc_bias_x: f64

IMU accelerometer x-axis bias in m/s^2

§acc_bias_y: f64

IMU accelerometer y-axis bias in m/s^2

§acc_bias_z: f64

IMU accelerometer z-axis bias in m/s^2

§gyro_bias_x: f64

IMU gyroscope x-axis bias in radians/s

§gyro_bias_y: f64

IMU gyroscope y-axis bias in radians/s

§gyro_bias_z: f64

IMU gyroscope z-axis bias in radians/s

§latitude_cov: f64

Latitude covariance

§longitude_cov: f64

Longitude covariance

§altitude_cov: f64

Altitude covariance

§velocity_n_cov: f64

Northward velocity covariance

§velocity_e_cov: f64

Eastward velocity covariance

§velocity_d_cov: f64

Downward velocity covariance

§roll_cov: f64

Roll covariance

§pitch_cov: f64

Pitch covariance

§yaw_cov: f64

Yaw covariance

§acc_bias_x_cov: f64

Accelerometer x-axis bias covariance

§acc_bias_y_cov: f64

Accelerometer y-axis bias covariance

§acc_bias_z_cov: f64

Accelerometer z-axis bias covariance

§gyro_bias_x_cov: f64

Gyroscope x-axis bias covariance

§gyro_bias_y_cov: f64

Gyroscope y-axis bias covariance

§gyro_bias_z_cov: f64

Gyroscope z-axis bias covariance

Implementations§

Source§

impl NavigationResult

Source

pub fn new() -> Self

Creates a new NavigationResult with default values.

Source

pub fn to_csv<P: AsRef<Path>>(records: &[Self], path: P) -> Result<()>

Writes the NavigationResult to a CSV file.

§Arguments
  • records - Vector of NavigationResult structs to write
  • path - Path where the CSV file will be saved
§Returns
  • io::Result<()> - Ok if successful, Err otherwise
Source

pub fn from_csv<P: AsRef<Path>>(path: P) -> Result<Vec<Self>, Box<dyn Error>>

Reads a CSV file and returns a vector of NavigationResult structs.

§Arguments
  • path - Path to the CSV file to read.
§Returns
  • Ok(Vec<NavigationResult>) if successful.
  • Err if the file cannot be read or parsed.

Trait Implementations§

Source§

impl Clone for NavigationResult

Source§

fn clone(&self) -> NavigationResult

Returns a duplicate of the value. Read more
1.0.0 · Source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
Source§

impl Debug for NavigationResult

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
Source§

impl Default for NavigationResult

Source§

fn default() -> Self

Returns the “default value” for a type. Read more
Source§

impl<'de> Deserialize<'de> for NavigationResult

Source§

fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>
where __D: Deserializer<'de>,

Deserialize this value from the given Serde deserializer. Read more
Source§

impl From<(&DateTime<Utc>, &Matrix<f64, Dyn, Const<1>, VecStorage<f64, Dyn, Const<1>>>, &Matrix<f64, Dyn, Dyn, VecStorage<f64, Dyn, Dyn>>)> for NavigationResult

Convert DVectors containing the navigation state mean and covariance into a NavigationResult struct.

This implementation is useful for converting the output of a Kalman filter or UKF into a NavigationResult, which can then be used for further processing or analysis.

§Arguments

  • timestamp: The timestamp of the navigation solution.
  • state: A DVector containing the navigation state mean.
  • covariance: A DMatrix containing the covariance of the state.
  • imu_data: An IMUData struct containing the IMU measurements.
  • mag_x, mag_y, mag_z: Magnetic field strength in micro teslas.
  • pressure: Pressure in millibars.
  • freeair: Free-air gravity anomaly in mGal.

§Returns

A NavigationResult struct containing the navigation solution.

Source§

fn from( (timestamp, state, covariance): (&DateTime<Utc>, &DVector<f64>, &DMatrix<f64>), ) -> Self

Converts to this type from the input type.
Source§

impl From<(&DateTime<Utc>, &StrapdownState, &IMUData, &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, &f64)> for NavigationResult

Convert StrapdownState to NavigationResult.

This implementation is useful for converting the output of a StrapdownState into a NavigationResult, which can then be used for further processing or analysis.

§Arguments

  • timestamp: The timestamp of the navigation solution.
  • state: A reference to the StrapdownState instance containing the navigation state.
  • imu_data: An IMUData struct containing the IMU measurements.
  • magnetic_vector: Magnetic field strength measurement in micro teslas (body frame x, y, z).
  • pressure: Pressure in millibars.

§Returns

A NavigationResult struct containing the navigation solution.

Source§

fn from( (timestamp, state, imu_data, magnetic_vector, pressure): (&DateTime<Utc>, &StrapdownState, &IMUData, &Vector3<f64>, &f64), ) -> Self

Converts to this type from the input type.
Source§

impl From<(&DateTime<Utc>, &UKF)> for NavigationResult

Convert NED UKF to NavigationResult.

This implementation is useful for converting the output of a UKF into a NavigationResult, which can then be used for further processing or analysis.

§Arguments

  • timestamp: The timestamp of the navigation solution.
  • ukf: A reference to the UKF instance containing the navigation state mean and covariance.
  • imu_data: An IMUData struct containing the IMU measurements.
  • magnetic_vector: Magnetic field strength measurement in micro teslas (body frame x, y, z).
  • pressure: Pressure in millibars.

§Returns

A NavigationResult struct containing the navigation solution.

Source§

fn from((timestamp, ukf): (&DateTime<Utc>, &UKF)) -> Self

Converts to this type from the input type.
Source§

impl Serialize for NavigationResult

Source§

fn serialize<__S>(&self, __serializer: __S) -> Result<__S::Ok, __S::Error>
where __S: Serializer,

Serialize this value into the given Serde serializer. Read more

Auto Trait Implementations§

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dest: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T> Same for T

Source§

type Output = T

Should always be Self
Source§

impl<SS, SP> SupersetOf<SS> for SP
where SS: SubsetOf<SP>,

Source§

fn to_subset(&self) -> Option<SS>

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more
Source§

fn is_in_subset(&self) -> bool

Checks if self is actually part of its subset T (and can be converted to it).
Source§

fn to_subset_unchecked(&self) -> SS

Use with care! Same as self.to_subset but without any property checks. Always succeeds.
Source§

fn from_subset(element: &SS) -> SP

The inclusion map: converts self to the equivalent element of its superset.
Source§

impl<SS, SP> SupersetOf<SS> for SP
where SS: SubsetOf<SP>,

Source§

fn to_subset(&self) -> Option<SS>

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more
Source§

fn is_in_subset(&self) -> bool

Checks if self is actually part of its subset T (and can be converted to it).
Source§

fn to_subset_unchecked(&self) -> SS

Use with care! Same as self.to_subset but without any property checks. Always succeeds.
Source§

fn from_subset(element: &SS) -> SP

The inclusion map: converts self to the equivalent element of its superset.
Source§

impl<T> ToOwned for T
where T: Clone,

Source§

type Owned = T

The resulting type after obtaining ownership.
Source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
Source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
Source§

impl<V, T> VZip<V> for T
where V: MultiLane<T>,

Source§

fn vzip(self) -> V

Source§

impl<T> DeserializeOwned for T
where T: for<'de> Deserialize<'de>,