1#![deny(missing_docs)]
53#![no_std]
54
55#[macro_use]
56extern crate bitflags;
57extern crate embedded_hal as hal;
58
59mod ak8963;
60mod conf;
61mod device;
62mod types;
63
64#[cfg(feature = "dmp")]
65mod dmp_firmware;
66
67#[cfg(feature = "dmp")]
68pub use dmp_firmware::DMP_FIRMWARE;
69
70use ak8963::AK8963;
71
72use core::marker::PhantomData;
73
74use hal::blocking::delay::DelayMs;
75use hal::spi::{Mode, Phase, Polarity};
76
77pub use conf::*;
78pub use types::*;
79
80#[doc(hidden)]
81pub use device::Releasable;
82pub use device::{
83 Device, I2CError, I2cDevice, NineDOFDevice, SpiDevice, SpiError
84};
85
86pub enum MpuXDevice {
88 MPU9250 = 0x71,
90 MPU9255 = 0x73,
92 MPU6500 = 0x70,
94}
95
96impl MpuXDevice {
97 fn imu_supported(b: u8) -> bool {
98 b == (MpuXDevice::MPU9250 as u8)
99 || b == (MpuXDevice::MPU9255 as u8)
100 || b == (MpuXDevice::MPU6500 as u8)
101 }
102
103 fn marg_supported(b: u8) -> bool {
104 b == (MpuXDevice::MPU9250 as u8) || b == (MpuXDevice::MPU9255 as u8)
105 }
106}
107
108pub struct Mpu9250<DEV, MODE> {
110 dev: DEV,
112 mag_sensitivity_adjustments: [f32; 3],
114 raw_mag_sensitivity_adjustments: [u8; 3],
115 gyro_scale: GyroScale,
117 accel_scale: AccelScale,
118 mag_scale: MagScale,
119 gyro_temp_data_rate: GyroTempDataRate,
120 accel_data_rate: AccelDataRate,
121 sample_rate_divisor: Option<u8>,
122 dmp_configuration: Option<DmpConfiguration>,
123 packet_size: usize,
124 _mode: PhantomData<MODE>,
126}
127
128#[derive(Debug, Copy, Clone)]
130pub enum Error<E> {
131 InvalidDevice(u8),
133 ModeNotSupported(u8),
135 BusError(E),
137 CalibrationError,
139 ReInitError,
142 DmpRead,
144 DmpWrite,
146 DmpFirmware,
148 DmpDataNotReady,
150 DmpDataInvalid,
152}
153
154impl<E> core::convert::From<E> for Error<E> {
155 fn from(error: E) -> Self {
156 Error::BusError(error)
157 }
158}
159
160const MMODE: u8 = 0x06;
162
163pub const G: f32 = 9.807;
165const PI_180: f32 = core::f32::consts::PI / 180.;
166const TEMP_SENSITIVITY: f32 = 333.87;
167const TEMP_DIFF: f32 = 21.0;
168const TEMP_ROOM_OFFSET: f32 = 0.0;
169
170#[cfg(not(feature = "i2c"))]
172mod spi_defs {
173 use super::*;
174 use hal::blocking::spi;
175 use hal::digital::v2::OutputPin;
176
177 impl<E, SPI, NCS> Mpu9250<SpiDevice<SPI, NCS>, Imu>
179 where SPI: spi::Write<u8, Error = E> + spi::Transfer<u8, Error = E>,
180 NCS: OutputPin
181 {
182 pub fn imu_default<D>(
185 spi: SPI,
186 ncs: NCS,
187 delay: &mut D)
188 -> Result<Self,
189 Error<<SpiDevice<SPI, NCS> as device::Device>::Error>>
190 where D: DelayMs<u8>
191 {
192 Self::imu(spi, ncs, delay, &mut MpuConfig::imu())
193 }
194
195 pub fn imu<D>(
200 spi: SPI,
201 ncs: NCS,
202 delay: &mut D,
203 config: &mut MpuConfig<Imu>)
204 -> Result<Self,
205 Error<<SpiDevice<SPI, NCS> as device::Device>::Error>>
206 where D: DelayMs<u8>
207 {
208 let dev = SpiDevice::new(spi, ncs);
209 Self::new_imu(dev, delay, config)
210 }
211
212 pub fn imu_with_reinit<D, F>(
223 spi: SPI,
224 ncs: NCS,
225 delay: &mut D,
226 config: &mut MpuConfig<Imu>,
227 reinit_fn: F)
228 -> Result<Self,
229 Error<<SpiDevice<SPI, NCS> as device::Device>::Error>>
230 where D: DelayMs<u8>,
231 F: FnOnce(SPI, NCS) -> Option<(SPI, NCS)>
232 {
233 let dev = SpiDevice::new(spi, ncs);
234 let mpu = Self::new_imu(dev, delay, config)?;
235 mpu.reinit_spi_device(reinit_fn)
236 }
237 }
238
239 impl<E, SPI, NCS> Mpu9250<SpiDevice<SPI, NCS>, Marg>
241 where SPI: spi::Write<u8, Error = E> + spi::Transfer<u8, Error = E>,
242 NCS: OutputPin
243 {
244 pub fn marg_default<D>(
249 spi: SPI,
250 ncs: NCS,
251 delay: &mut D)
252 -> Result<Self,
253 Error<<SpiDevice<SPI, NCS> as device::Device>::Error>>
254 where D: DelayMs<u8>
255 {
256 Mpu9250::marg(spi, ncs, delay, &mut MpuConfig::marg())
257 }
258
259 pub fn marg<D>(
264 spi: SPI,
265 ncs: NCS,
266 delay: &mut D,
267 config: &mut MpuConfig<Marg>)
268 -> Result<Self,
269 Error<<SpiDevice<SPI, NCS> as device::Device>::Error>>
270 where D: DelayMs<u8>
271 {
272 let dev = SpiDevice::new(spi, ncs);
273 Self::new_marg(dev, delay, config)
274 }
275
276 pub fn marg_with_reinit<D, F>(
287 spi: SPI,
288 ncs: NCS,
289 delay: &mut D,
290 config: &mut MpuConfig<Marg>,
291 reinit_fn: F)
292 -> Result<Self,
293 Error<<SpiDevice<SPI, NCS> as device::Device>::Error>>
294 where D: DelayMs<u8>,
295 F: FnOnce(SPI, NCS) -> Option<(SPI, NCS)>
296 {
297 let dev = SpiDevice::new(spi, ncs);
298 let mpu = Self::new_marg(dev, delay, config)?;
299 mpu.reinit_spi_device(reinit_fn)
300 }
301 }
302
303 #[cfg(feature = "dmp")]
304 impl<E, SPI, NCS> Mpu9250<SpiDevice<SPI, NCS>, Dmp>
305 where SPI: spi::Write<u8, Error = E> + spi::Transfer<u8, Error = E>,
306 NCS: OutputPin
307 {
308 pub fn dmp_default<D>(
310 spi: SPI,
311 ncs: NCS,
312 delay: &mut D,
313 firmware: &[u8])
314 -> Result<Self,
315 Error<<SpiDevice<SPI, NCS> as device::Device>::Error>>
316 where D: DelayMs<u8>
317 {
318 let dev = SpiDevice::new(spi, ncs);
319 Self::new_dmp(dev, delay, &mut MpuConfig::dmp(), firmware)
320 }
321
322 pub fn dmp<D>(
324 spi: SPI,
325 ncs: NCS,
326 delay: &mut D,
327 config: &mut MpuConfig<Dmp>,
328 firmware: &[u8])
329 -> Result<Self,
330 Error<<SpiDevice<SPI, NCS> as device::Device>::Error>>
331 where D: DelayMs<u8>
332 {
333 let dev = SpiDevice::new(spi, ncs);
334 Self::new_dmp(dev, delay, config, firmware)
335 }
336 }
337
338 impl<E, SPI, NCS, MODE> Mpu9250<SpiDevice<SPI, NCS>, MODE>
340 where SPI: spi::Write<u8, Error = E> + spi::Transfer<u8, Error = E>,
341 NCS: OutputPin
342 {
343 pub fn release(self) -> (SPI, NCS) {
345 self.dev.release()
346 }
347
348 fn reinit_spi_device<F>(
349 self,
350 reinit_fn: F)
351 -> Result<Self,
352 Error<<SpiDevice<SPI, NCS> as device::Device>::Error>>
353 where F: FnOnce(SPI, NCS) -> Option<(SPI, NCS)>
354 {
355 self.reset_device(|spidev| {
356 let (cspi, cncs) = spidev.release();
357 reinit_fn(cspi, cncs).map(|(nspi, nncs)| {
358 SpiDevice::new(nspi, nncs)
359 })
360 })
361 }
362 }
363}
364
365#[cfg(not(feature = "i2c"))]
366pub use spi_defs::*;
367
368#[cfg(feature = "i2c")]
369mod i2c_defs {
370 use super::*;
371 use hal::blocking::i2c;
372
373 impl<E, I2C> Mpu9250<I2cDevice<I2C>, Imu>
374 where I2C: i2c::Read<Error = E>
375 + i2c::Write<Error = E>
376 + i2c::WriteRead<Error = E>
377 {
378 pub fn imu_default<D>(
381 i2c: I2C,
382 delay: &mut D)
383 -> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
384 where D: DelayMs<u8>
385 {
386 Mpu9250::imu(i2c, delay, &mut MpuConfig::imu())
387 }
388
389 pub fn imu<D>(
394 i2c: I2C,
395 delay: &mut D,
396 config: &mut MpuConfig<Imu>)
397 -> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
398 where D: DelayMs<u8>
399 {
400 let dev = I2cDevice::new(i2c);
401 Mpu9250::new_imu(dev, delay, config)
402 }
403
404 pub fn imu_with_reinit<D, F>(
411 i2c: I2C,
412 delay: &mut D,
413 config: &mut MpuConfig<Imu>,
414 reinit_fn: F)
415 -> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
416 where D: DelayMs<u8>,
417 F: FnOnce(I2C) -> Option<I2C>
418 {
419 let dev = I2cDevice::new(i2c);
420 let mpu = Self::new_imu(dev, delay, config)?;
421 mpu.reinit_i2c_device(reinit_fn)
422 }
423 }
424
425 impl<E, I2C> Mpu9250<I2cDevice<I2C>, Marg>
426 where I2C: i2c::Read<Error = E>
427 + i2c::Write<Error = E>
428 + i2c::WriteRead<Error = E>
429 {
430 pub fn marg_default<D>(
435 i2c: I2C,
436 delay: &mut D)
437 -> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
438 where D: DelayMs<u8>
439 {
440 Mpu9250::marg(i2c, delay, &mut MpuConfig::marg())
441 }
442
443 pub fn marg<D>(
448 i2c: I2C,
449 delay: &mut D,
450 config: &mut MpuConfig<Marg>)
451 -> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
452 where D: DelayMs<u8>
453 {
454 let dev = I2cDevice::new(i2c);
455 Self::new_marg(dev, delay, config)
456 }
457
458 pub fn marg_with_reinit<D, F>(
465 i2c: I2C,
466 delay: &mut D,
467 config: &mut MpuConfig<Marg>,
468 reinit_fn: F)
469 -> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
470 where D: DelayMs<u8>,
471 F: FnOnce(I2C) -> Option<I2C>
472 {
473 let dev = I2cDevice::new(i2c);
474 let mpu = Self::new_marg(dev, delay, config)?;
475 mpu.reinit_i2c_device(reinit_fn)
476 }
477 }
478
479 #[cfg(feature = "dmp")]
480 impl<E, I2C> Mpu9250<I2cDevice<I2C>, Dmp>
481 where I2C: i2c::Read<Error = E>
482 + i2c::Write<Error = E>
483 + i2c::WriteRead<Error = E>
484 {
485 pub fn dmp_default<D>(
488 i2c: I2C,
489 delay: &mut D,
490 firmware: &[u8])
491 -> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
492 where D: DelayMs<u8>
493 {
494 let dev = I2cDevice::new(i2c);
495 Self::new_dmp(dev, delay, &mut MpuConfig::dmp(), firmware)
496 }
497
498 pub fn dmp<D>(
500 i2c: I2C,
501 delay: &mut D,
502 config: &mut MpuConfig<Dmp>,
503 firmware: &[u8])
504 -> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
505 where D: DelayMs<u8>
506 {
507 let dev = I2cDevice::new(i2c);
508 Self::new_dmp(dev, delay, config, firmware)
509 }
510 }
511
512 impl<E, I2C, MODE> Mpu9250<I2cDevice<I2C>, MODE>
514 where I2C: i2c::Read<Error = E>
515 + i2c::Write<Error = E>
516 + i2c::WriteRead<Error = E>
517 {
518 pub fn release(self) -> I2C {
520 self.dev.release()
521 }
522
523 fn reinit_i2c_device<F>(
524 self,
525 reinit_fn: F)
526 -> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
527 where F: FnOnce(I2C) -> Option<I2C>
528 {
529 self.reset_device(|i2cdev| {
530 let i2c = i2cdev.release();
531 reinit_fn(i2c).map(|i2c| I2cDevice::new(i2c))
532 })
533 }
534 }
535}
536
537#[cfg(feature = "i2c")]
538pub use i2c_defs::*;
539
540impl<E, DEV> Mpu9250<DEV, Imu> where DEV: Device<Error = E>
542{
543 fn new_imu<D>(dev: DEV,
546 delay: &mut D,
547 config: &mut MpuConfig<Imu>)
548 -> Result<Self, Error<E>>
549 where D: DelayMs<u8>
550 {
551 let mut mpu9250 =
552 Mpu9250 { dev,
553 raw_mag_sensitivity_adjustments: [0; 3],
554 mag_sensitivity_adjustments: [0.0; 3],
555 gyro_scale: config.gyro_scale.unwrap_or_default(),
556 accel_scale: config.accel_scale.unwrap_or_default(),
557 mag_scale: MagScale::default(),
558 accel_data_rate: config.accel_data_rate
559 .unwrap_or_default(),
560 gyro_temp_data_rate: config.gyro_temp_data_rate
561 .unwrap_or_default(),
562 sample_rate_divisor: config.sample_rate_divisor,
563 dmp_configuration: config.dmp_configuration,
564 packet_size: 0,
565 _mode: PhantomData };
566 mpu9250.init_mpu(delay)?;
567 let wai = mpu9250.who_am_i()?;
568 if MpuXDevice::imu_supported(wai) {
569 Ok(mpu9250)
570 } else {
571 Err(Error::InvalidDevice(wai))
572 }
573 }
574
575 pub fn config(&mut self, config: &mut MpuConfig<Imu>) -> Result<(), E> {
577 transpose(config.gyro_scale.map(|v| self.gyro_scale(v)))?;
578 transpose(config.accel_scale.map(|v| self.accel_scale(v)))?;
579 transpose(config.accel_data_rate.map(|v| self.accel_data_rate(v)))?;
580 transpose(config.gyro_temp_data_rate
581 .map(|v| self.gyro_temp_data_rate(v)))?;
582 transpose(config.sample_rate_divisor
583 .map(|v| self.sample_rate_divisor(v)))?;
584
585 Ok(())
586 }
587
588 pub fn unscaled_all<T>(&mut self) -> Result<UnscaledImuMeasurements<T>, E>
591 where T: From<[i16; 3]>
592 {
593 let buffer = &mut [0; 15];
594 self.dev.read_many(Register::ACCEL_XOUT_H, &mut buffer[..])?;
595 let accel = self.to_vector(buffer, 0).into();
596 let temp = ((u16(buffer[7]) << 8) | u16(buffer[8])) as i16;
597 let gyro = self.to_vector(buffer, 8).into();
598
599 Ok(UnscaledImuMeasurements { accel,
600 gyro,
601 temp })
602 }
603
604 pub fn all<T>(&mut self) -> Result<ImuMeasurements<T>, E>
607 where T: From<[f32; 3]>
608 {
609 let buffer = &mut [0; 15];
610 self.dev.read_many(Register::ACCEL_XOUT_H, &mut buffer[..])?;
611
612 let accel = self.scale_accel(buffer, 0).into();
613 let temp = self.scale_temp(buffer, 6);
614 let gyro = self.scale_gyro(buffer, 8).into();
615
616 Ok(ImuMeasurements { accel,
617 gyro,
618 temp })
619 }
620
621 pub fn calibrate_at_rest<D, T>(&mut self,
632 delay: &mut D)
633 -> Result<T, Error<E>>
634 where D: DelayMs<u8>,
635 T: From<[f32; 3]>
636 {
637 Ok(self._calibrate_at_rest(delay)?.into())
638 }
639}
640
641impl<E, DEV> Mpu9250<DEV, Marg>
643 where DEV: Device<Error = E> + AK8963<Error = E> + NineDOFDevice
644{
645 fn new_marg<D>(dev: DEV,
648 delay: &mut D,
649 config: &mut MpuConfig<Marg>)
650 -> Result<Self, Error<E>>
651 where D: DelayMs<u8>
652 {
653 let mut mpu9250 =
654 Mpu9250 { dev,
655 raw_mag_sensitivity_adjustments: [0; 3],
656 mag_sensitivity_adjustments: [0.0; 3],
657 gyro_scale: config.gyro_scale.unwrap_or_default(),
658 accel_scale: config.accel_scale.unwrap_or_default(),
659 mag_scale: config.mag_scale.unwrap_or_default(),
660 accel_data_rate: config.accel_data_rate
661 .unwrap_or_default(),
662 gyro_temp_data_rate: config.gyro_temp_data_rate
663 .unwrap_or_default(),
664 sample_rate_divisor: config.sample_rate_divisor,
665 dmp_configuration: config.dmp_configuration,
666 packet_size: 0,
667 _mode: PhantomData };
668 mpu9250.init_mpu(delay)?;
669 let wai = mpu9250.who_am_i()?;
670 if MpuXDevice::marg_supported(wai) {
671 mpu9250.init_ak8963(delay)?;
672 mpu9250.check_ak8963_who_am_i()?;
673 Ok(mpu9250)
674 } else if wai == MpuXDevice::MPU6500 as u8 {
675 Err(Error::ModeNotSupported(wai))
676 } else {
677 Err(Error::InvalidDevice(wai))
678 }
679 }
680
681 pub fn calibrate_at_rest<D, T>(&mut self,
692 delay: &mut D)
693 -> Result<T, Error<E>>
694 where D: DelayMs<u8>,
695 T: From<[f32; 3]>
696 {
697 let accel_biases = self._calibrate_at_rest(delay)?;
698 self.init_ak8963(delay)?;
699 Ok(accel_biases.into())
700 }
701
702 fn init_ak8963<D>(&mut self, delay: &mut D) -> Result<(), E>
703 where D: DelayMs<u8>
704 {
705 AK8963::init(&mut self.dev, delay)?;
706 delay.delay_ms(10);
707 AK8963::write(&mut self.dev, ak8963::Register::CNTL1, 0x00)?;
710 delay.delay_ms(10);
711
712 AK8963::write(&mut self.dev, ak8963::Register::CNTL1, 0x0F)?;
714 delay.delay_ms(20);
715 let mag_x_bias = AK8963::read(&mut self.dev, ak8963::Register::ASAX)?;
716 let mag_y_bias = AK8963::read(&mut self.dev, ak8963::Register::ASAY)?;
717 let mag_z_bias = AK8963::read(&mut self.dev, ak8963::Register::ASAZ)?;
718 self.raw_mag_sensitivity_adjustments =
720 [mag_x_bias, mag_y_bias, mag_z_bias];
721 self.mag_sensitivity_adjustments =
722 [((mag_x_bias - 128) as f32) / 256. + 1.,
723 ((mag_y_bias - 128) as f32) / 256. + 1.,
724 ((mag_z_bias - 128) as f32) / 256. + 1.];
725 AK8963::write(&mut self.dev, ak8963::Register::CNTL1, 0x00)?;
727 delay.delay_ms(10);
728 self._mag_scale()?;
730 delay.delay_ms(10);
731
732 AK8963::finalize(&mut self.dev, delay)?;
733
734 Ok(())
735 }
736
737 pub fn config(&mut self, config: &mut MpuConfig<Marg>) -> Result<(), E> {
739 transpose(config.gyro_scale.map(|v| self.gyro_scale(v)))?;
740 transpose(config.accel_scale.map(|v| self.accel_scale(v)))?;
741 transpose(config.mag_scale.map(|v| self.mag_scale(v)))?;
742 transpose(config.accel_data_rate.map(|v| self.accel_data_rate(v)))?;
743 transpose(config.gyro_temp_data_rate
744 .map(|v| self.gyro_temp_data_rate(v)))?;
745 transpose(config.sample_rate_divisor
746 .map(|v| self.sample_rate_divisor(v)))?;
747
748 Ok(())
749 }
750
751 pub fn unscaled_all<T>(&mut self) -> Result<UnscaledMargMeasurements<T>, E>
754 where T: From<[i16; 3]>
755 {
756 let buffer = &mut [0; 21];
757 NineDOFDevice::read_9dof(&mut self.dev,
758 Register::ACCEL_XOUT_H,
759 buffer)?;
760 let accel = self.to_vector(buffer, 0).into();
761 let temp = ((u16(buffer[7]) << 8) | u16(buffer[8])) as i16;
762 let gyro = self.to_vector(buffer, 8).into();
763 let mag = self.to_vector_inverted(buffer, 14).into();
764
765 Ok(UnscaledMargMeasurements { accel,
766 gyro,
767 temp,
768 mag })
769 }
770
771 pub fn all<T>(&mut self) -> Result<MargMeasurements<T>, E>
774 where T: From<[f32; 3]>
775 {
776 let buffer = &mut [0; 21];
777 NineDOFDevice::read_9dof(&mut self.dev,
778 Register::ACCEL_XOUT_H,
779 buffer)?;
780
781 let accel = self.scale_accel(buffer, 0).into();
782 let temp = self.scale_temp(buffer, 6);
783 let gyro = self.scale_gyro(buffer, 8).into();
784 let mag = self.scale_and_correct_mag(buffer, 14).into();
785
786 Ok(MargMeasurements { accel,
787 gyro,
788 temp,
789 mag })
790 }
791
792 pub fn magnetometer_healthy(&mut self) -> Result<bool, E> {
797 let buffer = &mut [0; 7];
798 let control =
800 AK8963::read(&mut self.dev, ak8963::Register::CNTL1)? & 0b11110000;
801 AK8963::write(&mut self.dev, ak8963::Register::CNTL1, control)?;
802 AK8963::write(&mut self.dev, ak8963::Register::ASTC, 0b01000000)?;
805 AK8963::write(&mut self.dev,
807 ak8963::Register::CNTL1,
808 control | 0b00001000)?;
809 while AK8963::read(&mut self.dev, ak8963::Register::ST1)? & 0b00000001
812 != 0
813 {}
814 self.dev.read_xyz(buffer)?;
817 AK8963::write(&mut self.dev, ak8963::Register::ASTC, 0x00)?;
819 AK8963::write(&mut self.dev, ak8963::Register::CNTL1, control)?;
821 let measurements = self.to_vector_inverted(buffer, 0);
825 let range = if (control & 0b00010000) != 0 {
826 200.0
827 } else {
828 50.0
829 };
830 for i in 0..3 {
831 let adjusted_measurement =
832 measurements[i] as f32 * self.mag_sensitivity_adjustments[i];
833 if !(adjusted_measurement < -range || adjusted_measurement > range)
834 {
835 return Ok(false);
836 }
837 }
838 Ok(true)
839 }
840
841 fn scale_and_correct_mag(&self, buffer: &[u8], offset: usize) -> [f32; 3] {
842 let resolution = self.mag_scale.resolution();
843 let raw = self.to_vector_inverted(buffer, offset);
844
845 [raw[0] as f32 * resolution * self.mag_sensitivity_adjustments[0],
846 raw[1] as f32 * resolution * self.mag_sensitivity_adjustments[1],
847 raw[2] as f32 * resolution * self.mag_sensitivity_adjustments[2]]
848 }
849
850 pub fn unscaled_mag<T>(&mut self) -> Result<T, E>
852 where T: From<[i16; 3]>
853 {
854 let buffer = &mut [0; 7];
855 self.dev.read_xyz(buffer)?;
856 Ok(self.to_vector_inverted(buffer, 0).into())
857 }
858
859 pub fn mag<T>(&mut self) -> Result<T, E>
862 where T: From<[f32; 3]>
863 {
864 let buffer = &mut [0; 7];
865 self.dev.read_xyz(buffer)?;
866 Ok(self.scale_and_correct_mag(buffer, 0).into())
867 }
868
869 pub fn raw_mag_sensitivity_adjustments<T>(&self) -> T
871 where T: From<[u8; 3]>
872 {
873 self.raw_mag_sensitivity_adjustments.into()
874 }
875
876 pub fn mag_sensitivity_adjustments<T>(&self) -> T
878 where T: From<[f32; 3]>
879 {
880 self.mag_sensitivity_adjustments.into()
881 }
882
883 pub fn mag_scale(&mut self, scale: MagScale) -> Result<(), E> {
887 self.mag_scale = scale;
888 self._mag_scale()
889 }
890
891 fn _mag_scale(&mut self) -> Result<(), E> {
892 let scale = self.mag_scale as u8;
894 AK8963::write(&mut self.dev,
895 ak8963::Register::CNTL1,
896 scale << 4 | MMODE)?;
897 Ok(())
898 }
899
900 fn check_ak8963_who_am_i(&mut self) -> Result<(), Error<E>> {
901 let ak8963_who_am_i = self.ak8963_who_am_i()?;
902 if ak8963_who_am_i == 0x48 {
903 Ok(())
904 } else {
905 Err(Error::InvalidDevice(ak8963_who_am_i))
906 }
907 }
908
909 pub fn ak8963_who_am_i(&mut self) -> Result<u8, E> {
911 AK8963::read(&mut self.dev, ak8963::Register::WHO_AM_I)
912 }
913}
914
915#[cfg(feature = "dmp")]
917impl<E, DEV> Mpu9250<DEV, Dmp> where DEV: Device<Error = E>
918{
919 fn new_dmp<D>(dev: DEV,
922 delay: &mut D,
923 config: &mut MpuConfig<Dmp>,
924 firmware: &[u8])
925 -> Result<Self, Error<E>>
926 where D: DelayMs<u8>
927 {
928 let mut mpu9250 =
929 Mpu9250 { dev,
930 raw_mag_sensitivity_adjustments: [0; 3],
931 mag_sensitivity_adjustments: [0.0; 3],
932 gyro_scale: config.gyro_scale
933 .unwrap_or(GyroScale::_2000DPS),
934 accel_scale: config.accel_scale
935 .unwrap_or(AccelScale::_8G),
936 mag_scale: config.mag_scale.unwrap_or_default(),
937 accel_data_rate:
938 config.accel_data_rate
939 .unwrap_or(AccelDataRate::DlpfConf(Dlpf::_1)),
940 gyro_temp_data_rate:
941 config.gyro_temp_data_rate
942 .unwrap_or(GyroTempDataRate::DlpfConf(Dlpf::_1)),
943 sample_rate_divisor: config.sample_rate_divisor
944 .or(Some(4)),
945 dmp_configuration: Some(config.dmp_configuration
946 .unwrap_or_default()),
947 packet_size: config.dmp_configuration
948 .unwrap_or_default()
949 .features
950 .packet_size(),
951 _mode: PhantomData };
952 mpu9250.init_mpu(delay)?;
953 mpu9250.init_dmp(delay, firmware)?;
954 Ok(mpu9250)
955 }
956
957 fn init_dmp<D>(&mut self,
959 delay: &mut D,
960 firmware: &[u8])
961 -> Result<(), Error<E>>
962 where D: DelayMs<u8>
963 {
964 let conf = self.dmp_configuration.unwrap_or_default();
965 const FIFO_EN: u8 = 1 << 6;
967 self.dev.write(Register::USER_CTRL, FIFO_EN)?;
968 delay.delay_ms(3);
969
970 self.interrupt_config(InterruptConfig::LATCH_INT_EN
972 | InterruptConfig::INT_ANYRD_CLEAR
973 | InterruptConfig::ACL
974 | InterruptConfig::BYPASS_EN)?;
975
976 self.load_firmware(firmware)?;
978
979 self.write_mem(DmpMemory::FCFG_1, &conf.orientation.gyro_axes())?;
981 self.write_mem(DmpMemory::FCFG_2, &conf.orientation.accel_axes())?;
982 self.write_mem(DmpMemory::FCFG_3, &conf.orientation.gyro_signs())?;
983 self.write_mem(DmpMemory::FCFG_7, &conf.orientation.accel_signs())?;
984
985 self.set_dmp_feature(delay)?;
987
988 let div = [0, conf.rate as u8];
989 self.write_mem(DmpMemory::D_0_22, &div)?;
990
991 self.write_mem(DmpMemory::CFG_6,
992 &[0xfe, 0xf2, 0xab, 0xc4, 0xaa, 0xf1, 0xdf, 0xdf,
993 0xbb, 0xaf, 0xdf, 0xdf])?;
994
995 self.dev.write(Register::INT_ENABLE, 0)?;
997 self.dev.write(Register::FIFO_EN, 0)?;
998
999 self.dev.write(Register::USER_CTRL, FIFO_EN)?;
1001 delay.delay_ms(10);
1002 self.interrupt_config(InterruptConfig::LATCH_INT_EN
1003 | InterruptConfig::INT_ANYRD_CLEAR
1004 | InterruptConfig::ACL
1005 | InterruptConfig::BYPASS_EN)?;
1006
1007 self.dev.write(Register::FIFO_EN, 0)?;
1008 self.dev.write(Register::INT_ENABLE, 0x02)?;
1009 self.dev.write(Register::FIFO_EN, 0)?;
1010 self.reset_fifo(delay)?;
1011
1012 self.write_mem(DmpMemory::CFG_FIFO_ON_EVENT,
1014 &[0xd8, 0xb1, 0xb9, 0xf3, 0x8b, 0xa3, 0x91, 0xb6,
1015 0x09, 0xb4, 0xd9])?;
1016
1017 Ok(())
1018 }
1019
1020 fn load_firmware(&mut self, firmware: &[u8]) -> Result<(), Error<E>> {
1022 let mut buffer: [u8; 17] = [0; 17];
1023 let mut addr: u16 = 0;
1024
1025 for chunk in firmware.chunks(16) {
1026 self.write_mem(addr, chunk)?;
1027 self.read_mem(addr, &mut buffer)?;
1028 if &buffer[1..chunk.len() + 1] != chunk {
1029 return Err(Error::DmpFirmware);
1030 }
1031 addr += chunk.len() as u16;
1032 }
1033 assert_eq!(addr as usize, firmware.len());
1034
1035 const DMP_START_ADDR: [u8; 2] = [0x04, 0x00];
1036 self.dev.write_many(Register::DMP_START_ADDR, &DMP_START_ADDR)?;
1037
1038 Ok(())
1039 }
1040
1041 fn write_mem<T>(&mut self, addr: T, data: &[u8]) -> Result<(), Error<E>>
1043 where T: Into<u16> + Copy
1044 {
1045 self.dev.write(Register::BANK_SEL, (addr.into() >> 8) as u8)?;
1046 self.dev.write(Register::MEM_ADDR, (addr.into() & 0xff) as u8)?;
1047 self.dev.write_many(Register::MEM_RW, data)?;
1048 Ok(())
1049 }
1050
1051 fn read_mem<T>(&mut self, addr: T, data: &mut [u8]) -> Result<(), Error<E>>
1053 where T: Into<u16> + Copy
1054 {
1055 self.dev.write(Register::BANK_SEL, (addr.into() >> 8) as u8)?;
1056 self.dev.write(Register::MEM_ADDR, (addr.into() & 0xff) as u8)?;
1057 self.dev.read_many(Register::MEM_RW, data)?;
1058 Ok(())
1059 }
1060
1061 fn set_dmp_feature<D>(&mut self, delay: &mut D) -> Result<(), Error<E>>
1063 where D: DelayMs<u8>
1064 {
1065 let features = self.dmp_configuration.unwrap_or_default().features;
1066 const GYRO_SF: [u8; 4] = [(46_850_825 >> 24) as u8,
1067 (46_850_825 >> 16) as u8,
1068 (46_850_825 >> 8) as u8,
1069 (46_850_825 & 0xff) as u8];
1070 self.write_mem(DmpMemory::D_0_104, &GYRO_SF)?;
1071
1072 let mut conf = [0xa3 as u8; 10];
1073 if features.raw_accel {
1074 conf[1] = 0xc0;
1075 conf[2] = 0xc8;
1076 conf[3] = 0xc2;
1077 }
1078 if features.raw_gyro {
1079 conf[4] = 0xc4;
1080 conf[5] = 0xcc;
1081 conf[6] = 0xc6;
1082 }
1083 self.write_mem(DmpMemory::CFG_15, &conf)?;
1084
1085 let mut set_config = |address,
1086 state,
1087 config_enabled,
1088 config_disabled|
1089 -> Result<(), Error<E>> {
1090 let config = if state {
1091 config_enabled
1092 } else {
1093 config_disabled
1094 };
1095 self.write_mem(address, config)?;
1096
1097 Ok(())
1098 };
1099
1100 set_config(DmpMemory::CFG_27,
1101 features.tap | features.android_orient,
1102 &[0x20],
1103 &[0xd8])?;
1104 set_config(DmpMemory::CFG_MOTION_BIAS,
1105 features.gyro_auto_calibrate,
1106 &[0xb8, 0xaa, 0xb3, 0x8d, 0xb4, 0x98, 0x0d, 0x35, 0x5d],
1107 &[0xb8, 0xaa, 0xaa, 0xaa, 0xb0, 0x88, 0xc3, 0xc5, 0xc7])?;
1108
1109 if features.raw_gyro {
1110 set_config(DmpMemory::CFG_GYRO_RAW_DATA,
1111 features.gyro_auto_calibrate,
1112 &[0xb2, 0x8b, 0xb6, 0x9b],
1113 &[0xb0, 0x80, 0xb4, 0x90])?;
1114 }
1115
1116 set_config(DmpMemory::CFG_20, features.tap, &[0xf8], &[0xd8])?;
1118 set_config(DmpMemory::CFG_ANDROID_ORIENT_INT,
1119 features.android_orient,
1120 &[0xd9],
1121 &[0xd8])?;
1122 set_config(DmpMemory::CFG_LP_QUAT,
1123 features.quat,
1124 &[0xc0, 0xc2, 0xc4, 0xc6],
1125 &[0x8b, 0x8b, 0x8b, 0x8b])?;
1126 set_config(DmpMemory::CFG_8,
1127 features.quat6,
1128 &[0x20, 0x28, 0x30, 0x38],
1129 &[0xa3, 0xa3, 0xa3, 0xa3])?;
1130
1131 self.reset_fifo(delay)?;
1132
1133 Ok(())
1134 }
1135
1136 pub fn dmp_unscaled_all<T1, T2>(
1139 &mut self)
1140 -> Result<UnscaledDmpMeasurement<T1, T2>, Error<E>>
1141 where T1: From<[i16; 3]>,
1142 T2: From<[i32; 4]>
1143 {
1144 let features = self.dmp_configuration.unwrap_or_default().features;
1145
1146 let mut buffer: [u8; 33] = [0; 33];
1147 let read = self.read_fifo(&mut buffer[..self.packet_size + 1])?;
1148 if read < 0 {
1149 return Err(Error::DmpDataNotReady);
1150 }
1151
1152 let mut offset = 0;
1153 let mut measures: UnscaledDmpMeasurement<T1, T2> =
1154 UnscaledDmpMeasurement { quaternion: None,
1155 accel: None,
1156 gyro: None };
1157 if features.quat6 || features.quat {
1158 measures.quaternion = Some(self.to_quat(&buffer).into());
1159 offset += 16;
1160 }
1161 if features.raw_accel {
1162 measures.accel = Some(self.to_vector(&buffer, offset).into());
1163 offset += 6;
1164 }
1165 if features.raw_gyro {
1166 measures.gyro = Some(self.to_vector(&buffer, offset).into());
1167 }
1169 Ok(measures)
1170 }
1171
1172 pub fn dmp_all<T1, T2>(&mut self)
1176 -> Result<DmpMeasurement<T1, T2>, Error<E>>
1177 where T1: From<[f32; 3]>,
1178 T2: From<[f64; 4]>
1179 {
1180 let features = self.dmp_configuration.unwrap_or_default().features;
1181
1182 let mut buffer: [u8; 33] = [0; 33];
1183 let read = self.read_fifo(&mut buffer[..self.packet_size + 1])?;
1184 if read < 0 {
1185 return Err(Error::DmpDataNotReady);
1186 }
1187
1188 let mut offset = 0;
1189 let mut measures: DmpMeasurement<T1, T2> =
1190 DmpMeasurement { quaternion: None,
1191 accel: None,
1192 gyro: None };
1193 if features.quat6 || features.quat {
1194 measures.quaternion = Some(self.to_norm_quat(&buffer).into());
1195 offset += 16;
1196 }
1197 if features.raw_accel {
1198 measures.accel = Some(self.scale_accel(&buffer, offset).into());
1199 offset += 6;
1200 }
1201 if features.raw_gyro {
1202 measures.gyro = Some(self.scale_gyro(&buffer, offset).into());
1203 }
1205 Ok(measures)
1206 }
1207
1208 fn to_quat(&self, buffer: &[u8]) -> [i32; 4] {
1210 [(buffer[1] as i32) << 24
1211 | (buffer[2] as i32) << 16
1212 | (buffer[3] as i32) << 8
1213 | buffer[4] as i32,
1214 (buffer[5] as i32) << 24
1215 | (buffer[6] as i32) << 16
1216 | (buffer[7] as i32) << 8
1217 | buffer[8] as i32,
1218 (buffer[9] as i32) << 24
1219 | (buffer[10] as i32) << 16
1220 | (buffer[11] as i32) << 8
1221 | buffer[12] as i32,
1222 (buffer[13] as i32) << 24
1223 | (buffer[14] as i32) << 16
1224 | (buffer[15] as i32) << 8
1225 | buffer[16] as i32]
1226 }
1227
1228 fn to_norm_quat(&self, buffer: &[u8]) -> [f64; 4] {
1230 let quat = self.to_quat(buffer);
1231 let quat = [f64::from(quat[0]),
1233 f64::from(quat[1]),
1234 f64::from(quat[2]),
1235 f64::from(quat[3])];
1236 let sum =
1237 libm::sqrt(quat.iter().map(|x| libm::pow(*x, 2.0)).sum::<f64>());
1238 [quat[0] / sum, quat[1] / sum, quat[2] / sum, quat[3] / sum]
1239 }
1240}
1241
1242impl<E, DEV, MODE> Mpu9250<DEV, MODE> where DEV: Device<Error = E>
1244{
1245 fn init_mpu<D>(&mut self, delay: &mut D) -> Result<(), E>
1246 where D: DelayMs<u8>
1247 {
1248 self.dev.write(Register::I2C_SLV0_CTRL, 0).ok(); self.dev.write(Register::I2C_SLV4_CTRL, 0).ok(); delay.delay_ms(1); self.dev.write(Register::PWR_MGMT_1, 0x80)?;
1259 delay.delay_ms(100); self.dev.write(Register::PWR_MGMT_1, 0x01)?;
1265 self.dev.write(Register::PWR_MGMT_2, 0x00)?;
1267
1268 self._gyro_scale()?;
1270 self._gyro_temp_data_rate()?;
1272
1273 self._accel_scale()?;
1275 self._accel_data_rate()?;
1277
1278 self._sample_rate_divisor()?;
1280
1281 self.dev.write(Register::INT_ENABLE, 0x00)?;
1283
1284 Ok(())
1285 }
1286
1287 fn reset_device<F>(self, f: F) -> Result<Self, Error<E>>
1288 where F: FnOnce(DEV) -> Option<DEV>
1289 {
1290 let raw_mag_sensitivity_adjustments =
1291 self.raw_mag_sensitivity_adjustments;
1292 let mag_sensitivity_adjustments = self.mag_sensitivity_adjustments;
1293 let gyro_scale = self.gyro_scale;
1294 let accel_scale = self.accel_scale;
1295 let mag_scale = self.mag_scale;
1296 let accel_data_rate = self.accel_data_rate;
1297 let gyro_temp_data_rate = self.gyro_temp_data_rate;
1298 let sample_rate_divisor = self.sample_rate_divisor;
1299 let dmp_configuration = self.dmp_configuration;
1300 let packet_size = self.packet_size;
1301 let _mode = self._mode;
1302 if let Some(new_dev) = f(self.dev) {
1303 Ok(Mpu9250 { dev: new_dev,
1304 raw_mag_sensitivity_adjustments,
1305 mag_sensitivity_adjustments,
1306 gyro_scale,
1307 accel_scale,
1308 mag_scale,
1309 accel_data_rate,
1310 gyro_temp_data_rate,
1311 sample_rate_divisor,
1312 dmp_configuration,
1313 packet_size,
1314 _mode })
1315 } else {
1316 Err(Error::ReInitError)
1317 }
1318 }
1319
1320 fn scale_accel(&self, buffer: &[u8], offset: usize) -> [f32; 3] {
1321 let resolution = self.accel_scale.resolution();
1322 let scale = G * resolution;
1323 let raw = self.to_vector(buffer, offset);
1324 [raw[0] as f32 * scale, raw[1] as f32 * scale, raw[2] as f32 * scale]
1325 }
1326
1327 fn scale_gyro(&self, buffer: &[u8], offset: usize) -> [f32; 3] {
1328 let resolution = self.gyro_scale.resolution();
1329 let scale = PI_180 * resolution;
1330 let raw = self.to_vector(buffer, offset);
1331 [raw[0] as f32 * scale, raw[1] as f32 * scale, raw[2] as f32 * scale]
1332 }
1333
1334 fn scale_temp(&self, buffer: &[u8], offset: usize) -> f32 {
1335 let rt = (u16(buffer[offset + 1]) << 8) | u16(buffer[offset + 2]);
1336 let t = rt as f32;
1337 (t - TEMP_ROOM_OFFSET) / TEMP_SENSITIVITY + TEMP_DIFF
1338 }
1339
1340 pub fn get_enabled_interrupts(&mut self) -> Result<InterruptEnable, E> {
1342 let bits = self.dev.read(Register::INT_ENABLE)?;
1343 Ok(InterruptEnable::from_bits_truncate(bits))
1344 }
1345
1346 pub fn get_interrupt_status(&mut self) -> Result<InterruptEnable, E> {
1348 let bits = self.dev.read(Register::INT_STATUS)?;
1349 Ok(InterruptEnable::from_bits_truncate(bits))
1350 }
1351
1352 pub fn enable_interrupts(&mut self, ie: InterruptEnable) -> Result<(), E> {
1354 self.dev.modify(Register::INT_ENABLE, |r| r | ie.bits())
1355 }
1356
1357 pub fn disable_interrupts(&mut self, ie: InterruptEnable) -> Result<(), E> {
1359 self.dev.modify(Register::INT_ENABLE, |r| r & !ie.bits())
1360 }
1361
1362 pub fn get_interrupt_config(&mut self) -> Result<InterruptConfig, E> {
1364 let bits = self.dev.read(Register::INT_PIN_CFG)?;
1365 Ok(InterruptConfig::from_bits_truncate(bits))
1366 }
1367
1368 pub fn interrupt_config(&mut self, ic: InterruptConfig) -> Result<(), E> {
1370 self.dev.write(Register::INT_PIN_CFG, ic.bits())
1371 }
1372
1373 pub fn reset_fifo<D>(&mut self, delay: &mut D) -> Result<(), Error<E>>
1375 where D: DelayMs<u8>
1376 {
1377 self.dev.write(Register::INT_ENABLE, 0)?;
1378 self.dev.write(Register::FIFO_EN, 0)?;
1379 self.dev.write(Register::USER_CTRL, 0)?;
1380 self.dev.write(Register::USER_CTRL, 0x0c)?;
1381 delay.delay_ms(3);
1382 self.dev.write(Register::USER_CTRL, 0xc0)?;
1383 self.dev.write(Register::INT_ENABLE, 0x02)?;
1384 self.dev.write(Register::FIFO_EN, 0)?;
1385
1386 Ok(())
1387 }
1388
1389 pub fn read_fifo(&mut self, data: &mut [u8]) -> Result<isize, Error<E>> {
1396 let mut buffer: [u8; 3] = [0; 3];
1397 self.dev.read_many(Register::FIFO_COUNT_H, &mut buffer)?;
1398 let count = (buffer[1] as usize) << 8 | buffer[2] as usize;
1399 if data.len() <= count + 1 {
1400 self.dev.read_many(Register::FIFO_RW, &mut data[..])?;
1401 }
1402 Ok(count as isize - data.len() as isize + 1)
1403 }
1404
1405 pub fn unscaled_accel<T>(&mut self) -> Result<T, E>
1407 where T: From<[i16; 3]>
1408 {
1409 let buffer = &mut [0; 7];
1410 self.dev.read_many(Register::ACCEL_XOUT_H, buffer)?;
1411 Ok(self.to_vector(buffer, 0).into())
1412 }
1413
1414 pub fn accel<T>(&mut self) -> Result<T, E>
1416 where T: From<[f32; 3]>
1417 {
1418 let buffer = &mut [0; 7];
1419 self.dev.read_many(Register::ACCEL_XOUT_H, buffer)?;
1420 Ok(self.scale_accel(buffer, 0).into())
1421 }
1422
1423 pub fn unscaled_gyro<T>(&mut self) -> Result<T, E>
1425 where T: From<[i16; 3]>
1426 {
1427 let buffer = &mut [0; 7];
1428 self.dev.read_many(Register::GYRO_XOUT_H, buffer)?;
1429 Ok(self.to_vector(buffer, 0).into())
1430 }
1431
1432 pub fn gyro<T>(&mut self) -> Result<T, E>
1434 where T: From<[f32; 3]>
1435 {
1436 let buffer = &mut [0; 7];
1437 self.dev.read_many(Register::GYRO_XOUT_H, buffer)?;
1438 Ok(self.scale_gyro(buffer, 0).into())
1439 }
1440
1441 pub fn accel_data_rate(&mut self,
1445 accel_data_rate: AccelDataRate)
1446 -> Result<(), E> {
1447 self.accel_data_rate = accel_data_rate;
1448 self._accel_data_rate()
1449 }
1450
1451 fn _accel_data_rate(&mut self) -> Result<(), E> {
1452 let bits = self.accel_data_rate.accel_config_bits();
1453 self.dev.write(Register::ACCEL_CONFIG_2, bits)?;
1454
1455 Ok(())
1456 }
1457
1458 pub fn accel_scale(&mut self, scale: AccelScale) -> Result<(), E> {
1462 self.accel_scale = scale;
1463 self._accel_scale()
1464 }
1465
1466 fn _accel_scale(&mut self) -> Result<(), E> {
1467 let scale = self.accel_scale as u8;
1468 self.dev.modify(Register::ACCEL_CONFIG, |r|
1469 (r & !0x18)
1471 | (scale << 3))?;
1473 Ok(())
1474 }
1475
1476 pub fn gyro_temp_data_rate(&mut self,
1481 data_rate: GyroTempDataRate)
1482 -> Result<(), E> {
1483 self.gyro_temp_data_rate = data_rate;
1484 self._gyro_temp_data_rate()
1485 }
1486
1487 fn _gyro_temp_data_rate(&mut self) -> Result<(), E> {
1488 let fchoice_bits = self.gyro_temp_data_rate.fchoice_b_bits();
1489 let dlpf_bits = self.gyro_temp_data_rate.dlpf_bits();
1490 self.dev
1492 .modify(Register::GYRO_CONFIG, |r| (r & !0b11) | fchoice_bits)?;
1493 self.dev.modify(Register::CONFIG, |r| (r & !0b111) | dlpf_bits)?;
1495
1496 Ok(())
1497 }
1498
1499 pub fn gyro_scale(&mut self, scale: GyroScale) -> Result<(), E> {
1503 self.gyro_scale = scale;
1504 self._gyro_scale()
1505 }
1506
1507 fn _gyro_scale(&mut self) -> Result<(), E> {
1508 let scale = self.gyro_scale as u8;
1509 self.dev.modify(Register::GYRO_CONFIG, |r|
1510 (r & !0x18)
1512 | (scale << 3))?;
1514
1515 Ok(())
1516 }
1517
1518 pub fn raw_temp(&mut self) -> Result<i16, E> {
1520 let buffer = &mut [0; 3];
1521 self.dev.read_many(Register::TEMP_OUT_H, buffer)?;
1522 let t = (u16(buffer[1]) << 8) | u16(buffer[2]);
1523 Ok(t as i16)
1524 }
1525
1526 pub fn temp(&mut self) -> Result<f32, E> {
1528 let buffer = &mut [0; 3];
1529 self.dev.read_many(Register::TEMP_OUT_H, buffer)?;
1530 Ok(self.scale_temp(buffer, 0))
1531 }
1532
1533 pub fn sample_rate_divisor(&mut self, smplrt_div: u8) -> Result<(), E> {
1542 self.sample_rate_divisor = Some(smplrt_div);
1543 self.dev.write(Register::SMPLRT_DIV, smplrt_div)?;
1544 Ok(())
1545 }
1546
1547 fn _sample_rate_divisor(&mut self) -> Result<(), E> {
1548 if let Some(sample_rate_div) = self.sample_rate_divisor {
1549 self.dev.write(Register::SMPLRT_DIV, sample_rate_div)?;
1550 }
1551 Ok(())
1552 }
1553
1554 fn _calibrate_at_rest<D>(&mut self,
1555 delay: &mut D)
1556 -> Result<[f32; 3], Error<E>>
1557 where D: DelayMs<u8>
1558 {
1559 let orig_gyro_scale = self.gyro_scale;
1561 let orig_accel_scale = self.accel_scale;
1562 let orig_gyro_temp_data_rate = self.gyro_temp_data_rate;
1563 let orig_accel_data_rate = self.accel_data_rate;
1564 let orig_sample_rate_divisor = self.sample_rate_divisor;
1565 self.dev.write(Register::PWR_MGMT_1, 0x80)?;
1567 self.dev.write(Register::PWR_MGMT_1, 0x01)?;
1571 self.dev.write(Register::PWR_MGMT_2, 0x00)?;
1573 delay.delay_ms(200);
1574
1575 self.dev.write(Register::INT_ENABLE, 0x00)?;
1578 self.dev.write(Register::FIFO_EN, 0x00)?;
1580 self.dev.write(Register::PWR_MGMT_1, 0x00)?;
1582 self.dev.write(Register::I2C_MST_CTRL, 0x00)?;
1584 self.dev.write(Register::USER_CTRL, 0x00)?;
1586 self.dev.write(Register::USER_CTRL, 0x0C)?;
1588 delay.delay_ms(15);
1589
1590 self.gyro_temp_data_rate(GyroTempDataRate::DlpfConf(Dlpf::_1))?;
1593 self.sample_rate_divisor(0)?;
1594 self.accel_data_rate(AccelDataRate::DlpfConf(Dlpf::_1))?;
1598 self.accel_scale(AccelScale::_2G)?;
1600
1601 self.dev.write(Register::USER_CTRL, 0x40)?;
1604 self.dev.write(Register::FIFO_EN, 0x78)?;
1606 delay.delay_ms(40);
1610
1611 self.dev.write(Register::FIFO_EN, 0x00)?;
1614 let buffer = &mut [0; 13]; self.dev.read_many(Register::FIFO_COUNT_H, &mut buffer[0..3])?;
1617 let fifo_count = ((u16(buffer[1]) << 8) | u16(buffer[2])) as i16;
1618 let packet_count = (fifo_count / 12) as i32;
1621 if packet_count < 20 {
1622 return Err(Error::CalibrationError);
1623 }
1624 let mut accel_biases = [0; 3];
1625 let mut gyro_biases = [0; 3];
1626 for _ in 0..packet_count {
1627 self.dev.read_many(Register::FIFO_RW, buffer)?;
1628 let accel_temp = self.to_vector(buffer, 0);
1629 let gyro_temp = self.to_vector(buffer, 6);
1630 for i in 0..3 {
1631 accel_biases[i] += accel_temp[i] as i32;
1632 gyro_biases[i] += gyro_temp[i] as i32;
1633 }
1634 }
1635 for i in 0..3 {
1636 accel_biases[i] /= packet_count;
1637 gyro_biases[i] /= packet_count;
1638 }
1639
1640 self.set_unscaled_gyro_bias(false,
1648 [(gyro_biases[0] / -4) as i16,
1649 (gyro_biases[1] / -4) as i16,
1650 (gyro_biases[2] / -4) as i16])?;
1651
1652 let resolution = self.accel_scale.resolution();
1654 let scale = G * resolution;
1655
1656 self.gyro_scale = orig_gyro_scale;
1658 self.accel_scale = orig_accel_scale;
1659 self.gyro_temp_data_rate = orig_gyro_temp_data_rate;
1660 self.accel_data_rate = orig_accel_data_rate;
1661 self.sample_rate_divisor = orig_sample_rate_divisor;
1662 self.init_mpu(delay)?;
1663
1664 Ok([accel_biases[0] as f32 * scale,
1665 accel_biases[1] as f32 * scale,
1666 accel_biases[2] as f32 * scale])
1667 }
1668
1669 fn get_unscaled_gyro_bias(&mut self) -> Result<[i16; 3], Error<E>> {
1672 Ok([(self.dev.read(Register::XG_OFFSET_H)? as i16) << 8
1673 | self.dev.read(Register::XG_OFFSET_L)? as i16,
1674 (self.dev.read(Register::YG_OFFSET_H)? as i16) << 8
1675 | self.dev.read(Register::YG_OFFSET_L)? as i16,
1676 (self.dev.read(Register::ZG_OFFSET_H)? as i16) << 8
1677 | self.dev.read(Register::ZG_OFFSET_L)? as i16])
1678 }
1679
1680 pub fn get_gyro_bias<T>(&mut self) -> Result<T, Error<E>>
1682 where T: From<[f32; 3]>
1683 {
1684 let biases = self.get_unscaled_gyro_bias()?;
1685 let scale = GyroScale::_1000DPS.resolution();
1686
1687 Ok([biases[0] as f32 * scale,
1688 biases[1] as f32 * scale,
1689 biases[2] as f32 * scale].into())
1690 }
1691
1692 fn set_unscaled_gyro_bias(&mut self,
1696 relative: bool,
1697 biases: [i16; 3])
1698 -> Result<(), Error<E>> {
1699 let mut new_biases = biases;
1700
1701 if relative {
1702 let old_biases = self.get_unscaled_gyro_bias()?;
1703
1704 for i in 0..3 {
1705 new_biases[i] += old_biases[i];
1706 }
1707 }
1708
1709 self.dev.write(Register::XG_OFFSET_H,
1710 ((new_biases[0] >> 8) & 0xFF) as u8)?;
1711 self.dev.write(Register::XG_OFFSET_L, (new_biases[0] & 0xFF) as u8)?;
1712 self.dev.write(Register::YG_OFFSET_H,
1713 ((new_biases[1] >> 8) & 0xFF) as u8)?;
1714 self.dev.write(Register::YG_OFFSET_L, (new_biases[1] & 0xFF) as u8)?;
1715 self.dev.write(Register::ZG_OFFSET_H,
1716 ((new_biases[2] >> 8) & 0xFF) as u8)?;
1717 self.dev.write(Register::ZG_OFFSET_L, (new_biases[2] & 0xFF) as u8)?;
1718
1719 Ok(())
1720 }
1721
1722 pub fn set_gyro_bias<T>(&mut self,
1726 relative: bool,
1727 biases: T)
1728 -> Result<(), Error<E>>
1729 where T: Into<[f32; 3]>
1730 {
1731 let biases = biases.into();
1732 let scale = GyroScale::_1000DPS.resolution();
1733
1734 self.set_unscaled_gyro_bias(relative,
1735 [(biases[0] / scale) as i16,
1736 (biases[1] / scale) as i16,
1737 (biases[2] / scale) as i16])
1738 }
1739
1740 fn get_unscaled_accel_bias(&mut self) -> Result<[i16; 3], Error<E>> {
1743 Ok([(self.dev.read(Register::XA_OFFSET_H)? as i16) << 8
1744 | self.dev.read(Register::XA_OFFSET_L)? as i16,
1745 (self.dev.read(Register::YA_OFFSET_H)? as i16) << 8
1746 | self.dev.read(Register::YA_OFFSET_L)? as i16,
1747 (self.dev.read(Register::ZA_OFFSET_H)? as i16) << 8
1748 | self.dev.read(Register::ZA_OFFSET_L)? as i16])
1749 }
1750
1751 pub fn get_accel_bias<T>(&mut self) -> Result<T, Error<E>>
1753 where T: From<[f32; 3]>
1754 {
1755 let biases = self.get_unscaled_accel_bias()?;
1756 let scale = G * AccelScale::_16G.resolution();
1757
1758 Ok([biases[0] as f32 * scale,
1759 biases[1] as f32 * scale,
1760 biases[2] as f32 * scale].into())
1761 }
1762
1763 fn set_unscaled_accel_bias(&mut self,
1768 relative: bool,
1769 biases: [i16; 3])
1770 -> Result<(), Error<E>> {
1771 let mut new_biases = self.get_unscaled_accel_bias()?;
1772
1773 for i in 0..3 {
1775 if !relative {
1776 new_biases[i] &= 1
1777 }
1778 new_biases[i] += biases[i] & !1;
1779 }
1780
1781 self.dev.write(Register::XA_OFFSET_H,
1782 ((new_biases[0] >> 8) & 0xFF) as u8)?;
1783 self.dev.write(Register::XA_OFFSET_L, (new_biases[0] & 0xFF) as u8)?;
1784 self.dev.write(Register::YA_OFFSET_H,
1785 ((new_biases[1] >> 8) & 0xFF) as u8)?;
1786 self.dev.write(Register::YA_OFFSET_L, (new_biases[1] & 0xFF) as u8)?;
1787 self.dev.write(Register::ZA_OFFSET_H,
1788 ((new_biases[2] >> 8) & 0xFF) as u8)?;
1789 self.dev.write(Register::ZA_OFFSET_L, (new_biases[2] & 0xFF) as u8)?;
1790
1791 Ok(())
1792 }
1793
1794 pub fn set_accel_bias<T>(&mut self,
1799 relative: bool,
1800 biases: T)
1801 -> Result<(), Error<E>>
1802 where T: Into<[f32; 3]>
1803 {
1804 let biases = biases.into();
1805 let scale = G * AccelScale::_16G.resolution();
1806
1807 self.set_unscaled_accel_bias(relative,
1808 [(biases[0] / scale) as i16,
1809 (biases[1] / scale) as i16,
1810 (biases[2] / scale) as i16])
1811 }
1812
1813 fn to_vector(&self, buffer: &[u8], offset: usize) -> [i16; 3] {
1814 [((u16(buffer[offset + 1]) << 8) | u16(buffer[offset + 2])) as i16,
1815 ((u16(buffer[offset + 3]) << 8) | u16(buffer[offset + 4])) as i16,
1816 ((u16(buffer[offset + 5]) << 8) | u16(buffer[offset + 6])) as i16]
1817 }
1818
1819 fn to_vector_inverted(&self, buffer: &[u8], offset: usize) -> [i16; 3] {
1820 [((u16(buffer[offset + 2]) << 8) + u16(buffer[offset + 1])) as i16,
1821 ((u16(buffer[offset + 4]) << 8) + u16(buffer[offset + 3])) as i16,
1822 ((u16(buffer[offset + 6]) << 8) + u16(buffer[offset + 5])) as i16]
1823 }
1824
1825 pub fn who_am_i(&mut self) -> Result<u8, E> {
1827 self.dev.read(Register::WHO_AM_I)
1828 }
1829}
1830
1831impl<DEV, MODE> Mpu9250<DEV, MODE> {
1833 pub fn accel_resolution(&self) -> f32 {
1835 self.accel_scale.resolution()
1836 }
1837
1838 pub fn gyro_resolution(&self) -> f32 {
1840 self.gyro_scale.resolution()
1841 }
1842
1843 pub fn mag_resolution(&self) -> f32 {
1845 self.mag_scale.resolution()
1846 }
1847}
1848
1849pub const MODE: Mode = Mode { polarity: Polarity::IdleHigh,
1851 phase: Phase::CaptureOnSecondTransition };
1852
1853#[allow(dead_code)]
1854#[allow(non_camel_case_types)]
1855#[derive(Clone, Copy)]
1856#[doc(hidden)]
1857pub enum Register {
1858 ACCEL_CONFIG = 0x1c,
1859 ACCEL_CONFIG_2 = 0x1d,
1860 ACCEL_XOUT_H = 0x3b,
1861 ACCEL_YOUT_H = 0x3d,
1862 CONFIG = 0x1a,
1863 XG_OFFSET_H = 0x13, XG_OFFSET_L = 0x14,
1865 YG_OFFSET_H = 0x15,
1866 YG_OFFSET_L = 0x16,
1867 ZG_OFFSET_H = 0x17,
1868 ZG_OFFSET_L = 0x18,
1869 EXT_SENS_DATA_00 = 0x49,
1870 EXT_SENS_DATA_01 = 0x4a,
1871 EXT_SENS_DATA_02 = 0x4b,
1872 EXT_SENS_DATA_03 = 0x4c,
1873 EXT_SENS_DATA_04 = 0x4d,
1874 GYRO_CONFIG = 0x1b,
1875 SMPLRT_DIV = 0x19,
1876 GYRO_XOUT_H = 0x43,
1877 FIFO_EN = 0x23,
1878 I2C_MST_CTRL = 0x24,
1879 I2C_MST_STATUS = 0x36,
1880 I2C_SLV0_ADDR = 0x25,
1881 I2C_SLV0_CTRL = 0x27,
1882 I2C_SLV0_DO = 0x63,
1883 I2C_SLV0_REG = 0x26,
1884 I2C_SLV4_ADDR = 0x31,
1885 I2C_SLV4_CTRL = 0x34,
1886 I2C_SLV4_DI = 0x35,
1887 I2C_SLV4_DO = 0x33,
1888 I2C_SLV4_REG = 0x32,
1889 INT_PIN_CFG = 0x37,
1890 INT_ENABLE = 0x38,
1891 INT_STATUS = 0x3a,
1892 PWR_MGMT_1 = 0x6b,
1893 PWR_MGMT_2 = 0x6c,
1894 TEMP_OUT_H = 0x41,
1895 USER_CTRL = 0x6a,
1896 BANK_SEL = 0x6d,
1897 MEM_ADDR = 0x6e,
1898 MEM_RW = 0x6f,
1899 DMP_START_ADDR = 0x70,
1900 FIFO_COUNT_H = 0x72,
1901 FIFO_RW = 0x74,
1902 WHO_AM_I = 0x75,
1903 XA_OFFSET_H = 0x77,
1904 XA_OFFSET_L = 0x78,
1905 YA_OFFSET_H = 0x7A,
1906 YA_OFFSET_L = 0x7B,
1907 ZA_OFFSET_H = 0x7D,
1908 ZA_OFFSET_L = 0x7E,
1909}
1910
1911const R: u8 = 1 << 7;
1912const W: u8 = 0 << 7;
1913
1914impl Register {
1915 fn read_address(&self) -> u8 {
1916 *self as u8 | R
1917 }
1918
1919 fn write_address(&self) -> u8 {
1920 *self as u8 | W
1921 }
1922}
1923
1924#[allow(dead_code)]
1925#[allow(non_camel_case_types)]
1926#[derive(Clone, Copy)]
1927#[doc(hidden)]
1928pub enum DmpMemory {
1929 CFG_LP_QUAT = 2712,
1930 END_ORIENT_TEMP = 1866,
1931 CFG_27 = 2742,
1932 CFG_20 = 2224,
1933 CFG_23 = 2745,
1934 CFG_FIFO_ON_EVENT = 2690,
1935 END_PREDICTION_UPDATE = 1761,
1936 CGNOTICE_INTR = 2620,
1937 X_GRT_Y_TMP = 1358,
1938 CFG_DR_INT = 1029,
1939 CFG_AUTH = 1035,
1940 UPDATE_PROP_ROT = 1835,
1941 END_COMPARE_Y_X_TMP2 = 1455,
1942 SKIP_X_GRT_Y_TMP = 1359,
1943 SKIP_END_COMPARE = 1435,
1944 FCFG_3 = 1088,
1945 FCFG_2 = 1066,
1946 FCFG_1 = 1062,
1947 END_COMPARE_Y_X_TMP3 = 1434,
1948 FCFG_7 = 1073,
1949 FCFG_6 = 1106,
1950 FLAT_STATE_END = 1713,
1951 SWING_END_4 = 1616,
1952 SWING_END_2 = 1565,
1953 SWING_END_3 = 1587,
1954 SWING_END_1 = 1550,
1955 CFG_8 = 2718,
1956 CFG_15 = 2727,
1957 CFG_16 = 2746,
1958 CFG_EXT_GYRO_BIAS = 1189,
1959 END_COMPARE_Y_X_TMP = 1407,
1960 DO_NOT_UPDATE_PROP_ROT = 1839,
1961 CFG_7 = 1205,
1962 FLAT_STATE_END_TEMP = 1683,
1963 END_COMPARE_Y_X = 1484,
1964 SKIP_SWING_END_1 = 1551,
1965 SKIP_SWING_END_3 = 1588,
1966 SKIP_SWING_END_2 = 1566,
1967 TILTG75_START = 1672,
1968 CFG_6 = 2753,
1969 TILTL75_END = 1669,
1970 END_ORIENT = 1884,
1971 CFG_FLICK_IN = 2573,
1972 TILTL75_START = 1643,
1973 CFG_MOTION_BIAS = 1208,
1974 X_GRT_Y = 1408,
1975 TEMPLABEL = 2324,
1976 CFG_ANDROID_ORIENT_INT = 1853,
1977 CFG_GYRO_RAW_DATA = 2722,
1978 X_GRT_Y_TMP2 = 1379,
1979
1980 D_0_22 = 22 + 512,
1981 D_0_24 = 24 + 512,
1982
1983 D_0_36 = 36,
1984 D_0_96 = 96,
1986 D_0_104 = 104,
1987 D_0_108 = 108,
1988 D_0_163 = 163,
1989 D_0_188 = 188,
1990 D_0_192 = 192,
1991 D_0_224 = 224,
1992 D_0_228 = 228,
1993 D_0_232 = 232,
1994 D_0_236 = 236,
1995
1996 D_1_2 = 256 + 2,
1997 D_1_4 = 256 + 4,
1998 D_1_8 = 256 + 8,
1999 D_1_10 = 256 + 10,
2000 D_1_24 = 256 + 24,
2001 D_1_28 = 256 + 28,
2002 D_1_36 = 256 + 36,
2003 D_1_40 = 256 + 40,
2004 D_1_44 = 256 + 44,
2005 D_1_72 = 256 + 72,
2006 D_1_74 = 256 + 74,
2007 D_1_79 = 256 + 79,
2008 D_1_88 = 256 + 88,
2009 D_1_90 = 256 + 90,
2010 D_1_92 = 256 + 92,
2011 D_1_96 = 256 + 96,
2012 D_1_98 = 256 + 98,
2013 D_1_106 = 256 + 106,
2014 D_1_108 = 256 + 108,
2015 D_1_112 = 256 + 112,
2016 D_1_128 = 256 + 144,
2017 D_1_152 = 256 + 12,
2018 D_1_160 = 256 + 160,
2019 D_1_176 = 256 + 176,
2020 D_1_178 = 256 + 178,
2021 D_1_218 = 256 + 218,
2022 D_1_232 = 256 + 232,
2023 D_1_236 = 256 + 236,
2024 D_1_240 = 256 + 240,
2025 D_1_244 = 256 + 244,
2026 D_1_250 = 256 + 250,
2027 D_1_252 = 256 + 252,
2028 D_2_12 = 512 + 12,
2029 D_2_96 = 512 + 96,
2030 D_2_108 = 512 + 108,
2031 D_2_208 = 512 + 208,
2032 D_2_224 = 512 + 224,
2033 D_2_244 = 512 + 244,
2035 D_2_248 = 512 + 248,
2036 D_2_252 = 512 + 252,
2037
2038 CPASS_BIAS_X = 35 * 16 + 4,
2039 CPASS_BIAS_Y = 35 * 16 + 8,
2040 CPASS_BIAS_Z = 35 * 16 + 12,
2041 CPASS_MTX_00 = 36 * 16,
2042 CPASS_MTX_01 = 36 * 16 + 4,
2043 CPASS_MTX_02 = 36 * 16 + 8,
2044 CPASS_MTX_10 = 36 * 16 + 12,
2045 CPASS_MTX_11 = 37 * 16,
2046 CPASS_MTX_12 = 37 * 16 + 4,
2047 CPASS_MTX_20 = 37 * 16 + 8,
2048 CPASS_MTX_21 = 37 * 16 + 12,
2049 CPASS_MTX_22 = 43 * 16 + 12,
2050 D_EXT_GYRO_BIAS_X = 61 * 16,
2051 D_EXT_GYRO_BIAS_Y = 61 * 16 + 4,
2052 D_EXT_GYRO_BIAS_Z = 61 * 16 + 8,
2053 D_ACT0 = 40 * 16,
2054 D_ACSX = 40 * 16 + 4,
2055 D_ACSY = 40 * 16 + 8,
2056 D_ACSZ = 40 * 16 + 12,
2057
2058 FLICK_MSG = 45 * 16 + 4,
2059 FLICK_COUNTER = 45 * 16 + 8,
2060 FLICK_LOWER = 45 * 16 + 12,
2061 FLICK_UPPER = 46 * 16 + 12,
2062
2063 D_AUTH_OUT = 992,
2064 D_AUTH_IN = 996,
2065 D_AUTH_A = 1000,
2066 D_AUTH_B = 1004,
2067
2068 D_PEDSTD_BP_B = 768 + 0x1C,
2069 D_PEDSTD_HP_A = 768 + 0x78,
2070 D_PEDSTD_HP_B = 768 + 0x7C,
2071 D_PEDSTD_BP_A4 = 768 + 0x40,
2072 D_PEDSTD_BP_A3 = 768 + 0x44,
2073 D_PEDSTD_BP_A2 = 768 + 0x48,
2074 D_PEDSTD_BP_A1 = 768 + 0x4C,
2075 D_PEDSTD_INT_THRSH = 768 + 0x68,
2076 D_PEDSTD_CLIP = 768 + 0x6C,
2077 D_PEDSTD_SB = 768 + 0x28,
2078 D_PEDSTD_SB_TIME = 768 + 0x2C,
2079 D_PEDSTD_PEAKTHRSH = 768 + 0x98,
2080 D_PEDSTD_TIML = 768 + 0x2A,
2081 D_PEDSTD_TIMH = 768 + 0x2E,
2082 D_PEDSTD_PEAK = 768 + 0x94,
2083 D_PEDSTD_STEPCTR = 768 + 0x60,
2084 D_PEDSTD_TIMECTR = 964,
2085 D_PEDSTD_DECI = 768 + 0xA0,
2086
2087 D_ACCEL_BIAS = 660,
2089
2090 D_ORIENT_GAP = 76,
2091
2092 D_TILT0_H = 48,
2093 D_TILT0_L = 50,
2094 D_TILT1_H = 52,
2095 D_TILT1_L = 54,
2096 D_TILT2_H = 56,
2097 D_TILT2_L = 58,
2098 D_TILT3_H = 60,
2099 D_TILT3_L = 62,
2100}
2101
2102impl Into<u16> for DmpMemory {
2103 fn into(self) -> u16 {
2104 self as u16
2105 }
2106}
2107
2108#[derive(Clone, Copy, Debug)]
2110pub struct UnscaledImuMeasurements<T> {
2111 pub accel: T,
2113 pub gyro: T,
2115 pub temp: i16,
2117}
2118
2119#[derive(Clone, Copy, Debug)]
2121pub struct ImuMeasurements<T> {
2122 pub accel: T,
2124 pub gyro: T,
2126 pub temp: f32,
2128}
2129
2130#[derive(Copy, Clone, Debug)]
2132pub struct UnscaledMargMeasurements<T> {
2133 pub accel: T,
2135 pub gyro: T,
2137 pub mag: T,
2139 pub temp: i16,
2141}
2142
2143#[derive(Copy, Clone, Debug)]
2146pub struct MargMeasurements<T> {
2147 pub accel: T,
2149 pub gyro: T,
2151 pub mag: T,
2153 pub temp: f32,
2155}
2156
2157#[derive(Copy, Clone, Debug)]
2163pub struct UnscaledDmpMeasurement<T1, T2> {
2164 pub quaternion: Option<T2>,
2166 pub accel: Option<T1>,
2168 pub gyro: Option<T1>,
2170}
2171
2172#[derive(Copy, Clone, Debug)]
2178pub struct DmpMeasurement<T1, T2> {
2179 pub quaternion: Option<T2>,
2181 pub accel: Option<T1>,
2183 pub gyro: Option<T1>,
2185}
2186
2187fn transpose<T, E>(o: Option<Result<T, E>>) -> Result<Option<T>, E> {
2188 match o {
2189 Some(Ok(x)) => Ok(Some(x)),
2190 Some(Err(e)) => Err(e),
2191 None => Ok(None),
2192 }
2193}
2194
2195fn u16(u: u8) -> u16 {
2196 return u as u16;
2197}