Struct eskf::Builder [−][src]
Builder for ESKF
Implementations
impl Builder
[src]
pub fn new() -> Self
[src]
Create a new ESKF
builder with which to configure an ESKF
pub fn acceleration_variance(self, var: f32) -> Self
[src]
Set the acceleration variance of the IMU system being modeled
The variance should be m/s²
pub fn acceleration_variance_from_vec(self, var: Vector3<f32>) -> Self
[src]
Set the acceleration variance of the IMU system being modeled
The variance should be a vector in [m/s²
, 3]
pub fn rotation_variance(self, var: f32) -> Self
[src]
Set the rotation variance of the IMU system being modeled
The variance should be rad/s
pub fn rotation_variance_from_vec(self, var: Vector3<f32>) -> Self
[src]
Set the rotation variance of the IMU system being modeled
The variance should a vector in [rad/s
, 3]
pub fn acceleration_bias(self, bias: f32) -> Self
[src]
Set the acceleration bias of the IMU system being modeled
The bias should be m/(s²sqrt(s))
pub fn acceleration_bias_from_vec(self, bias: Vector3<f32>) -> Self
[src]
Set the acceleration bias of the IMU system being modeled
The bias should be a vector in [m/(s²sqrt(s))
, 3]
pub fn rotation_bias(self, bias: f32) -> Self
[src]
Set the rotation bias of the IMU system being modeled
The bias should be rad/(s sqrt(s))
pub fn rotation_bias_from_vec(self, bias: Vector3<f32>) -> Self
[src]
Set the rotation bias of the IMU system being modeled
The bias should a vector in [rad/(s sqrt(s))
, 3]
pub fn initial_covariance(self, covar: f32) -> Self
[src]
Set the initial covariance for the process matrix
The covariance value should be a small process value so that the covariance of the filter quickly converges to the correct value. Too small values could lead to the filter taking a long time to converge and report a lower covariance than what it should.
pub fn build(self) -> ESKF
[src]
Convert the builder into a new filter
Trait Implementations
impl Clone for Builder
[src]
impl Copy for Builder
[src]
impl Debug for Builder
[src]
impl Default for Builder
[src]
Auto Trait Implementations
impl RefUnwindSafe for Builder
impl Send for Builder
impl Sync for Builder
impl Unpin for Builder
impl UnwindSafe for Builder
Blanket Implementations
impl<T> Any for T where
T: 'static + ?Sized,
[src]
T: 'static + ?Sized,
impl<T> Borrow<T> for T where
T: ?Sized,
[src]
T: ?Sized,
impl<T> BorrowMut<T> for T where
T: ?Sized,
[src]
T: ?Sized,
pub fn borrow_mut(&mut self) -> &mut T
[src]
impl<T> From<T> for T
[src]
impl<T, U> Into<U> for T where
U: From<T>,
[src]
U: From<T>,
impl<T> Same<T> for T
type Output = T
Should always be Self
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
SS: SubsetOf<SP>,
pub fn to_subset(&self) -> Option<SS>
pub fn is_in_subset(&self) -> bool
pub fn to_subset_unchecked(&self) -> SS
pub fn from_subset(element: &SS) -> SP
impl<T> ToOwned for T where
T: Clone,
[src]
T: Clone,
type Owned = T
The resulting type after obtaining ownership.
pub fn to_owned(&self) -> T
[src]
pub fn clone_into(&self, target: &mut T)
[src]
impl<T, U> TryFrom<U> for T where
U: Into<T>,
[src]
U: Into<T>,
type Error = Infallible
The type returned in the event of a conversion error.
pub fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>
[src]
impl<T, U> TryInto<U> for T where
U: TryFrom<T>,
[src]
U: TryFrom<T>,