pub struct StrapdownState {
pub position: Vector3<f64>,
pub velocity: Vector3<f64>,
pub attitude: Rotation3<f64>,
}
Expand description
Basic structure for holding the strapdown mechanization state in the form of position, velocity, and attitude. Attitude is stored in matrix form (rotation or direction cosine matrix) and position and velocity are stored as vectors. The order or the states depends on the coordinate system used. The struct does not care, but the coordinate system used will determine which functions you should use. Default is NED but nonetheless must be assigned. For compuational simplicity, latitude and logitude are stored as radians.
Fields§
§position: Vector3<f64>
§velocity: Vector3<f64>
§attitude: Rotation3<f64>
Implementations§
Source§impl StrapdownState
impl StrapdownState
Sourcepub fn new() -> StrapdownState
pub fn new() -> StrapdownState
Create a new StrapdownState with all zeros
Sourcepub fn new_from(
position: Vector3<f64>,
velocity: Vector3<f64>,
attitude: Vector3<f64>,
) -> StrapdownState
pub fn new_from( position: Vector3<f64>, velocity: Vector3<f64>, attitude: Vector3<f64>, ) -> StrapdownState
Create a new StrapdownState from a position, velocity, and attitude vector, where the attitude vector is in the form of Euler angles in degrees
Sourcepub fn new_from_vector(state: SVector<f64, 9>) -> StrapdownState
pub fn new_from_vector(state: SVector<f64, 9>) -> StrapdownState
Convert a one dimensional vector to a StrapdownState
The vector is in the form of: (pn, pe, pd, v_n, v_e, v_d, roll, pitch, yaw) where the angles for attitude, latitude (pn), and longitude (pe) are in radians.
Sourcepub fn forward(&mut self, imu_data: &IMUData, dt: f64)
pub fn forward(&mut self, imu_data: &IMUData, dt: f64)
NED form of the forward kinematics equations. Corresponds to section 5.4 Local-Navigation Frame Equations.
Sourcepub fn to_vector(&self, in_degrees: bool) -> SVector<f64, 9>
pub fn to_vector(&self, in_degrees: bool) -> SVector<f64, 9>
ENU form of the forward kinematics equations. Corresponds to section 5.4 Local-Navigation Frame Equations. Mathematrically identical to NED, but the coordinate order in the data structures is different. Attitude is still specified by a roll-pitch-yaw Euler angle sequence. Convert the StrapdownState to a one dimensional vector The vector is in the form of: [pn, pe, pd, v_n, v_e, v_d, phi, theta, psi]
Trait Implementations§
Source§impl Clone for StrapdownState
impl Clone for StrapdownState
Source§fn clone(&self) -> StrapdownState
fn clone(&self) -> StrapdownState
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read moreSource§impl Debug for StrapdownState
impl Debug for StrapdownState
impl Copy for StrapdownState
Auto Trait Implementations§
impl Freeze for StrapdownState
impl RefUnwindSafe for StrapdownState
impl Send for StrapdownState
impl Sync for StrapdownState
impl Unpin for StrapdownState
impl UnwindSafe for StrapdownState
Blanket Implementations§
Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Source§impl<T> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
Source§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
Source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
self
from the equivalent element of its
superset. Read moreSource§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
self
is actually part of its subset T
(and can be converted to it).Source§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
self.to_subset
but without any property checks. Always succeeds.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self
to the equivalent element of its superset.Source§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
Source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
self
from the equivalent element of its
superset. Read moreSource§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
self
is actually part of its subset T
(and can be converted to it).Source§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
self.to_subset
but without any property checks. Always succeeds.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self
to the equivalent element of its superset.