Struct mpu9250::Mpu9250

source ·
pub struct Mpu9250<DEV, MODE> { /* private fields */ }
Expand description

MPU9250 driver

Implementations§

source§

impl<E, SPI, NCS> Mpu9250<SpiDevice<SPI, NCS>, Imu>where SPI: Write<u8, Error = E> + Transfer<u8, Error = E>, NCS: OutputPin,

source

pub fn imu_default<D>( spi: SPI, ncs: NCS, delay: &mut D ) -> Result<Self, Error<<SpiDevice<SPI, NCS> as Device>::Error>>where D: DelayMs<u8>,

Creates a new Imu driver from a SPI peripheral and a NCS pin with default configuration.

source

pub fn imu<D>( spi: SPI, ncs: NCS, delay: &mut D, config: &mut MpuConfig<Imu> ) -> Result<Self, Error<<SpiDevice<SPI, NCS> as Device>::Error>>where D: DelayMs<u8>,

Creates a new Imu driver from a SPI peripheral and a NCS pin with provided configuration Config.

source

pub fn imu_with_reinit<D, F>( spi: SPI, ncs: NCS, delay: &mut D, config: &mut MpuConfig<Imu>, reinit_fn: F ) -> Result<Self, Error<<SpiDevice<SPI, NCS> as Device>::Error>>where D: DelayMs<u8>, F: FnOnce(SPI, NCS) -> Option<(SPI, NCS)>,

Creates a new Imu driver from a SPI peripheral and a NCS pin with provided configuration Config. Reinit function can be used to re-initialize SPI bus. Usecase: change SPI speed for faster data transfer: “Communication with all registers of the device is performed using either I2C at 400kHz or SPI at 1M Hz. For applications requiring faster communications, the sensor and interrupt registers may be read using SPI at 20MHz.”

source§

impl<E, SPI, NCS> Mpu9250<SpiDevice<SPI, NCS>, Marg>where SPI: Write<u8, Error = E> + Transfer<u8, Error = E>, NCS: OutputPin,

source

pub fn marg_default<D>( spi: SPI, ncs: NCS, delay: &mut D ) -> Result<Self, Error<<SpiDevice<SPI, NCS> as Device>::Error>>where D: DelayMs<u8>,

Creates a new Marg driver from a SPI peripheral and a NCS pin with default Config.

source

pub fn marg<D>( spi: SPI, ncs: NCS, delay: &mut D, config: &mut MpuConfig<Marg> ) -> Result<Self, Error<<SpiDevice<SPI, NCS> as Device>::Error>>where D: DelayMs<u8>,

Creates a new MARG driver from a SPI peripheral and a NCS pin with provided configuration Config.

source

pub fn marg_with_reinit<D, F>( spi: SPI, ncs: NCS, delay: &mut D, config: &mut MpuConfig<Marg>, reinit_fn: F ) -> Result<Self, Error<<SpiDevice<SPI, NCS> as Device>::Error>>where D: DelayMs<u8>, F: FnOnce(SPI, NCS) -> Option<(SPI, NCS)>,

Creates a new MARG driver from a SPI peripheral and a NCS pin with provided configuration Config. Reinit function can be used to re-initialize SPI bus. Usecase: change SPI speed for faster data transfer: “Communication with all registers of the device is performed using either I2C at 400kHz or SPI at 1M Hz. For applications requiring faster communications, the sensor and interrupt registers may be read using SPI at 20MHz.”

source§

impl<E, SPI, NCS, MODE> Mpu9250<SpiDevice<SPI, NCS>, MODE>where SPI: Write<u8, Error = E> + Transfer<u8, Error = E>, NCS: OutputPin,

source

pub fn release(self) -> (SPI, NCS)

Destroys the driver recovering the SPI peripheral and the NCS pin

source§

impl<E, DEV> Mpu9250<DEV, Imu>where DEV: Device<Error = E>,

source

pub fn config(&mut self, config: &mut MpuConfig<Imu>) -> Result<(), E>

Configures device using provided MpuConfig.

source

pub fn unscaled_all<T>(&mut self) -> Result<UnscaledImuMeasurements<T>, E>where T: From<[i16; 3]>,

Reads and returns raw unscaled Accelerometer + Gyroscope + Thermometer measurements (LSB).

source

pub fn all<T>(&mut self) -> Result<ImuMeasurements<T>, E>where T: From<[f32; 3]>,

Reads and returns Accelerometer + Gyroscope + Thermometer measurements scaled and converted to respective units.

source

pub fn calibrate_at_rest<D, T>(&mut self, delay: &mut D) -> Result<T, Error<E>>where D: DelayMs<u8>, T: From<[f32; 3]>,

Calculates the average of the at-rest readings of accelerometer and gyroscope and then loads the resulting biases into gyro offset registers. Retunrs either Ok with accelerometer biases, or Err(Error), where Error::CalibrationError means soft error, and user can proceed on their own risk.

Accelerometer biases should be processed separately.

NOTE: MPU is able to store accelerometer biases, to apply them automatically, but at this moment it does not work.

source§

impl<E, DEV> Mpu9250<DEV, Marg>where DEV: Device<Error = E> + AK8963<Error = E> + NineDOFDevice,

source

pub fn calibrate_at_rest<D, T>(&mut self, delay: &mut D) -> Result<T, Error<E>>where D: DelayMs<u8>, T: From<[f32; 3]>,

Calculates the average of the at-rest readings of accelerometer and gyroscope and then loads the resulting biases into gyro offset registers. Retunrs either Ok with accelerometer biases, or Err(Error), where Error::CalibrationError means soft error, and user can proceed on their own risk.

Accelerometer biases should be processed separately.

NOTE: MPU is able to store accelerometer biases, to apply them automatically, but at this moment it does not work.

source

pub fn config(&mut self, config: &mut MpuConfig<Marg>) -> Result<(), E>

Configures device using provided MpuConfig.

source

pub fn unscaled_all<T>(&mut self) -> Result<UnscaledMargMeasurements<T>, E>where T: From<[i16; 3]>,

Reads and returns raw unscaled Accelerometer + Gyroscope + Thermometer

  • Magnetometer measurements (LSB).
source

pub fn all<T>(&mut self) -> Result<MargMeasurements<T>, E>where T: From<[f32; 3]>,

Reads and returns Accelerometer + Gyroscope + Thermometer + Magnetometer measurements scaled and converted to respective units.

source

pub fn magnetometer_healthy(&mut self) -> Result<bool, E>

Perform magnetometer self-test

Measure magnetic field generated by internal magnetic source. Note that this would leave device in power-down mode.

source

pub fn unscaled_mag<T>(&mut self) -> Result<T, E>where T: From<[i16; 3]>,

Reads and returns raw unscaled Magnetometer measurements (LSB).

source

pub fn mag<T>(&mut self) -> Result<T, E>where T: From<[f32; 3]>,

Read and returns Magnetometer measurements scaled, adjusted for factory sensitivities, and converted to microTeslas.

source

pub fn raw_mag_sensitivity_adjustments<T>(&self) -> Twhere T: From<[u8; 3]>,

Returns raw mag sensitivity adjustments

source

pub fn mag_sensitivity_adjustments<T>(&self) -> Twhere T: From<[f32; 3]>,

Returns mag sensitivity adjustments

source

pub fn mag_scale(&mut self, scale: MagScale) -> Result<(), E>

Configures magnetrometer full reading scale (MagScale)

source

pub fn ak8963_who_am_i(&mut self) -> Result<u8, E>

Reads the AK8963 (magnetometer) WHO_AM_I register; should return 0x48

source§

impl<E, DEV, MODE> Mpu9250<DEV, MODE>where DEV: Device<Error = E>,

source

pub fn get_enabled_interrupts(&mut self) -> Result<InterruptEnable, E>

Get enabled interrupts

source

pub fn get_interrupt_status(&mut self) -> Result<InterruptEnable, E>

Get interrupt status

source

pub fn enable_interrupts(&mut self, ie: InterruptEnable) -> Result<(), E>

Enable specific interrupts

source

pub fn disable_interrupts(&mut self, ie: InterruptEnable) -> Result<(), E>

Disable specific interrupts

source

pub fn get_interrupt_config(&mut self) -> Result<InterruptConfig, E>

Get interrupt configurtion

source

pub fn interrupt_config(&mut self, ic: InterruptConfig) -> Result<(), E>

Overwrites current interrupt configuration

source

pub fn reset_fifo<D>(&mut self, delay: &mut D) -> Result<(), Error<E>>where D: DelayMs<u8>,

Reset the internal FIFO

source

pub fn read_fifo(&mut self, data: &mut [u8]) -> Result<isize, Error<E>>

Read internal FIFO into data. The first byte must be discarded. Return the number of byte left in the FIFO.

  • If the number is positive, bytes are left in the FIFO
  • If the number is negative, only data.len() - 1 - size bytes were avilable and were not read
  • If the number is 0, the FIFO is empty and data has been filled fully
source

pub fn unscaled_accel<T>(&mut self) -> Result<T, E>where T: From<[i16; 3]>,

Reads and returns unscaled accelerometer measurements (LSB).

source

pub fn accel<T>(&mut self) -> Result<T, E>where T: From<[f32; 3]>,

Reads and returns accelerometer measurements scaled and converted to g.

source

pub fn unscaled_gyro<T>(&mut self) -> Result<T, E>where T: From<[i16; 3]>,

Reads and returns unsacled Gyroscope measurements (LSB).

source

pub fn gyro<T>(&mut self) -> Result<T, E>where T: From<[f32; 3]>,

Reads and returns gyroscope measurements scaled and converted to rad/s.

source

pub fn accel_data_rate( &mut self, accel_data_rate: AccelDataRate ) -> Result<(), E>

Configures accelerometer data rate config (AccelDataRate).

source

pub fn accel_scale(&mut self, scale: AccelScale) -> Result<(), E>

Configures accelerometer full reading scale (Accel scale).

source

pub fn gyro_temp_data_rate( &mut self, data_rate: GyroTempDataRate ) -> Result<(), E>

Configures gyroscope and temperatures data rate config (GyroTempDataRate).

source

pub fn gyro_scale(&mut self, scale: GyroScale) -> Result<(), E>

Configures gyroscope full reading scale (Gyro scale).

source

pub fn raw_temp(&mut self) -> Result<i16, E>

Reads and returns raw unscaled temperature sensor measurements (LSB).

source

pub fn temp(&mut self) -> Result<f32, E>

Reads and returns adjusted temperature measurements converted to C.

source

pub fn sample_rate_divisor(&mut self, smplrt_div: u8) -> Result<(), E>

Configures sample rate divisor. Sample rate divisor divides the internal sample rate to generate the sample rate that controls sensor data output rate, FIFO sample rate. NOTE: This register is only effective when dlpf mode used for GyroTempDataRate see GyroTempDataRate. SampleRate = InternalSampleRate / (1 + SMPLRT_DIV).

source

pub fn get_gyro_bias<T>(&mut self) -> Result<T, Error<E>>where T: From<[f32; 3]>,

Get scaled gyroscope biases.

source

pub fn set_gyro_bias<T>( &mut self, relative: bool, biases: T ) -> Result<(), Error<E>>where T: Into<[f32; 3]>,

Set scaled gyro biases. In relative mode it will add the new biases to the existing ones instead of replacing them.

source

pub fn get_accel_bias<T>(&mut self) -> Result<T, Error<E>>where T: From<[f32; 3]>,

Get scaled accelerometer biases.

source

pub fn set_accel_bias<T>( &mut self, relative: bool, biases: T ) -> Result<(), Error<E>>where T: Into<[f32; 3]>,

Set scaled accelerometer biases. Keep in mind that the registers contain factory-supplied values after reset. In relative mode it will add the new biases to the existing ones instead of replacing them.

source

pub fn who_am_i(&mut self) -> Result<u8, E>

Reads the WHO_AM_I register; should return 0x71

source§

impl<DEV, MODE> Mpu9250<DEV, MODE>

source

pub fn accel_resolution(&self) -> f32

Returns Accelerometer resolution.

source

pub fn gyro_resolution(&self) -> f32

Returns Gyroscope resolution.

source

pub fn mag_resolution(&self) -> f32

Returns Magnetometer resolution.

Auto Trait Implementations§

§

impl<DEV, MODE> RefUnwindSafe for Mpu9250<DEV, MODE>where DEV: RefUnwindSafe, MODE: RefUnwindSafe,

§

impl<DEV, MODE> Send for Mpu9250<DEV, MODE>where DEV: Send, MODE: Send,

§

impl<DEV, MODE> Sync for Mpu9250<DEV, MODE>where DEV: Sync, MODE: Sync,

§

impl<DEV, MODE> Unpin for Mpu9250<DEV, MODE>where DEV: Unpin, MODE: Unpin,

§

impl<DEV, MODE> UnwindSafe for Mpu9250<DEV, MODE>where DEV: UnwindSafe, MODE: UnwindSafe,

Blanket Implementations§

source§

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

source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
source§

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

source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
source§

impl<T> BorrowMut<T> for Twhere 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 Twhere 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, U> TryFrom<U> for Twhere U: Into<T>,

§

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 Twhere U: TryFrom<T>,

§

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.