[−][src]Struct mpu9250_i2c::Mpu9250
The MPU9250, this is where all the work is done.
Implementations
impl<I, D, E> Mpu9250<I, D> where
I: Read<Error = E> + Write<Error = E> + WriteRead<Error = E>,
D: DelayMs<u8>,
[src]
I: Read<Error = E> + Write<Error = E> + WriteRead<Error = E>,
D: DelayMs<u8>,
pub fn new(dev: I, delay: D, cal: Calibration) -> Result<Self, E>
[src]
Creates a new driver for the MPU 9250.
pub fn init(&mut self) -> Result<(), E>
[src]
Initialise the device with by performing the following
- a soft reset
- setting the clock source
- setting the Accelerometer and Gyroscope Full Scale ranges
- Enabling the magenetometer
pub fn wait(&mut self, ms: u8)
[src]
Wait for the given amount of time in milliseconds.
pub fn get_accel_gyro_rate_ms(&mut self) -> u64
[src]
Get the update rate in milliseconds
pub fn set_clock_source(&mut self, src: u8) -> Result<(), E>
[src]
Set the clock source
pub fn get_clock_source(&mut self) -> Result<u8, E>
[src]
Get the clock source
pub fn set_full_scale_gyro_range(
&mut self,
scale_factor: GyroConfig
) -> Result<(), E>
[src]
&mut self,
scale_factor: GyroConfig
) -> Result<(), E>
Set the Full Scale range and calculate the scale factor
pub fn get_full_scale_gyro_range(&mut self) -> Result<u8, E>
[src]
Read the Full Scale range for the gyro from the device
pub fn set_full_scale_accel_range(
&mut self,
scale_factor: AccelConfig
) -> Result<(), E>
[src]
&mut self,
scale_factor: AccelConfig
) -> Result<(), E>
Set the Full Scale range and calculate the scale factor
pub fn get_full_scale_accel_range(&mut self) -> Result<u8, E>
[src]
Read the Full Scale range for the accelerometer from the device
pub fn set_sleep_enabled(&mut self) -> Result<(), E>
[src]
Set the sleep enabled byte, read MPU9250 hardware docs for more details
pub fn get_sleep_enabled(&mut self) -> Result<bool, E>
[src]
Get the sleep enabled byte.
pub fn set_i2c_master_mode(&mut self) -> Result<(), E>
[src]
Put the device into i2c master mode.
pub fn get_i2c_master_mode(&mut self) -> Result<bool, E>
[src]
Returns true
if the device is in i2c master mode
pub fn get_gyro_power_settings(&mut self) -> Result<Vector<bool>, E>
[src]
Get the power management settings for the gyroscope
pub fn get_accel_power_settings(&mut self) -> Result<Vector<bool>, E>
[src]
Get the power management settings for the accelerometer
pub fn get_accel(&mut self) -> Result<Vector<f32>, E>
[src]
Get the accelerometer data.
Returns a vector and the units are in g.
pub fn get_gyro(&mut self) -> Result<Vector<f32>, E>
[src]
Get the gyroscope data.
Returns a vector and the units are in degrees / second.
pub fn get_accel_gyro(&mut self) -> Result<(Vector<f32>, Vector<f32>), E>
[src]
Get the accelerometer and gyroscope data. This is more efficient than reading the accelerometer and gyroscope individually.
The results are written into the two vectors proviced va
and vg
.
pub fn get_temperature_raw(&mut self) -> Result<i16, E>
[src]
Get the raw temperature data
pub fn get_temperature_celsius(&mut self) -> Result<f32, E>
[src]
Get the temperature in degrees Celcius
pub fn get_device_id(&mut self) -> Result<u8, E>
[src]
Get the device id
pub fn set_bypass_enabled(&mut self, state: bool) -> Result<(), E>
[src]
enable bypass, read the MPU9250 docs.
pub fn get_bypass_enabled(&mut self) -> Result<bool, E>
[src]
Check if bypass is enabled
pub fn enable_magnetometer(&mut self) -> Result<bool, E>
[src]
Enable the magnetometer. This will set the bypass, then run ak8963_init()
.
pub fn ak8963_init(&mut self) -> Result<(), E>
[src]
Initialise the magnetometer
pub fn ak8963_get_device_id(&mut self) -> Result<u8, E>
[src]
Get the magnetomter device Id
pub fn ak8963_update_sensitivity_adjustment_values(&mut self) -> Result<(), E>
[src]
Get and update the magnetometer sensitivity adjustment values
pub fn get_mag(&mut self) -> Result<Vector<f32>, E>
[src]
Get the magnetometer data. Returns values in degrees per second.
Note, this will align the orientation of the magnetometer's reference frame to the same as the accelerometer and gyroscope. Read the "Orientation of Axes" section of the Mpu9250 vendor documentation.
pub fn ak8963_get_mag_raw(&mut self, bytes: &mut [u8]) -> Result<(), E>
[src]
Get the raw magnetometer data This function has an intentional delay of 1 millisecond.
pub fn ak8963_get_cntl(&mut self) -> Result<Ctnl1, E>
[src]
Get the magnetometer control details
pub fn ak8963_set_cntl(&mut self, mode: Ctnl1) -> Result<(), E>
[src]
Set the magnetometer control details
pub fn get_calibration(&mut self) -> Calibration
[src]
Set the currently used calibration values
pub fn ak8963_get_asa(&mut self) -> Vector<f32>
[src]
Get the sensitivity adjustment values
pub fn get_accel_inv_scale(&mut self) -> f32
[src]
Get the accelometer scale factor
pub fn get_gyro_inv_scale(&mut self) -> f32
[src]
Get the gyrscope scale factor
Auto Trait Implementations
impl<I, D> RefUnwindSafe for Mpu9250<I, D> where
D: RefUnwindSafe,
I: RefUnwindSafe,
D: RefUnwindSafe,
I: RefUnwindSafe,
impl<I, D> Send for Mpu9250<I, D> where
D: Send,
I: Send,
D: Send,
I: Send,
impl<I, D> Sync for Mpu9250<I, D> where
D: Sync,
I: Sync,
D: Sync,
I: Sync,
impl<I, D> Unpin for Mpu9250<I, D> where
D: Unpin,
I: Unpin,
D: Unpin,
I: Unpin,
impl<I, D> UnwindSafe for Mpu9250<I, D> where
D: UnwindSafe,
I: UnwindSafe,
D: UnwindSafe,
I: UnwindSafe,
Blanket Implementations
impl<T> Any for T where
T: 'static + ?Sized,
[src]
T: 'static + ?Sized,
impl<T> Borrow<T> for T where
T: ?Sized,
[src]
T: ?Sized,
impl<T> BorrowMut<T> for T where
T: ?Sized,
[src]
T: ?Sized,
fn borrow_mut(&mut self) -> &mut T
[src]
impl<T> From<T> for T
[src]
impl<T, U> Into<U> for T where
U: From<T>,
[src]
U: From<T>,
impl<T, U> TryFrom<U> for T where
U: Into<T>,
[src]
U: Into<T>,
type Error = Infallible
The type returned in the event of a conversion error.
fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>
[src]
impl<T, U> TryInto<U> for T where
U: TryFrom<T>,
[src]
U: TryFrom<T>,