Struct Icm20948

Source
pub struct Icm20948<BUS, MAG, INIT, DELAY, E> { /* private fields */ }

Implementations§

Source§

impl<BUS, DELAY, E> Icm20948<IcmBusI2c<BUS>, MagDisabled, NotInit, DELAY, E>
where BUS: I2c<Error = E>, E: Into<IcmError<E>>, DELAY: DelayNs,

Source

pub fn new_i2c_from_cfg( bus: BUS, cfg: Icm20948Config, delay: DELAY, ) -> Icm20948<IcmBusI2c<BUS>, MagDisabled, NotInit, DELAY, E>

Creates an uninitialized IMU struct with the given config.

Source

pub fn new_i2c( bus: BUS, delay: DELAY, ) -> Icm20948<IcmBusI2c<BUS>, MagDisabled, NotInit, DELAY, E>

Creates an uninitialized IMU struct with a default config.

Source§

impl<BUS, DELAY, E> Icm20948<IcmBusSpi<BUS>, MagDisabled, NotInit, DELAY, E>
where BUS: SpiDevice<Error = E>, E: Into<IcmError<E>>, DELAY: DelayNs,

Source

pub fn new_spi_from_cfg( bus: BUS, cfg: Icm20948Config, delay: DELAY, ) -> Icm20948<IcmBusSpi<BUS>, MagDisabled, NotInit, DELAY, E>

Creates an uninitialized IMU struct with the given config.

Source

pub fn new_spi( bus: BUS, delay: DELAY, ) -> Icm20948<IcmBusSpi<BUS>, MagDisabled, NotInit, DELAY, E>

Creates an uninitialized IMU struct with a default config.

Source§

impl<BUS, DELAY, E> Icm20948<IcmBusI2c<BUS>, MagDisabled, NotInit, DELAY, E>
where BUS: I2c<Error = E>, E: Into<IcmError<E>>, DELAY: DelayNs,

Source

pub fn set_address( self, address: impl Into<I2cAddress>, ) -> Icm20948<IcmBusI2c<BUS>, MagDisabled, NotInit, DELAY, E>

Set I2C address of ICM module. See I2cAddress for defaults, otherwise u8 implements Into<I2cAddress>

Source§

impl<BUS, DELAY, E> Icm20948<BUS, MagDisabled, NotInit, DELAY, E>
where BUS: BusTransfer<E>, DELAY: DelayNs,

Source

pub fn acc_range( self, acc_range: AccRange, ) -> Icm20948<BUS, MagDisabled, NotInit, DELAY, E>

Set accelerometer measuring range, choises are 2G, 4G, 8G or 16G

Source

pub fn acc_dlp( self, acc_dlp: AccDlp, ) -> Icm20948<BUS, MagDisabled, NotInit, DELAY, E>

Set accelerometer digital lowpass filter frequency

Source

pub fn acc_unit( self, acc_unit: AccUnit, ) -> Icm20948<BUS, MagDisabled, NotInit, DELAY, E>

Set returned unit of accelerometer measurement, choises are Gs or m/s^2

Source

pub fn acc_odr( self, acc_odr: u16, ) -> Icm20948<BUS, MagDisabled, NotInit, DELAY, E>

Set accelerometer output data rate

Source

pub fn gyr_range( self, gyr_range: GyrRange, ) -> Icm20948<BUS, MagDisabled, NotInit, DELAY, E>

Set gyroscope measuring range, choises are 250Dps, 500Dps, 1000Dps and 2000Dps

Source

pub fn gyr_dlp( self, gyr_dlp: GyrDlp, ) -> Icm20948<BUS, MagDisabled, NotInit, DELAY, E>

Set gyroscope digital low pass filter frequency

Source

pub fn gyr_unit( self, gyr_unit: GyrUnit, ) -> Icm20948<BUS, MagDisabled, NotInit, DELAY, E>

Set returned unit of gyroscope measurement, choises are degrees/s or radians/s

Source

pub fn gyr_odr( self, gyr_odr: u8, ) -> Icm20948<BUS, MagDisabled, NotInit, DELAY, E>

Set gyroscope output data rate

Source

pub async fn initialize_6dof( self, ) -> Result<Icm20948<BUS, MagDisabled, Init, DELAY, E>, IcmError<E>>

Initializes the IMU with accelerometer and gyroscope

Source

pub async fn initialize_9dof( self, ) -> Result<Icm20948<BUS, MagEnabled, Init, DELAY, E>, IcmError<E>>

Initializes the IMU with accelerometer, gyroscope and magnetometer

Source§

impl<BUS, E, MAG, INIT, DELAY> Icm20948<BUS, MAG, INIT, DELAY, E>
where BUS: BusTransfer<E>, DELAY: DelayNs,

Source

pub async fn device_reset(&mut self) -> Result<(), E>

Reset accelerometer / gyroscope module

Source

pub async fn set_acc_range(&mut self, range: AccRange) -> Result<(), E>

Configure acceleromter to measure with given range

Source

pub async fn set_gyr_range(&mut self, range: GyrRange) -> Result<(), E>

Configure gyroscope to measure with given range

Source

pub fn set_acc_unit(&mut self, unit: AccUnit)

Set returned unit of accelerometer

Source

pub fn set_gyr_unit(&mut self, unit: GyrUnit)

Set returned unit of gyroscope

Source

pub async fn set_acc_dlp(&mut self, acc_dlp: AccDlp) -> Result<(), E>

Set (or disable) accelerometer digital low-pass filter

Source

pub async fn set_gyr_dlp(&mut self, gyr_dlp: GyrDlp) -> Result<(), E>

Set (or disable) gyroscope digital low-pass filter

Source

pub async fn set_acc_odr(&mut self, acc_odr: u16) -> Result<(), E>

Set accelerometer output data rate. Value will be clamped above 4095.

Source

pub async fn set_gyr_odr(&mut self, gyr_odr: u8) -> Result<(), E>

Set gyroscope output data rate.

Source§

impl<BUS, DELAY, E> Icm20948<BUS, MagEnabled, Init, DELAY, E>
where BUS: BusTransfer<E>, DELAY: DelayNs,

Source

pub fn set_mag_calibration(&mut self, offset: [f32; 3], scale: [f32; 3])

Set magnetometer calibration data (offset,scale)

Source

pub fn reset_mag_calibration(&mut self)

Resets (disables) magnetometer calibration data

Source

pub async fn read_mag(&mut self) -> Result<Vector3<f32>, E>

Get vector of scaled magnetometer values

Source

pub async fn read_mag_unscaled(&mut self) -> Result<[i16; 3], E>

Get array of unscaled accelerometer values

Source

pub async fn read_9dof(&mut self) -> Result<Data9Dof<f32>, E>

Get scaled measurement for accelerometer, gyroscope and magnetometer, and temperature

Source

pub async fn read_9dof_unscaled(&mut self) -> Result<Data9Dof<i16>, E>

Get unscaled measurements for accelerometer and gyroscope, and temperature

Source§

impl<BUS, E, MAG, DELAY> Icm20948<BUS, MAG, Init, DELAY, E>
where BUS: BusTransfer<E>, E: Into<IcmError<E>>, DELAY: DelayNs,

Source

pub async fn read_acc_unscaled(&mut self) -> Result<Vector3<i16>, E>

Get array of unscaled accelerometer values

Source

pub async fn read_acc(&mut self) -> Result<Vector3<f32>, E>

Get array of scaled accelerometer values

Source

pub async fn read_gyr_unscaled(&mut self) -> Result<Vector3<i16>, E>

Get array of unscaled gyroscope values

Source

pub async fn read_gyr(&mut self) -> Result<Vector3<f32>, E>

Get array of scaled gyroscope values

Source

pub async fn read_6dof(&mut self) -> Result<Data6Dof<f32>, E>

Get scaled measurements for accelerometer and gyroscope, and temperature

Source

pub async fn read_6dof_unscaled(&mut self) -> Result<Data6Dof<i16>, E>

Get unscaled measurements for accelerometer and gyroscope, and temperature

Source

pub async fn gyr_calibrate(&mut self, num: usize) -> Result<(), E>

Collects and averages num sampels for gyro calibration and saves them on-chip

Source

pub async fn set_gyr_offsets(&mut self, offsets: Vector3<i16>) -> Result<(), E>

Set gyroscope calibration offsets by writing them to the IMU

Source

pub async fn set_acc_offsets(&mut self, offsets: Vector3<i16>) -> Result<(), E>

Set accelerometer calibration offsets by writing them to the IMU

Source

pub async fn new_data_ready(&mut self) -> u8

Returns the number of new readings in FIFO buffer

Auto Trait Implementations§

§

impl<BUS, MAG, INIT, DELAY, E> Freeze for Icm20948<BUS, MAG, INIT, DELAY, E>
where BUS: Freeze, DELAY: Freeze, MAG: Freeze,

§

impl<BUS, MAG, INIT, DELAY, E> RefUnwindSafe for Icm20948<BUS, MAG, INIT, DELAY, E>

§

impl<BUS, MAG, INIT, DELAY, E> Send for Icm20948<BUS, MAG, INIT, DELAY, E>
where BUS: Send, DELAY: Send, MAG: Send, INIT: Send, E: Send,

§

impl<BUS, MAG, INIT, DELAY, E> Sync for Icm20948<BUS, MAG, INIT, DELAY, E>
where BUS: Sync, DELAY: Sync, MAG: Sync, INIT: Sync, E: Sync,

§

impl<BUS, MAG, INIT, DELAY, E> Unpin for Icm20948<BUS, MAG, INIT, DELAY, E>
where BUS: Unpin, DELAY: Unpin, MAG: Unpin, INIT: Unpin, E: Unpin,

§

impl<BUS, MAG, INIT, DELAY, E> UnwindSafe for Icm20948<BUS, MAG, INIT, DELAY, E>
where BUS: UnwindSafe, DELAY: UnwindSafe, MAG: UnwindSafe, INIT: UnwindSafe, E: UnwindSafe,

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> 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<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.