Struct mpu9250::Mpu9250 [−][src]
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]
impl<E, SPI, NCS> Mpu9250<SPI, NCS, Imu> where
SPI: Write<u8, Error = E> + Transfer<u8, Error = E>,
NCS: OutputPin,
pub fn imu_default<D>(spi: SPI, ncs: NCS, delay: &mut D) -> Result<Self, E> where
D: DelayMs<u8>,
[src]
pub fn imu_default<D>(spi: SPI, ncs: NCS, delay: &mut D) -> Result<Self, E> where
D: DelayMs<u8>,
Creates a new Imu
driver from a SPI peripheral and a NCS pin with
default Accel scale
, Gyro scale
, DLPF
, and
with no sample rate divisor.
pub fn imu<D>(
spi: SPI,
ncs: NCS,
delay: &mut D,
gyro_scale: Option<GyroScale>,
accel_scale: Option<AccelScale>,
digital_low_pass_filter_mode: Option<Dlpf>,
sample_rate_divisor: Option<u8>
) -> Result<Self, E> where
D: DelayMs<u8>,
[src]
pub fn imu<D>(
spi: SPI,
ncs: NCS,
delay: &mut D,
gyro_scale: Option<GyroScale>,
accel_scale: Option<AccelScale>,
digital_low_pass_filter_mode: Option<Dlpf>,
sample_rate_divisor: Option<u8>
) -> Result<Self, E> where
D: DelayMs<u8>,
Creates a new Imu driver from a SPI peripheral and a NCS pin with
optionally configured Accel scale
, Gyro scale
,
DLPF
, and sample rate divisor.
pub fn unscaled_all(&mut self) -> Result<UnscaledImuMeasurements, E>
[src]
pub fn unscaled_all(&mut self) -> Result<UnscaledImuMeasurements, E>
Reads and returns raw unscaled Accelerometer + Gyroscope + Thermometer measurements (LSB).
pub fn all(&mut self) -> Result<ImuMeasurements, E>
[src]
pub fn all(&mut self) -> Result<ImuMeasurements, E>
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]
impl<E, SPI, NCS> Mpu9250<SPI, NCS, Marg> where
SPI: Write<u8, Error = E> + Transfer<u8, Error = E>,
NCS: OutputPin,
pub fn marg_default<D>(spi: SPI, ncs: NCS, delay: &mut D) -> Result<Self, E> where
D: DelayMs<u8>,
[src]
pub fn marg_default<D>(spi: SPI, ncs: NCS, delay: &mut D) -> Result<Self, E> where
D: DelayMs<u8>,
Creates a new Marg
driver from a SPI peripheral and a NCS pin with
default Accel scale
, Gyro scale
, Mag scale
, DLPF
, and
with no sample rate divisor.
pub fn marg<D>(
spi: SPI,
ncs: NCS,
delay: &mut D,
gyro_scale: Option<GyroScale>,
accel_scale: Option<AccelScale>,
mag_scale: Option<MagScale>,
dlpf: Option<Dlpf>,
smplrt_div: Option<u8>
) -> Result<Self, E> where
D: DelayMs<u8>,
[src]
pub fn marg<D>(
spi: SPI,
ncs: NCS,
delay: &mut D,
gyro_scale: Option<GyroScale>,
accel_scale: Option<AccelScale>,
mag_scale: Option<MagScale>,
dlpf: Option<Dlpf>,
smplrt_div: Option<u8>
) -> Result<Self, E> where
D: DelayMs<u8>,
Creates a new MARG driver from a SPI peripheral and a NCS pin with
optionally configured Accel scale
, Gyro scale
,
Mag scale
, DLPF
, and sample rate divisor.
pub fn all_unscaled(&mut self) -> Result<UnscaledMargMeasurements, E>
[src]
pub fn all_unscaled(&mut self) -> Result<UnscaledMargMeasurements, E>
Reads and returns raw unscaled Accelerometer + Gyroscope + Thermometer
- Magnetometer measurements (LSB).
pub fn all(&mut self) -> Result<MargMeasurements, E>
[src]
pub fn all(&mut self) -> Result<MargMeasurements, E>
Reads and returns Accelerometer + Gyroscope + Thermometer + Magnetometer measurements scaled and converted to respective units.
pub fn unscaled_mag(&mut self) -> Result<I16x3, E>
[src]
pub fn unscaled_mag(&mut self) -> Result<I16x3, E>
Reads and returns raw unscaled Magnetometer measurements (LSB).
pub fn mag(&mut self) -> Result<F32x3, E>
[src]
pub fn mag(&mut self) -> Result<F32x3, E>
Read and returns Magnetometer measurements scaled, adjusted for factory sensitivities, and converted to Teslas.
pub fn raw_mag_sensitivity_adjustments(&self) -> [u8; 3]
[src]
pub fn raw_mag_sensitivity_adjustments(&self) -> [u8; 3]
Returns raw mag sensitivity adjustments
pub fn mag_sensitivity_adjustments(&self) -> F32x3
[src]
pub fn mag_sensitivity_adjustments(&self) -> F32x3
Returns mag sensitivity adjustments
pub fn mag_scale(&mut self, scale: MagScale) -> Result<(), E>
[src]
pub fn mag_scale(&mut self, scale: MagScale) -> Result<(), E>
Sets magnetrometer full reading scale (MagScale
)
pub fn ak8963_who_am_i(&mut self) -> Result<u8, E>
[src]
pub fn ak8963_who_am_i(&mut self) -> Result<u8, E>
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]
impl<E, SPI, NCS, MODE> Mpu9250<SPI, NCS, MODE> where
SPI: Write<u8, Error = E> + Transfer<u8, Error = E>,
NCS: OutputPin,
pub fn unscaled_accel(&mut self) -> Result<I16x3, E>
[src]
pub fn unscaled_accel(&mut self) -> Result<I16x3, E>
Reads and returns unscaled accelerometer measurements (LSB).
pub fn accel(&mut self) -> Result<F32x3, E>
[src]
pub fn accel(&mut self) -> Result<F32x3, E>
Reads and returns accelerometer measurements scaled and converted to g.
pub fn accel_filter(&mut self, dlpf: Dlpf) -> Result<(), E>
[src]
pub fn accel_filter(&mut self, dlpf: Dlpf) -> Result<(), E>
Applies a digital low pass filter to the accelerometer data (Dlpf
).
pub fn accel_scale(&mut self, scale: AccelScale) -> Result<(), E>
[src]
pub fn accel_scale(&mut self, scale: AccelScale) -> Result<(), E>
Sets accelerometer full reading scale (Accel scale
).
pub fn unscaled_gyro(&mut self) -> Result<I16x3, E>
[src]
pub fn unscaled_gyro(&mut self) -> Result<I16x3, E>
Reads and returns unsacled Gyroscope measurements (LSB).
pub fn gyro(&mut self) -> Result<F32x3, E>
[src]
pub fn gyro(&mut self) -> Result<F32x3, E>
Reads and returns gyroscope measurements scaled and converted to rad/s.
pub fn gyro_filter(&mut self, dlpf: Dlpf) -> Result<(), E>
[src]
pub fn gyro_filter(&mut self, dlpf: Dlpf) -> Result<(), E>
Applies a digital low pass filter to the gyroscope data (Dlpf
).
pub fn gyro_scale(&mut self, scale: GyroScale) -> Result<(), E>
[src]
pub fn gyro_scale(&mut self, scale: GyroScale) -> Result<(), E>
Sets gyroscope full reading scale (Gyro scale
).
pub fn raw_temp(&mut self) -> Result<i16, E>
[src]
pub fn raw_temp(&mut self) -> Result<i16, E>
Reads and returns raw unscaled temperature sensor measurements (LSB).
pub fn temp(&mut self) -> Result<f32, E>
[src]
pub fn temp(&mut self) -> Result<f32, E>
Reads and returns adjusted temperature measurements converted to C.
pub fn sample_rate_divisor(&mut self, smplrt_div: u8) -> Result<(), E>
[src]
pub fn sample_rate_divisor(&mut self, smplrt_div: u8) -> Result<(), E>
Clears Fchoice bits and sets rate divisor (SMPLRT_DIV).
pub fn release(self) -> (SPI, NCS)
[src]
pub fn release(self) -> (SPI, NCS)
Destroys the driver recovering the SPI peripheral and the NCS pin
pub fn who_am_i(&mut self) -> Result<u8, E>
[src]
pub fn who_am_i(&mut self) -> Result<u8, E>
Reads the WHO_AM_I register; should return 0x71
impl<SPI, NCS, MODE> Mpu9250<SPI, NCS, MODE>
[src]
impl<SPI, NCS, MODE> Mpu9250<SPI, NCS, MODE>
pub fn accel_resolution(&self) -> f32
[src]
pub fn accel_resolution(&self) -> f32
Returns Accelerometer resolution.
pub fn gyro_resolution(&self) -> f32
[src]
pub fn gyro_resolution(&self) -> f32
Returns Gyroscope resolution.
pub fn mag_resolution(&self) -> f32
[src]
pub fn mag_resolution(&self) -> f32
Returns Magnetometer resolution.