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, Error<E>> where
D: DelayMs<u8>,
[src]
pub fn imu_default<D>(
spi: SPI,
ncs: NCS,
delay: &mut D
) -> Result<Self, Error<E>> where
D: DelayMs<u8>,
Creates a new Imu
driver from a SPI peripheral and a NCS pin with
default Accel scale
, Gyro scale
, AccelDataRateConfig
,
GyroTempDataRateConfig
, 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>,
accel_data_rate_config: Option<AccelDataRateConfig>,
gyro_temp_data_rate_config: Option<GyroTempDataRateConfig>,
sample_rate_divisor: Option<u8>
) -> Result<Self, Error<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>,
accel_data_rate_config: Option<AccelDataRateConfig>,
gyro_temp_data_rate_config: Option<GyroTempDataRateConfig>,
sample_rate_divisor: Option<u8>
) -> Result<Self, Error<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
,
AccelDataRateConfig
, GyroTempDataRateConfig
, 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, Error<E>> where
D: DelayMs<u8>,
[src]
pub fn marg_default<D>(
spi: SPI,
ncs: NCS,
delay: &mut D
) -> Result<Self, Error<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
,
AccelDataRateConfig
, GyroTempDataRateConfig
,
and 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>,
accel_data_rate_config: Option<AccelDataRateConfig>,
gyro_temp_data_rate_config: Option<GyroTempDataRateConfig>,
sample_rate_divisor: Option<u8>
) -> Result<Self, Error<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>,
accel_data_rate_config: Option<AccelDataRateConfig>,
gyro_temp_data_rate_config: Option<GyroTempDataRateConfig>,
sample_rate_divisor: Option<u8>
) -> Result<Self, Error<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
, AccelDataRateConfig
, GyroTempDataRateConfig
,
and sample rate divisor.
pub fn unscaled_all(&mut self) -> Result<UnscaledMargMeasurements, E>
[src]
pub fn unscaled_all(&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<Vector3<i16>, E>
[src]
pub fn unscaled_mag(&mut self) -> Result<Vector3<i16>, E>
Reads and returns raw unscaled Magnetometer measurements (LSB).
pub fn mag(&mut self) -> Result<Vector3<f32>, E>
[src]
pub fn mag(&mut self) -> Result<Vector3<f32>, E>
Read and returns Magnetometer measurements scaled, adjusted for factory sensitivities, and converted to Teslas.
pub fn raw_mag_sensitivity_adjustments(&self) -> Vector3<u8>
[src]
pub fn raw_mag_sensitivity_adjustments(&self) -> Vector3<u8>
Returns raw mag sensitivity adjustments
pub fn mag_sensitivity_adjustments(&self) -> Vector3<f32>
[src]
pub fn mag_sensitivity_adjustments(&self) -> Vector3<f32>
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<Vector3<i16>, E>
[src]
pub fn unscaled_accel(&mut self) -> Result<Vector3<i16>, E>
Reads and returns unscaled accelerometer measurements (LSB).
pub fn accel(&mut self) -> Result<Vector3<f32>, E>
[src]
pub fn accel(&mut self) -> Result<Vector3<f32>, E>
Reads and returns accelerometer measurements scaled and converted to g.
pub fn unscaled_gyro(&mut self) -> Result<Vector3<i16>, E>
[src]
pub fn unscaled_gyro(&mut self) -> Result<Vector3<i16>, E>
Reads and returns unsacled Gyroscope measurements (LSB).
pub fn gyro(&mut self) -> Result<Vector3<f32>, E>
[src]
pub fn gyro(&mut self) -> Result<Vector3<f32>, E>
Reads and returns gyroscope measurements scaled and converted to rad/s.
pub fn accel_config(
&mut self,
accel_config: AccelDataRateConfig
) -> Result<(), E>
[src]
pub fn accel_config(
&mut self,
accel_config: AccelDataRateConfig
) -> Result<(), E>
Sets accelerometer data rate config (AccelDataRateConfig
).
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 gyro_temp_config(
&mut self,
gyro_temp_config: GyroTempDataRateConfig
) -> Result<(), E>
[src]
pub fn gyro_temp_config(
&mut self,
gyro_temp_config: GyroTempDataRateConfig
) -> Result<(), E>
Sets gyroscope and temperatures data rate config
(GyroTempDataRateConfig
).
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>
Sets 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
GyroTempDataRateConfig see GyroTempDataRateConfig
.
SampleRate = InternalSampleRate / (1 + SMPLRT_DIV).
pub fn calibrate_at_rest<D>(&mut self, delay: &mut D) -> Result<(), E> where
D: DelayMs<u8>,
[src]
pub fn calibrate_at_rest<D>(&mut self, delay: &mut D) -> Result<(), E> where
D: DelayMs<u8>,
Calculates the average of the at-rest readings of accelerometer and gyroscope and then loads the resulting offsets into accelerometer and gyro bias registers.
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.