[][src]Struct mpu9250::Mpu9250

pub struct Mpu9250<SPI, NCS, MODE> { /* fields omitted */ }

MPU9250 driver

Methods

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

pub fn imu_default<D>(
    spi: SPI,
    ncs: NCS,
    delay: &mut D
) -> Result<Self, Error<E>> where
    D: DelayMs<u8>, 
[src]

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

pub fn imu<D>(
    spi: SPI,
    ncs: NCS,
    delay: &mut D,
    config: &mut MpuConfig<Imu>
) -> Result<Self, Error<E>> where
    D: DelayMs<u8>, 
[src]

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

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

Configures device using provided MpuConfig.

pub fn unscaled_all(&mut self) -> Result<UnscaledImuMeasurements, E>[src]

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

pub fn all(&mut self) -> Result<ImuMeasurements, E>[src]

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

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

pub fn marg_default<D>(
    spi: SPI,
    ncs: NCS,
    delay: &mut D
) -> Result<Self, Error<E>> where
    D: DelayMs<u8>, 
[src]

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

pub fn marg<D>(
    spi: SPI,
    ncs: NCS,
    delay: &mut D,
    config: &mut MpuConfig<Marg>
) -> Result<Self, Error<E>> where
    D: DelayMs<u8>, 
[src]

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

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

Configures device using provided MpuConfig.

pub fn unscaled_all(&mut self) -> Result<UnscaledMargMeasurements, E>[src]

Reads and returns raw unscaled Accelerometer + Gyroscope + Thermometer

  • Magnetometer measurements (LSB).

pub fn all(&mut self) -> Result<MargMeasurements, E>[src]

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

pub fn unscaled_mag(&mut self) -> Result<Vector3<i16>, E>[src]

Reads and returns raw unscaled Magnetometer measurements (LSB).

pub fn mag(&mut self) -> Result<Vector3<f32>, E>[src]

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

pub fn raw_mag_sensitivity_adjustments(&self) -> Vector3<u8>[src]

Returns raw mag sensitivity adjustments

pub fn mag_sensitivity_adjustments(&self) -> Vector3<f32>[src]

Returns mag sensitivity adjustments

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

Configures magnetrometer full reading scale (MagScale)

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

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

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

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

Get enabled interrupts

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

Enable specific interrupts

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

Disable specific interrupts

pub fn unscaled_accel(&mut self) -> Result<Vector3<i16>, E>[src]

Reads and returns unscaled accelerometer measurements (LSB).

pub fn accel(&mut self) -> Result<Vector3<f32>, E>[src]

Reads and returns accelerometer measurements scaled and converted to g.

pub fn unscaled_gyro(&mut self) -> Result<Vector3<i16>, E>[src]

Reads and returns unsacled Gyroscope measurements (LSB).

pub fn gyro(&mut self) -> Result<Vector3<f32>, E>[src]

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

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

Configures accelerometer data rate config (AccelDataRate).

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

Configures accelerometer full reading scale (Accel scale).

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

Configures gyroscope and temperatures data rate config (GyroTempDataRate).

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

Configures gyroscope full reading scale (Gyro scale).

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

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

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

Reads and returns adjusted temperature measurements converted to C.

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

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

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

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. NOTE: MPU has register to store accelerometer biases, but there are some complications, so setting them doesn't work.

pub fn release(self) -> (SPI, NCS)[src]

Destroys the driver recovering the SPI peripheral and the NCS pin

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

Reads the WHO_AM_I register; should return 0x71

impl<SPI, NCS, MODE> Mpu9250<SPI, NCS, MODE>[src]

pub fn accel_resolution(&self) -> f32[src]

Returns Accelerometer resolution.

pub fn gyro_resolution(&self) -> f32[src]

Returns Gyroscope resolution.

pub fn mag_resolution(&self) -> f32[src]

Returns Magnetometer resolution.

Auto Trait Implementations

impl<SPI, NCS, MODE> Send for Mpu9250<SPI, NCS, MODE> where
    MODE: Send,
    NCS: Send,
    SPI: Send

impl<SPI, NCS, MODE> Sync for Mpu9250<SPI, NCS, MODE> where
    MODE: Sync,
    NCS: Sync,
    SPI: Sync

Blanket Implementations

impl<T> From for T[src]

impl<T, U> TryFrom for T where
    U: Into<T>, 
[src]

type Error = !

🔬 This is a nightly-only experimental API. (try_from)

The type returned in the event of a conversion error.

impl<T, U> TryInto for T where
    U: TryFrom<T>, 
[src]

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

🔬 This is a nightly-only experimental API. (try_from)

The type returned in the event of a conversion error.

impl<T, U> Into for T where
    U: From<T>, 
[src]

impl<T> Borrow for T where
    T: ?Sized
[src]

impl<T> BorrowMut for T where
    T: ?Sized
[src]

impl<T> Any for T where
    T: 'static + ?Sized
[src]

impl<T> Same for T

type Output = T

Should always be Self

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