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,
impl<E, SPI, NCS> Mpu9250<SpiDevice<SPI, NCS>, Imu>where SPI: Write<u8, Error = E> + Transfer<u8, Error = E>, NCS: OutputPin,
sourcepub fn imu_default<D>(
spi: SPI,
ncs: NCS,
delay: &mut D
) -> Result<Self, Error<<SpiDevice<SPI, NCS> as Device>::Error>>where
D: DelayMs<u8>,
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.
sourcepub 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>,
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
.
sourcepub 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)>,
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,
impl<E, SPI, NCS> Mpu9250<SpiDevice<SPI, NCS>, Marg>where SPI: Write<u8, Error = E> + Transfer<u8, Error = E>, NCS: OutputPin,
sourcepub fn marg_default<D>(
spi: SPI,
ncs: NCS,
delay: &mut D
) -> Result<Self, Error<<SpiDevice<SPI, NCS> as Device>::Error>>where
D: DelayMs<u8>,
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>,
sourcepub 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>,
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
.
sourcepub 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)>,
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,
impl<E, SPI, NCS, MODE> Mpu9250<SpiDevice<SPI, NCS>, MODE>where SPI: Write<u8, Error = E> + Transfer<u8, Error = E>, NCS: OutputPin,
sourcepub fn release(self) -> (SPI, NCS)
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>,
impl<E, DEV> Mpu9250<DEV, Imu>where DEV: Device<Error = E>,
sourcepub fn config(&mut self, config: &mut MpuConfig<Imu>) -> Result<(), E>
pub fn config(&mut self, config: &mut MpuConfig<Imu>) -> Result<(), E>
Configures device using provided MpuConfig
.
sourcepub fn unscaled_all<T>(&mut self) -> Result<UnscaledImuMeasurements<T>, E>where
T: From<[i16; 3]>,
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).
sourcepub fn all<T>(&mut self) -> Result<ImuMeasurements<T>, E>where
T: From<[f32; 3]>,
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.
sourcepub fn calibrate_at_rest<D, T>(&mut self, delay: &mut D) -> Result<T, Error<E>>where
D: DelayMs<u8>,
T: From<[f32; 3]>,
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,
impl<E, DEV> Mpu9250<DEV, Marg>where DEV: Device<Error = E> + AK8963<Error = E> + NineDOFDevice,
sourcepub fn calibrate_at_rest<D, T>(&mut self, delay: &mut D) -> Result<T, Error<E>>where
D: DelayMs<u8>,
T: From<[f32; 3]>,
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.
sourcepub fn config(&mut self, config: &mut MpuConfig<Marg>) -> Result<(), E>
pub fn config(&mut self, config: &mut MpuConfig<Marg>) -> Result<(), E>
Configures device using provided MpuConfig
.
sourcepub fn unscaled_all<T>(&mut self) -> Result<UnscaledMargMeasurements<T>, E>where
T: From<[i16; 3]>,
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).
sourcepub fn all<T>(&mut self) -> Result<MargMeasurements<T>, E>where
T: From<[f32; 3]>,
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.
sourcepub fn magnetometer_healthy(&mut self) -> Result<bool, E>
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.
sourcepub fn unscaled_mag<T>(&mut self) -> Result<T, E>where
T: From<[i16; 3]>,
pub fn unscaled_mag<T>(&mut self) -> Result<T, E>where T: From<[i16; 3]>,
Reads and returns raw unscaled Magnetometer measurements (LSB).
sourcepub fn mag<T>(&mut self) -> Result<T, E>where
T: From<[f32; 3]>,
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.
sourcepub fn raw_mag_sensitivity_adjustments<T>(&self) -> Twhere
T: From<[u8; 3]>,
pub fn raw_mag_sensitivity_adjustments<T>(&self) -> Twhere T: From<[u8; 3]>,
Returns raw mag sensitivity adjustments
sourcepub fn mag_sensitivity_adjustments<T>(&self) -> Twhere
T: From<[f32; 3]>,
pub fn mag_sensitivity_adjustments<T>(&self) -> Twhere T: From<[f32; 3]>,
Returns mag sensitivity adjustments
sourcepub fn mag_scale(&mut self, scale: MagScale) -> Result<(), E>
pub fn mag_scale(&mut self, scale: MagScale) -> Result<(), E>
Configures magnetrometer full reading scale (MagScale
)
sourcepub fn ak8963_who_am_i(&mut self) -> Result<u8, E>
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>,
impl<E, DEV, MODE> Mpu9250<DEV, MODE>where DEV: Device<Error = E>,
sourcepub fn get_enabled_interrupts(&mut self) -> Result<InterruptEnable, E>
pub fn get_enabled_interrupts(&mut self) -> Result<InterruptEnable, E>
Get enabled interrupts
sourcepub fn get_interrupt_status(&mut self) -> Result<InterruptEnable, E>
pub fn get_interrupt_status(&mut self) -> Result<InterruptEnable, E>
Get interrupt status
sourcepub fn enable_interrupts(&mut self, ie: InterruptEnable) -> Result<(), E>
pub fn enable_interrupts(&mut self, ie: InterruptEnable) -> Result<(), E>
Enable specific interrupts
sourcepub fn disable_interrupts(&mut self, ie: InterruptEnable) -> Result<(), E>
pub fn disable_interrupts(&mut self, ie: InterruptEnable) -> Result<(), E>
Disable specific interrupts
sourcepub fn get_interrupt_config(&mut self) -> Result<InterruptConfig, E>
pub fn get_interrupt_config(&mut self) -> Result<InterruptConfig, E>
Get interrupt configurtion
sourcepub fn interrupt_config(&mut self, ic: InterruptConfig) -> Result<(), E>
pub fn interrupt_config(&mut self, ic: InterruptConfig) -> Result<(), E>
Overwrites current interrupt configuration
sourcepub fn reset_fifo<D>(&mut self, delay: &mut D) -> Result<(), Error<E>>where
D: DelayMs<u8>,
pub fn reset_fifo<D>(&mut self, delay: &mut D) -> Result<(), Error<E>>where D: DelayMs<u8>,
Reset the internal FIFO
sourcepub fn read_fifo(&mut self, data: &mut [u8]) -> Result<isize, Error<E>>
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
sourcepub fn unscaled_accel<T>(&mut self) -> Result<T, E>where
T: From<[i16; 3]>,
pub fn unscaled_accel<T>(&mut self) -> Result<T, E>where T: From<[i16; 3]>,
Reads and returns unscaled accelerometer measurements (LSB).
sourcepub fn accel<T>(&mut self) -> Result<T, E>where
T: From<[f32; 3]>,
pub fn accel<T>(&mut self) -> Result<T, E>where T: From<[f32; 3]>,
Reads and returns accelerometer measurements scaled and converted to g.
sourcepub fn unscaled_gyro<T>(&mut self) -> Result<T, E>where
T: From<[i16; 3]>,
pub fn unscaled_gyro<T>(&mut self) -> Result<T, E>where T: From<[i16; 3]>,
Reads and returns unsacled Gyroscope measurements (LSB).
sourcepub fn gyro<T>(&mut self) -> Result<T, E>where
T: From<[f32; 3]>,
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.
sourcepub fn accel_data_rate(
&mut self,
accel_data_rate: AccelDataRate
) -> Result<(), E>
pub fn accel_data_rate( &mut self, accel_data_rate: AccelDataRate ) -> Result<(), E>
Configures accelerometer data rate config (AccelDataRate
).
sourcepub fn accel_scale(&mut self, scale: AccelScale) -> Result<(), E>
pub fn accel_scale(&mut self, scale: AccelScale) -> Result<(), E>
Configures accelerometer full reading scale (Accel scale
).
sourcepub fn gyro_temp_data_rate(
&mut self,
data_rate: GyroTempDataRate
) -> Result<(), E>
pub fn gyro_temp_data_rate( &mut self, data_rate: GyroTempDataRate ) -> Result<(), E>
Configures gyroscope and temperatures data rate config
(GyroTempDataRate
).
sourcepub fn gyro_scale(&mut self, scale: GyroScale) -> Result<(), E>
pub fn gyro_scale(&mut self, scale: GyroScale) -> Result<(), E>
Configures gyroscope full reading scale (Gyro scale
).
sourcepub fn raw_temp(&mut self) -> Result<i16, E>
pub fn raw_temp(&mut self) -> Result<i16, E>
Reads and returns raw unscaled temperature sensor measurements (LSB).
sourcepub fn temp(&mut self) -> Result<f32, E>
pub fn temp(&mut self) -> Result<f32, E>
Reads and returns adjusted temperature measurements converted to C.
sourcepub fn sample_rate_divisor(&mut self, smplrt_div: u8) -> Result<(), E>
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).
sourcepub fn get_gyro_bias<T>(&mut self) -> Result<T, Error<E>>where
T: From<[f32; 3]>,
pub fn get_gyro_bias<T>(&mut self) -> Result<T, Error<E>>where T: From<[f32; 3]>,
Get scaled gyroscope biases.
sourcepub fn set_gyro_bias<T>(
&mut self,
relative: bool,
biases: T
) -> Result<(), Error<E>>where
T: Into<[f32; 3]>,
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.
sourcepub fn get_accel_bias<T>(&mut self) -> Result<T, Error<E>>where
T: From<[f32; 3]>,
pub fn get_accel_bias<T>(&mut self) -> Result<T, Error<E>>where T: From<[f32; 3]>,
Get scaled accelerometer biases.
sourcepub fn set_accel_bias<T>(
&mut self,
relative: bool,
biases: T
) -> Result<(), Error<E>>where
T: Into<[f32; 3]>,
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§impl<DEV, MODE> Mpu9250<DEV, MODE>
impl<DEV, MODE> Mpu9250<DEV, MODE>
sourcepub fn accel_resolution(&self) -> f32
pub fn accel_resolution(&self) -> f32
Returns Accelerometer resolution.
sourcepub fn gyro_resolution(&self) -> f32
pub fn gyro_resolution(&self) -> f32
Returns Gyroscope resolution.
sourcepub fn mag_resolution(&self) -> f32
pub fn mag_resolution(&self) -> f32
Returns Magnetometer resolution.