1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606 1607 1608 1609 1610 1611 1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634 1635 1636 1637 1638 1639 1640 1641 1642 1643 1644 1645 1646 1647 1648 1649 1650 1651 1652 1653 1654 1655 1656 1657 1658 1659 1660 1661 1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678 1679 1680 1681 1682 1683 1684 1685 1686 1687 1688 1689 1690 1691 1692 1693 1694 1695 1696 1697 1698 1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716 1717 1718 1719 1720 1721 1722 1723 1724 1725 1726 1727 1728 1729 1730 1731 1732 1733 1734 1735 1736 1737 1738 1739 1740 1741 1742 1743 1744 1745 1746 1747 1748 1749 1750 1751 1752 1753 1754 1755 1756 1757 1758 1759 1760 1761 1762 1763 1764 1765 1766 1767 1768 1769 1770 1771 1772 1773 1774 1775 1776 1777 1778 1779 1780 1781 1782 1783 1784 1785 1786 1787 1788 1789 1790 1791 1792 1793 1794 1795 1796 1797 1798 1799 1800 1801 1802 1803 1804 1805 1806 1807 1808 1809 1810 1811 1812 1813 1814 1815 1816 1817 1818 1819 1820 1821 1822 1823 1824 1825 1826 1827 1828 1829 1830 1831 1832 1833 1834 1835 1836 1837 1838 1839 1840 1841 1842 1843 1844 1845 1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858 1859 1860 1861 1862 1863 1864 1865 1866 1867 1868 1869 1870 1871 1872 1873 1874 1875 1876 1877 1878 1879 1880 1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895 1896 1897 1898 1899 1900 1901 1902 1903 1904 1905 1906 1907 1908 1909 1910 1911 1912 1913 1914 1915 1916 1917 1918 1919 1920 1921 1922 1923 1924 1925 1926 1927 1928 1929 1930 1931 1932 1933 1934 1935 1936 1937 1938 1939 1940 1941 1942 1943 1944 1945 1946 1947 1948 1949 1950 1951 1952 1953 1954 1955 1956 1957 1958 1959 1960 1961 1962 1963 1964 1965 1966 1967 1968 1969 1970 1971 1972 1973 1974 1975 1976 1977 1978 1979 1980 1981 1982 1983 1984 1985 1986 1987 1988 1989 1990 1991 1992 1993 1994 1995 1996 1997 1998 1999 2000 2001 2002 2003 2004 2005 2006 2007 2008 2009 2010 2011 2012 2013 2014 2015 2016 2017 2018 2019 2020 2021 2022 2023 2024 2025 2026 2027 2028 2029 2030 2031 2032 2033 2034 2035 2036 2037 2038 2039 2040 2041 2042 2043 2044 2045 2046 2047 2048 2049 2050 2051 2052 2053 2054 2055 2056 2057 2058 2059 2060 2061 2062 2063 2064 2065 2066 2067 2068 2069 2070 2071 2072 2073 2074 2075 2076 2077 2078 2079 2080 2081 2082 2083 2084 2085 2086 2087 2088 2089 2090 2091 2092 2093 2094 2095 2096 2097 2098 2099 2100 2101 2102 2103 2104 2105 2106 2107 2108 2109 2110 2111 2112 2113 2114 2115 2116 2117 2118 2119 2120 2121 2122 2123 2124 2125 2126 2127 2128 2129 2130 2131 2132 2133 2134 2135 2136 2137 2138 2139 2140 2141 2142 2143 2144 2145 2146 2147 2148 2149 2150 2151 2152 2153 2154 2155 2156 2157 2158 2159 2160 2161 2162 2163 2164 2165 2166 2167 2168 2169 2170 2171 2172 2173 2174 2175 2176 2177 2178 2179 2180 2181 2182 2183 2184 2185 2186 2187 2188 2189 2190 2191 2192 2193 2194 2195 2196 2197
//! no_std driver for the MPU9250 & onboard AK8963 (accelerometer + gyroscope +
//! magnetometer IMU)
//!
//! # Connections
//!
//! - NCS
//! - SCL = SCK
//! - SDA = SDI = MOSI
//! - AD0 = SDO = MISO
//!
//! # Usage
//!
//! Use embedded-hal implementation to get SPI, NCS, and delay, then create mpu
//! handle
//!
//! ```
//! // to create sensor with mag support and default configuration:
//! let mut mpu = Mpu9250::marg_default(spi, ncs, &mut delay)?;
//! // to create sensor without mag support and default configuration:
//! let mut mpu = Mpu9250::imu_default(spi, ncs, &mut delay)?;
//! // to get all supported measurements:
//! let all = mpu.all()?;
//! println!("{:?}", all);
//! // One can also use conf module to supply configuration:
//! let mut mpu =
//! Mpu9250::marg(spi,
//! ncs,
//! &mut delay,
//! MpuConfig::marg().mag_scale(conf::MagScale::_14BITS))?;
//! ```
//!
//! More examples (for stm32) in [Proving ground] repo.
//!
//! # References
//!
//! - [Product specification][2]
//!
//! [1]: https://www.invensense.com/wp-content/uploads/2015/02/PS-MPU-9250A-01-v1.1.pdf
//!
//! - [Register map][2]
//!
//! [2]: https://www.invensense.com/wp-content/uploads/2015/02/RM-MPU-9250A-00-v1.6.pdf
//!
//! - [AK8963 specification][3]
//!
//! [3]: https://www.akm.com/akm/en/file/datasheet/AK8963C.pdf
//!
//! - [Proving ground][4]
//!
//! [4]: https://github.com/copterust/proving-ground
#![deny(missing_docs)]
#![no_std]
#[macro_use]
extern crate bitflags;
extern crate embedded_hal as hal;
mod ak8963;
mod conf;
mod device;
mod types;
#[cfg(feature = "dmp")]
mod dmp_firmware;
#[cfg(feature = "dmp")]
pub use dmp_firmware::DMP_FIRMWARE;
use ak8963::AK8963;
use core::marker::PhantomData;
use hal::blocking::delay::DelayMs;
use hal::spi::{Mode, Phase, Polarity};
pub use conf::*;
pub use types::*;
#[doc(hidden)]
pub use device::Releasable;
pub use device::{
Device, I2CError, I2cDevice, NineDOFDevice, SpiDevice, SpiError
};
/// Suported MPUx devices
pub enum MpuXDevice {
/// MPU 9250
MPU9250 = 0x71,
/// MPU 9255
MPU9255 = 0x73,
/// MPU 6500
MPU6500 = 0x70,
}
impl MpuXDevice {
fn imu_supported(b: u8) -> bool {
b == (MpuXDevice::MPU9250 as u8)
|| b == (MpuXDevice::MPU9255 as u8)
|| b == (MpuXDevice::MPU6500 as u8)
}
fn marg_supported(b: u8) -> bool {
b == (MpuXDevice::MPU9250 as u8) || b == (MpuXDevice::MPU9255 as u8)
}
}
/// MPU9250 driver
pub struct Mpu9250<DEV, MODE> {
// connections
dev: DEV,
// data; factory defaults.
mag_sensitivity_adjustments: [f32; 3],
raw_mag_sensitivity_adjustments: [u8; 3],
// configuration
gyro_scale: GyroScale,
accel_scale: AccelScale,
mag_scale: MagScale,
gyro_temp_data_rate: GyroTempDataRate,
accel_data_rate: AccelDataRate,
sample_rate_divisor: Option<u8>,
dmp_configuration: Option<DmpConfiguration>,
packet_size: usize,
// mode
_mode: PhantomData<MODE>,
}
/// MPU Error
#[derive(Debug, Copy, Clone)]
pub enum Error<E> {
/// WHO_AM_I returned invalid value (returned value is argument).
InvalidDevice(u8),
/// Mode not supported by device (WHO_AM_I is argument)
ModeNotSupported(u8),
/// Underlying bus error.
BusError(E),
/// Calibration error (not enough data gathered)
CalibrationError,
/// Reinitialization error (user provided function was unable to re-init
/// device)
ReInitError,
/// DMP read internal memory error
DmpRead,
/// DMP write internal memory error
DmpWrite,
/// DMP firmware loading error
DmpFirmware,
/// DMP data are not ready yet
DmpDataNotReady,
/// DMP data do not correspond to the expected format
DmpDataInvalid,
}
impl<E> core::convert::From<E> for Error<E> {
fn from(error: E) -> Self {
Error::BusError(error)
}
}
// 2 for 8 Hz, 6 for 100 Hz continuous magnetometer data read
const MMODE: u8 = 0x06;
/// G constant
pub const G: f32 = 9.807;
const PI_180: f32 = core::f32::consts::PI / 180.;
const TEMP_SENSITIVITY: f32 = 333.87;
const TEMP_DIFF: f32 = 21.0;
const TEMP_ROOM_OFFSET: f32 = 0.0;
/// SPI device definitions
#[cfg(not(feature = "i2c"))]
mod spi_defs {
use super::*;
use hal::blocking::spi;
use hal::digital::v2::OutputPin;
// SPI device, 6DOF
impl<E, SPI, NCS> Mpu9250<SpiDevice<SPI, NCS>, Imu>
where SPI: spi::Write<u8, Error = E> + spi::Transfer<u8, Error = E>,
NCS: OutputPin
{
/// Creates a new [`Imu`] driver from a SPI peripheral and a NCS pin
/// with default configuration.
pub fn imu_default<D>(
spi: SPI,
ncs: NCS,
delay: &mut D)
-> Result<Self,
Error<<SpiDevice<SPI, NCS> as device::Device>::Error>>
where D: DelayMs<u8>
{
Self::imu(spi, ncs, delay, &mut MpuConfig::imu())
}
/// Creates a new Imu driver from a SPI peripheral and a NCS pin with
/// provided configuration [`Config`].
///
/// [`Config`]: ./conf/struct.MpuConfig.html
pub fn imu<D>(
spi: SPI,
ncs: NCS,
delay: &mut D,
config: &mut MpuConfig<Imu>)
-> Result<Self,
Error<<SpiDevice<SPI, NCS> as device::Device>::Error>>
where D: DelayMs<u8>
{
let dev = SpiDevice::new(spi, ncs);
Self::new_imu(dev, delay, config)
}
/// 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."
///
/// [`Config`]: ./conf/struct.MpuConfig.html
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::Device>::Error>>
where D: DelayMs<u8>,
F: FnOnce(SPI, NCS) -> Option<(SPI, NCS)>
{
let dev = SpiDevice::new(spi, ncs);
let mpu = Self::new_imu(dev, delay, config)?;
mpu.reinit_spi_device(reinit_fn)
}
}
// SPI device, 9 DOF
impl<E, SPI, NCS> Mpu9250<SpiDevice<SPI, NCS>, Marg>
where SPI: spi::Write<u8, Error = E> + spi::Transfer<u8, Error = E>,
NCS: OutputPin
{
/// Creates a new [`Marg`] driver from a SPI peripheral and a NCS pin
/// with default [`Config`].
///
/// [`Config`]: ./conf/struct.MpuConfig.html
pub fn marg_default<D>(
spi: SPI,
ncs: NCS,
delay: &mut D)
-> Result<Self,
Error<<SpiDevice<SPI, NCS> as device::Device>::Error>>
where D: DelayMs<u8>
{
Mpu9250::marg(spi, ncs, delay, &mut MpuConfig::marg())
}
/// Creates a new MARG driver from a SPI peripheral and a NCS pin
/// with provided configuration [`Config`].
///
/// [`Config`]: ./conf/struct.MpuConfig.html
pub fn marg<D>(
spi: SPI,
ncs: NCS,
delay: &mut D,
config: &mut MpuConfig<Marg>)
-> Result<Self,
Error<<SpiDevice<SPI, NCS> as device::Device>::Error>>
where D: DelayMs<u8>
{
let dev = SpiDevice::new(spi, ncs);
Self::new_marg(dev, delay, config)
}
/// 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."
///
/// [`Config`]: ./conf/struct.MpuConfig.html
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::Device>::Error>>
where D: DelayMs<u8>,
F: FnOnce(SPI, NCS) -> Option<(SPI, NCS)>
{
let dev = SpiDevice::new(spi, ncs);
let mpu = Self::new_marg(dev, delay, config)?;
mpu.reinit_spi_device(reinit_fn)
}
}
#[cfg(feature = "dmp")]
impl<E, SPI, NCS> Mpu9250<SpiDevice<SPI, NCS>, Dmp>
where SPI: spi::Write<u8, Error = E> + spi::Transfer<u8, Error = E>,
NCS: OutputPin
{
/// Create a new dmp device with default configuration
pub fn dmp_default<D>(
spi: SPI,
ncs: NCS,
delay: &mut D,
firmware: &[u8])
-> Result<Self,
Error<<SpiDevice<SPI, NCS> as device::Device>::Error>>
where D: DelayMs<u8>
{
let dev = SpiDevice::new(spi, ncs);
Self::new_dmp(dev, delay, &mut MpuConfig::dmp(), firmware)
}
/// Create a new dmp device
pub fn dmp<D>(
spi: SPI,
ncs: NCS,
delay: &mut D,
config: &mut MpuConfig<Dmp>,
firmware: &[u8])
-> Result<Self,
Error<<SpiDevice<SPI, NCS> as device::Device>::Error>>
where D: DelayMs<u8>
{
let dev = SpiDevice::new(spi, ncs);
Self::new_dmp(dev, delay, config, firmware)
}
}
// SPI device, any mode
impl<E, SPI, NCS, MODE> Mpu9250<SpiDevice<SPI, NCS>, MODE>
where SPI: spi::Write<u8, Error = E> + spi::Transfer<u8, Error = E>,
NCS: OutputPin
{
/// Destroys the driver recovering the SPI peripheral and the NCS pin
pub fn release(self) -> (SPI, NCS) {
self.dev.release()
}
fn reinit_spi_device<F>(
self,
reinit_fn: F)
-> Result<Self,
Error<<SpiDevice<SPI, NCS> as device::Device>::Error>>
where F: FnOnce(SPI, NCS) -> Option<(SPI, NCS)>
{
self.reset_device(|spidev| {
let (cspi, cncs) = spidev.release();
reinit_fn(cspi, cncs).map(|(nspi, nncs)| {
SpiDevice::new(nspi, nncs)
})
})
}
}
}
#[cfg(not(feature = "i2c"))]
pub use spi_defs::*;
#[cfg(feature = "i2c")]
mod i2c_defs {
use super::*;
use hal::blocking::i2c;
impl<E, I2C> Mpu9250<I2cDevice<I2C>, Imu>
where I2C: i2c::Read<Error = E>
+ i2c::Write<Error = E>
+ i2c::WriteRead<Error = E>
{
/// Creates a new [`Imu`] driver from an I2C peripheral
/// with default configuration.
pub fn imu_default<D>(
i2c: I2C,
delay: &mut D)
-> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
where D: DelayMs<u8>
{
Mpu9250::imu(i2c, delay, &mut MpuConfig::imu())
}
/// Creates a new Imu driver from an I2C peripheral with the
/// provided configuration [`Config`].
///
/// [`Config`]: ./conf/struct.MpuConfig.html
pub fn imu<D>(
i2c: I2C,
delay: &mut D,
config: &mut MpuConfig<Imu>)
-> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
where D: DelayMs<u8>
{
let dev = I2cDevice::new(i2c);
Mpu9250::new_imu(dev, delay, config)
}
/// Creates a new IMU driver from an I2C peripheral
/// with provided configuration [`Config`]. Reinit function can be used
/// to re-initialize I2C bus. Usecase: change I2C speed for
/// faster data transfer.
///
/// [`Config`]: ./conf/struct.MpuConfig.html
pub fn imu_with_reinit<D, F>(
i2c: I2C,
delay: &mut D,
config: &mut MpuConfig<Imu>,
reinit_fn: F)
-> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
where D: DelayMs<u8>,
F: FnOnce(I2C) -> Option<I2C>
{
let dev = I2cDevice::new(i2c);
let mpu = Self::new_imu(dev, delay, config)?;
mpu.reinit_i2c_device(reinit_fn)
}
}
impl<E, I2C> Mpu9250<I2cDevice<I2C>, Marg>
where I2C: i2c::Read<Error = E>
+ i2c::Write<Error = E>
+ i2c::WriteRead<Error = E>
{
/// Creates a new [`Marg`] driver from an I2C peripheral with
/// default [`Config`].
///
/// [`Config`]: ./conf/struct.MpuConfig.html
pub fn marg_default<D>(
i2c: I2C,
delay: &mut D)
-> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
where D: DelayMs<u8>
{
Mpu9250::marg(i2c, delay, &mut MpuConfig::marg())
}
/// Creates a new MARG driver from an I2C peripheral
/// with provided configuration [`Config`].
///
/// [`Config`]: ./conf/struct.MpuConfig.html
pub fn marg<D>(
i2c: I2C,
delay: &mut D,
config: &mut MpuConfig<Marg>)
-> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
where D: DelayMs<u8>
{
let dev = I2cDevice::new(i2c);
Self::new_marg(dev, delay, config)
}
/// Creates a new MARG driver from an I2C peripheral
/// with provided configuration [`Config`]. Reinit function can be used
/// to re-initialize I2C bus. Usecase: change I2C speed for
/// faster data transfer.
///
/// [`Config`]: ./conf/struct.MpuConfig.html
pub fn marg_with_reinit<D, F>(
i2c: I2C,
delay: &mut D,
config: &mut MpuConfig<Marg>,
reinit_fn: F)
-> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
where D: DelayMs<u8>,
F: FnOnce(I2C) -> Option<I2C>
{
let dev = I2cDevice::new(i2c);
let mpu = Self::new_marg(dev, delay, config)?;
mpu.reinit_i2c_device(reinit_fn)
}
}
#[cfg(feature = "dmp")]
impl<E, I2C> Mpu9250<I2cDevice<I2C>, Dmp>
where I2C: i2c::Read<Error = E>
+ i2c::Write<Error = E>
+ i2c::WriteRead<Error = E>
{
/// Creates a new DMP driver from an I2C peripheral with default
/// configuration
pub fn dmp_default<D>(
i2c: I2C,
delay: &mut D,
firmware: &[u8])
-> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
where D: DelayMs<u8>
{
let dev = I2cDevice::new(i2c);
Self::new_dmp(dev, delay, &mut MpuConfig::dmp(), firmware)
}
/// Creates a new DMP driver from an I2C peripheral
pub fn dmp<D>(
i2c: I2C,
delay: &mut D,
config: &mut MpuConfig<Dmp>,
firmware: &[u8])
-> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
where D: DelayMs<u8>
{
let dev = I2cDevice::new(i2c);
Self::new_dmp(dev, delay, config, firmware)
}
}
// I2C device, any mode
impl<E, I2C, MODE> Mpu9250<I2cDevice<I2C>, MODE>
where I2C: i2c::Read<Error = E>
+ i2c::Write<Error = E>
+ i2c::WriteRead<Error = E>
{
/// Destroys the driver, recovering the I2C peripheral
pub fn release(self) -> I2C {
self.dev.release()
}
fn reinit_i2c_device<F>(
self,
reinit_fn: F)
-> Result<Self, Error<<I2cDevice<I2C> as device::Device>::Error>>
where F: FnOnce(I2C) -> Option<I2C>
{
self.reset_device(|i2cdev| {
let i2c = i2cdev.release();
reinit_fn(i2c).map(|i2c| I2cDevice::new(i2c))
})
}
}
}
#[cfg(feature = "i2c")]
pub use i2c_defs::*;
// Any device, 6DOF
impl<E, DEV> Mpu9250<DEV, Imu> where DEV: Device<Error = E>
{
/// Private constructor that creates an IMU-based MPU with the
/// specified device.
fn new_imu<D>(dev: DEV,
delay: &mut D,
config: &mut MpuConfig<Imu>)
-> Result<Self, Error<E>>
where D: DelayMs<u8>
{
let mut mpu9250 =
Mpu9250 { dev,
raw_mag_sensitivity_adjustments: [0; 3],
mag_sensitivity_adjustments: [0.0; 3],
gyro_scale: config.gyro_scale.unwrap_or_default(),
accel_scale: config.accel_scale.unwrap_or_default(),
mag_scale: MagScale::default(),
accel_data_rate: config.accel_data_rate
.unwrap_or_default(),
gyro_temp_data_rate: config.gyro_temp_data_rate
.unwrap_or_default(),
sample_rate_divisor: config.sample_rate_divisor,
dmp_configuration: config.dmp_configuration,
packet_size: 0,
_mode: PhantomData };
mpu9250.init_mpu(delay)?;
let wai = mpu9250.who_am_i()?;
if MpuXDevice::imu_supported(wai) {
Ok(mpu9250)
} else {
Err(Error::InvalidDevice(wai))
}
}
/// Configures device using provided [`MpuConfig`].
pub fn config(&mut self, config: &mut MpuConfig<Imu>) -> Result<(), E> {
transpose(config.gyro_scale.map(|v| self.gyro_scale(v)))?;
transpose(config.accel_scale.map(|v| self.accel_scale(v)))?;
transpose(config.accel_data_rate.map(|v| self.accel_data_rate(v)))?;
transpose(config.gyro_temp_data_rate
.map(|v| self.gyro_temp_data_rate(v)))?;
transpose(config.sample_rate_divisor
.map(|v| self.sample_rate_divisor(v)))?;
Ok(())
}
/// Reads and returns raw unscaled Accelerometer + Gyroscope + Thermometer
/// measurements (LSB).
pub fn unscaled_all<T>(&mut self) -> Result<UnscaledImuMeasurements<T>, E>
where T: From<[i16; 3]>
{
let buffer = &mut [0; 15];
self.dev.read_many(Register::ACCEL_XOUT_H, &mut buffer[..])?;
let accel = self.to_vector(buffer, 0).into();
let temp = ((u16(buffer[7]) << 8) | u16(buffer[8])) as i16;
let gyro = self.to_vector(buffer, 8).into();
Ok(UnscaledImuMeasurements { accel,
gyro,
temp })
}
/// Reads and returns Accelerometer + Gyroscope + Thermometer
/// measurements scaled and converted to respective units.
pub fn all<T>(&mut self) -> Result<ImuMeasurements<T>, E>
where T: From<[f32; 3]>
{
let buffer = &mut [0; 15];
self.dev.read_many(Register::ACCEL_XOUT_H, &mut buffer[..])?;
let accel = self.scale_accel(buffer, 0).into();
let temp = self.scale_temp(buffer, 6);
let gyro = self.scale_gyro(buffer, 8).into();
Ok(ImuMeasurements { accel,
gyro,
temp })
}
/// 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.
pub fn calibrate_at_rest<D, T>(&mut self,
delay: &mut D)
-> Result<T, Error<E>>
where D: DelayMs<u8>,
T: From<[f32; 3]>
{
Ok(self._calibrate_at_rest(delay)?.into())
}
}
// Any device, 9DOF
impl<E, DEV> Mpu9250<DEV, Marg>
where DEV: Device<Error = E> + AK8963<Error = E> + NineDOFDevice
{
// Private constructor that creates a MARG-based MPU with
// the specificed device.
fn new_marg<D>(dev: DEV,
delay: &mut D,
config: &mut MpuConfig<Marg>)
-> Result<Self, Error<E>>
where D: DelayMs<u8>
{
let mut mpu9250 =
Mpu9250 { dev,
raw_mag_sensitivity_adjustments: [0; 3],
mag_sensitivity_adjustments: [0.0; 3],
gyro_scale: config.gyro_scale.unwrap_or_default(),
accel_scale: config.accel_scale.unwrap_or_default(),
mag_scale: config.mag_scale.unwrap_or_default(),
accel_data_rate: config.accel_data_rate
.unwrap_or_default(),
gyro_temp_data_rate: config.gyro_temp_data_rate
.unwrap_or_default(),
sample_rate_divisor: config.sample_rate_divisor,
dmp_configuration: config.dmp_configuration,
packet_size: 0,
_mode: PhantomData };
mpu9250.init_mpu(delay)?;
let wai = mpu9250.who_am_i()?;
if MpuXDevice::marg_supported(wai) {
mpu9250.init_ak8963(delay)?;
mpu9250.check_ak8963_who_am_i()?;
Ok(mpu9250)
} else if wai == MpuXDevice::MPU6500 as u8 {
Err(Error::ModeNotSupported(wai))
} else {
Err(Error::InvalidDevice(wai))
}
}
/// 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.
pub fn calibrate_at_rest<D, T>(&mut self,
delay: &mut D)
-> Result<T, Error<E>>
where D: DelayMs<u8>,
T: From<[f32; 3]>
{
let accel_biases = self._calibrate_at_rest(delay)?;
self.init_ak8963(delay)?;
Ok(accel_biases.into())
}
fn init_ak8963<D>(&mut self, delay: &mut D) -> Result<(), E>
where D: DelayMs<u8>
{
AK8963::init(&mut self.dev, delay)?;
delay.delay_ms(10);
// First extract the factory calibration for each magnetometer axis
// Power down
AK8963::write(&mut self.dev, ak8963::Register::CNTL1, 0x00)?;
delay.delay_ms(10);
// Fuse ROM access mode
AK8963::write(&mut self.dev, ak8963::Register::CNTL1, 0x0F)?;
delay.delay_ms(20);
let mag_x_bias = AK8963::read(&mut self.dev, ak8963::Register::ASAX)?;
let mag_y_bias = AK8963::read(&mut self.dev, ak8963::Register::ASAY)?;
let mag_z_bias = AK8963::read(&mut self.dev, ak8963::Register::ASAZ)?;
// Return x-axis sensitivity adjustment values, etc.
self.raw_mag_sensitivity_adjustments =
[mag_x_bias, mag_y_bias, mag_z_bias];
self.mag_sensitivity_adjustments =
[((mag_x_bias - 128) as f32) / 256. + 1.,
((mag_y_bias - 128) as f32) / 256. + 1.,
((mag_z_bias - 128) as f32) / 256. + 1.];
// Power down magnetometer
AK8963::write(&mut self.dev, ak8963::Register::CNTL1, 0x00)?;
delay.delay_ms(10);
// Set magnetometer data resolution and sample ODR
self._mag_scale()?;
delay.delay_ms(10);
AK8963::finalize(&mut self.dev, delay)?;
Ok(())
}
/// Configures device using provided [`MpuConfig`].
pub fn config(&mut self, config: &mut MpuConfig<Marg>) -> Result<(), E> {
transpose(config.gyro_scale.map(|v| self.gyro_scale(v)))?;
transpose(config.accel_scale.map(|v| self.accel_scale(v)))?;
transpose(config.mag_scale.map(|v| self.mag_scale(v)))?;
transpose(config.accel_data_rate.map(|v| self.accel_data_rate(v)))?;
transpose(config.gyro_temp_data_rate
.map(|v| self.gyro_temp_data_rate(v)))?;
transpose(config.sample_rate_divisor
.map(|v| self.sample_rate_divisor(v)))?;
Ok(())
}
/// Reads and returns raw unscaled Accelerometer + Gyroscope + Thermometer
/// + Magnetometer measurements (LSB).
pub fn unscaled_all<T>(&mut self) -> Result<UnscaledMargMeasurements<T>, E>
where T: From<[i16; 3]>
{
let buffer = &mut [0; 21];
NineDOFDevice::read_9dof(&mut self.dev,
Register::ACCEL_XOUT_H,
buffer)?;
let accel = self.to_vector(buffer, 0).into();
let temp = ((u16(buffer[7]) << 8) | u16(buffer[8])) as i16;
let gyro = self.to_vector(buffer, 8).into();
let mag = self.to_vector_inverted(buffer, 14).into();
Ok(UnscaledMargMeasurements { accel,
gyro,
temp,
mag })
}
/// Reads and returns Accelerometer + Gyroscope + Thermometer + Magnetometer
/// measurements scaled and converted to respective units.
pub fn all<T>(&mut self) -> Result<MargMeasurements<T>, E>
where T: From<[f32; 3]>
{
let buffer = &mut [0; 21];
NineDOFDevice::read_9dof(&mut self.dev,
Register::ACCEL_XOUT_H,
buffer)?;
let accel = self.scale_accel(buffer, 0).into();
let temp = self.scale_temp(buffer, 6);
let gyro = self.scale_gyro(buffer, 8).into();
let mag = self.scale_and_correct_mag(buffer, 14).into();
Ok(MargMeasurements { accel,
gyro,
temp,
mag })
}
/// Perform magnetometer self-test
///
/// Measure magnetic field generated by internal magnetic source.
/// Note that this would leave device in power-down mode.
pub fn magnetometer_healthy(&mut self) -> Result<bool, E> {
let buffer = &mut [0; 7];
// (1) Set Power-down mode. (MODE[3:0]=“0000”)
let control =
AK8963::read(&mut self.dev, ak8963::Register::CNTL1)? & 0b11110000;
AK8963::write(&mut self.dev, ak8963::Register::CNTL1, control)?;
// (2) Write “1” to SELF bit of ASTC register (other bits in this
// register should be kept “0”)
AK8963::write(&mut self.dev, ak8963::Register::ASTC, 0b01000000)?;
// (3) Set Self-test Mode. (MODE[3:0]=“1000”)
AK8963::write(&mut self.dev,
ak8963::Register::CNTL1,
control | 0b00001000)?;
// (4) Check Data Ready or not by any of the following method.
// - Polling DRDY bit of ST1 register
while AK8963::read(&mut self.dev, ak8963::Register::ST1)? & 0b00000001
!= 0
{}
// When Data Ready, proceed to the next step.
// (5) Read measurement data (HXL to HZH)
self.dev.read_xyz(buffer)?;
// (6) Write “0” to SELF bit of ASTC register
AK8963::write(&mut self.dev, ak8963::Register::ASTC, 0x00)?;
// (7) Set Power-down mode. (MODE[3:0]=“0000”)
AK8963::write(&mut self.dev, ak8963::Register::CNTL1, control)?;
// When measurement data read by the above sequence is in the range
// of following table after sensitivity adjustment (refer to 8.3.11),
// AK8963 is working normally
let measurements = self.to_vector_inverted(buffer, 0);
let range = if (control & 0b00010000) != 0 {
200.0
} else {
50.0
};
for i in 0..3 {
let adjusted_measurement =
measurements[i] as f32 * self.mag_sensitivity_adjustments[i];
if !(adjusted_measurement < -range || adjusted_measurement > range)
{
return Ok(false);
}
}
Ok(true)
}
fn scale_and_correct_mag(&self, buffer: &[u8], offset: usize) -> [f32; 3] {
let resolution = self.mag_scale.resolution();
let raw = self.to_vector_inverted(buffer, offset);
[raw[0] as f32 * resolution * self.mag_sensitivity_adjustments[0],
raw[1] as f32 * resolution * self.mag_sensitivity_adjustments[1],
raw[2] as f32 * resolution * self.mag_sensitivity_adjustments[2]]
}
/// Reads and returns raw unscaled Magnetometer measurements (LSB).
pub fn unscaled_mag<T>(&mut self) -> Result<T, E>
where T: From<[i16; 3]>
{
let buffer = &mut [0; 7];
self.dev.read_xyz(buffer)?;
Ok(self.to_vector_inverted(buffer, 0).into())
}
/// Read and returns Magnetometer measurements scaled, adjusted for factory
/// sensitivities, and converted to microTeslas.
pub fn mag<T>(&mut self) -> Result<T, E>
where T: From<[f32; 3]>
{
let buffer = &mut [0; 7];
self.dev.read_xyz(buffer)?;
Ok(self.scale_and_correct_mag(buffer, 0).into())
}
/// Returns raw mag sensitivity adjustments
pub fn raw_mag_sensitivity_adjustments<T>(&self) -> T
where T: From<[u8; 3]>
{
self.raw_mag_sensitivity_adjustments.into()
}
/// Returns mag sensitivity adjustments
pub fn mag_sensitivity_adjustments<T>(&self) -> T
where T: From<[f32; 3]>
{
self.mag_sensitivity_adjustments.into()
}
/// Configures magnetrometer full reading scale ([`MagScale`])
///
/// [`Mag scale`]: ./conf/enum.MagScale.html
pub fn mag_scale(&mut self, scale: MagScale) -> Result<(), E> {
self.mag_scale = scale;
self._mag_scale()
}
fn _mag_scale(&mut self) -> Result<(), E> {
// Set magnetometer data resolution and sample ODR
let scale = self.mag_scale as u8;
AK8963::write(&mut self.dev,
ak8963::Register::CNTL1,
scale << 4 | MMODE)?;
Ok(())
}
fn check_ak8963_who_am_i(&mut self) -> Result<(), Error<E>> {
let ak8963_who_am_i = self.ak8963_who_am_i()?;
if ak8963_who_am_i == 0x48 {
Ok(())
} else {
Err(Error::InvalidDevice(ak8963_who_am_i))
}
}
/// Reads the AK8963 (magnetometer) WHO_AM_I register; should return `0x48`
pub fn ak8963_who_am_i(&mut self) -> Result<u8, E> {
AK8963::read(&mut self.dev, ak8963::Register::WHO_AM_I)
}
}
// Any device, DMP
#[cfg(feature = "dmp")]
impl<E, DEV> Mpu9250<DEV, Dmp> where DEV: Device<Error = E>
{
/// Private constructor that creates a DMP-based MPU with the
/// specified device.
fn new_dmp<D>(dev: DEV,
delay: &mut D,
config: &mut MpuConfig<Dmp>,
firmware: &[u8])
-> Result<Self, Error<E>>
where D: DelayMs<u8>
{
let mut mpu9250 =
Mpu9250 { dev,
raw_mag_sensitivity_adjustments: [0; 3],
mag_sensitivity_adjustments: [0.0; 3],
gyro_scale: config.gyro_scale
.unwrap_or(GyroScale::_2000DPS),
accel_scale: config.accel_scale
.unwrap_or(AccelScale::_8G),
mag_scale: config.mag_scale.unwrap_or_default(),
accel_data_rate:
config.accel_data_rate
.unwrap_or(AccelDataRate::DlpfConf(Dlpf::_1)),
gyro_temp_data_rate:
config.gyro_temp_data_rate
.unwrap_or(GyroTempDataRate::DlpfConf(Dlpf::_1)),
sample_rate_divisor: config.sample_rate_divisor
.or(Some(4)),
dmp_configuration: Some(config.dmp_configuration
.unwrap_or_default()),
packet_size: config.dmp_configuration
.unwrap_or_default()
.features
.packet_size(),
_mode: PhantomData };
mpu9250.init_mpu(delay)?;
mpu9250.init_dmp(delay, firmware)?;
Ok(mpu9250)
}
/// Logic to init the dmp
fn init_dmp<D>(&mut self,
delay: &mut D,
firmware: &[u8])
-> Result<(), Error<E>>
where D: DelayMs<u8>
{
let conf = self.dmp_configuration.unwrap_or_default();
// disable i2c master mode and enable fifo
const FIFO_EN: u8 = 1 << 6;
self.dev.write(Register::USER_CTRL, FIFO_EN)?;
delay.delay_ms(3);
// enable i2c bypass
self.interrupt_config(InterruptConfig::LATCH_INT_EN
| InterruptConfig::INT_ANYRD_CLEAR
| InterruptConfig::ACL
| InterruptConfig::BYPASS_EN)?;
// load firmware
self.load_firmware(firmware)?;
// load orientation
self.write_mem(DmpMemory::FCFG_1, &conf.orientation.gyro_axes())?;
self.write_mem(DmpMemory::FCFG_2, &conf.orientation.accel_axes())?;
self.write_mem(DmpMemory::FCFG_3, &conf.orientation.gyro_signs())?;
self.write_mem(DmpMemory::FCFG_7, &conf.orientation.accel_signs())?;
// set dmp features
self.set_dmp_feature(delay)?;
let div = [0, conf.rate as u8];
self.write_mem(DmpMemory::D_0_22, &div)?;
self.write_mem(DmpMemory::CFG_6,
&[0xfe, 0xf2, 0xab, 0xc4, 0xaa, 0xf1, 0xdf, 0xdf,
0xbb, 0xaf, 0xdf, 0xdf])?;
// turn on the dmp
self.dev.write(Register::INT_ENABLE, 0)?;
self.dev.write(Register::FIFO_EN, 0)?;
// enable i2c bypass
self.dev.write(Register::USER_CTRL, FIFO_EN)?;
delay.delay_ms(10);
self.interrupt_config(InterruptConfig::LATCH_INT_EN
| InterruptConfig::INT_ANYRD_CLEAR
| InterruptConfig::ACL
| InterruptConfig::BYPASS_EN)?;
self.dev.write(Register::FIFO_EN, 0)?;
self.dev.write(Register::INT_ENABLE, 0x02)?;
self.dev.write(Register::FIFO_EN, 0)?;
self.reset_fifo(delay)?;
// set interrupt mode
self.write_mem(DmpMemory::CFG_FIFO_ON_EVENT,
&[0xd8, 0xb1, 0xb9, 0xf3, 0x8b, 0xa3, 0x91, 0xb6,
0x09, 0xb4, 0xd9])?;
Ok(())
}
/// Load the provided firmware in the internal dmp memory
fn load_firmware(&mut self, firmware: &[u8]) -> Result<(), Error<E>> {
let mut buffer: [u8; 17] = [0; 17];
let mut addr: u16 = 0;
for chunk in firmware.chunks(16) {
self.write_mem(addr, chunk)?;
self.read_mem(addr, &mut buffer)?;
if &buffer[1..chunk.len() + 1] != chunk {
return Err(Error::DmpFirmware);
}
addr += chunk.len() as u16;
}
assert_eq!(addr as usize, firmware.len());
const DMP_START_ADDR: [u8; 2] = [0x04, 0x00];
self.dev.write_many(Register::DMP_START_ADDR, &DMP_START_ADDR)?;
Ok(())
}
/// Write the provided slice at the specified address in dmp memory
fn write_mem<T>(&mut self, addr: T, data: &[u8]) -> Result<(), Error<E>>
where T: Into<u16> + Copy
{
self.dev.write(Register::BANK_SEL, (addr.into() >> 8) as u8)?;
self.dev.write(Register::MEM_ADDR, (addr.into() & 0xff) as u8)?;
self.dev.write_many(Register::MEM_RW, data)?;
Ok(())
}
/// Read dmp memory at the specified address into data
fn read_mem<T>(&mut self, addr: T, data: &mut [u8]) -> Result<(), Error<E>>
where T: Into<u16> + Copy
{
self.dev.write(Register::BANK_SEL, (addr.into() >> 8) as u8)?;
self.dev.write(Register::MEM_ADDR, (addr.into() & 0xff) as u8)?;
self.dev.read_many(Register::MEM_RW, data)?;
Ok(())
}
/// Select which dmp features should be enabled
fn set_dmp_feature<D>(&mut self, delay: &mut D) -> Result<(), Error<E>>
where D: DelayMs<u8>
{
let features = self.dmp_configuration.unwrap_or_default().features;
const GYRO_SF: [u8; 4] = [(46_850_825 >> 24) as u8,
(46_850_825 >> 16) as u8,
(46_850_825 >> 8) as u8,
(46_850_825 & 0xff) as u8];
self.write_mem(DmpMemory::D_0_104, &GYRO_SF)?;
let mut conf = [0xa3 as u8; 10];
if features.raw_accel {
conf[1] = 0xc0;
conf[2] = 0xc8;
conf[3] = 0xc2;
}
if features.raw_gyro {
conf[4] = 0xc4;
conf[5] = 0xcc;
conf[6] = 0xc6;
}
self.write_mem(DmpMemory::CFG_15, &conf)?;
let mut set_config = |address,
state,
config_enabled,
config_disabled|
-> Result<(), Error<E>> {
let config = if state {
config_enabled
} else {
config_disabled
};
self.write_mem(address, config)?;
Ok(())
};
set_config(DmpMemory::CFG_27,
features.tap | features.android_orient,
&[0x20],
&[0xd8])?;
set_config(DmpMemory::CFG_MOTION_BIAS,
features.gyro_auto_calibrate,
&[0xb8, 0xaa, 0xb3, 0x8d, 0xb4, 0x98, 0x0d, 0x35, 0x5d],
&[0xb8, 0xaa, 0xaa, 0xaa, 0xb0, 0x88, 0xc3, 0xc5, 0xc7])?;
if features.raw_gyro {
set_config(DmpMemory::CFG_GYRO_RAW_DATA,
features.gyro_auto_calibrate,
&[0xb2, 0x8b, 0xb6, 0x9b],
&[0xb0, 0x80, 0xb4, 0x90])?;
}
// TODO handle tap
set_config(DmpMemory::CFG_20, features.tap, &[0xf8], &[0xd8])?;
set_config(DmpMemory::CFG_ANDROID_ORIENT_INT,
features.android_orient,
&[0xd9],
&[0xd8])?;
set_config(DmpMemory::CFG_LP_QUAT,
features.quat,
&[0xc0, 0xc2, 0xc4, 0xc6],
&[0x8b, 0x8b, 0x8b, 0x8b])?;
set_config(DmpMemory::CFG_8,
features.quat6,
&[0x20, 0x28, 0x30, 0x38],
&[0xa3, 0xa3, 0xa3, 0xa3])?;
self.reset_fifo(delay)?;
Ok(())
}
/// Reads and returns raw unscaled DMP measurement depending on
/// activated features(LSB).
pub fn dmp_unscaled_all<T1, T2>(
&mut self)
-> Result<UnscaledDmpMeasurement<T1, T2>, Error<E>>
where T1: From<[i16; 3]>,
T2: From<[i32; 4]>
{
let features = self.dmp_configuration.unwrap_or_default().features;
let mut buffer: [u8; 33] = [0; 33];
let read = self.read_fifo(&mut buffer[..self.packet_size + 1])?;
if read < 0 {
return Err(Error::DmpDataNotReady);
}
let mut offset = 0;
let mut measures: UnscaledDmpMeasurement<T1, T2> =
UnscaledDmpMeasurement { quaternion: None,
accel: None,
gyro: None };
if features.quat6 || features.quat {
measures.quaternion = Some(self.to_quat(&buffer).into());
offset += 16;
}
if features.raw_accel {
measures.accel = Some(self.to_vector(&buffer, offset).into());
offset += 6;
}
if features.raw_gyro {
measures.gyro = Some(self.to_vector(&buffer, offset).into());
//offset += 6;
}
Ok(measures)
}
/// Read all measurement from DMP
/// Reads and returns DMP measurement scaled depending on
/// activated features(LSB).
pub fn dmp_all<T1, T2>(&mut self)
-> Result<DmpMeasurement<T1, T2>, Error<E>>
where T1: From<[f32; 3]>,
T2: From<[f64; 4]>
{
let features = self.dmp_configuration.unwrap_or_default().features;
let mut buffer: [u8; 33] = [0; 33];
let read = self.read_fifo(&mut buffer[..self.packet_size + 1])?;
if read < 0 {
return Err(Error::DmpDataNotReady);
}
let mut offset = 0;
let mut measures: DmpMeasurement<T1, T2> =
DmpMeasurement { quaternion: None,
accel: None,
gyro: None };
if features.quat6 || features.quat {
measures.quaternion = Some(self.to_norm_quat(&buffer).into());
offset += 16;
}
if features.raw_accel {
measures.accel = Some(self.scale_accel(&buffer, offset).into());
offset += 6;
}
if features.raw_gyro {
measures.gyro = Some(self.scale_gyro(&buffer, offset).into());
//offset += 6;
}
Ok(measures)
}
/// Parse quaternion from fifo buffer
fn to_quat(&self, buffer: &[u8]) -> [i32; 4] {
[(buffer[1] as i32) << 24
| (buffer[2] as i32) << 16
| (buffer[3] as i32) << 8
| buffer[4] as i32,
(buffer[5] as i32) << 24
| (buffer[6] as i32) << 16
| (buffer[7] as i32) << 8
| buffer[8] as i32,
(buffer[9] as i32) << 24
| (buffer[10] as i32) << 16
| (buffer[11] as i32) << 8
| buffer[12] as i32,
(buffer[13] as i32) << 24
| (buffer[14] as i32) << 16
| (buffer[15] as i32) << 8
| buffer[16] as i32]
}
/// Normalized the quaternion
fn to_norm_quat(&self, buffer: &[u8]) -> [f64; 4] {
let quat = self.to_quat(buffer);
//TODO handle this better, here is an ugly map on fixed size array
let quat = [f64::from(quat[0]),
f64::from(quat[1]),
f64::from(quat[2]),
f64::from(quat[3])];
let sum =
libm::sqrt(quat.iter().map(|x| libm::pow(*x, 2.0)).sum::<f64>());
[quat[0] / sum, quat[1] / sum, quat[2] / sum, quat[3] / sum]
}
}
// Any device, any mode
impl<E, DEV, MODE> Mpu9250<DEV, MODE> where DEV: Device<Error = E>
{
fn init_mpu<D>(&mut self, delay: &mut D) -> Result<(), E>
where D: DelayMs<u8>
{
// Stop all communication with peripherals (such as AK8963).
// If the chip is already powered up and if the communication is already
// running then resetting the MPU can result in a stuck
// peripheral that cannot be recovered from, except by
// physically powering down the peripheral.
self.dev.write(Register::I2C_SLV0_CTRL, 0).ok(); // Ignore error code.
self.dev.write(Register::I2C_SLV4_CTRL, 0).ok(); // Ignore error code.
delay.delay_ms(1); // Wait for transfer to finish.
// wake up device
self.dev.write(Register::PWR_MGMT_1, 0x80)?;
delay.delay_ms(100); // Wait for all registers to reset
// get stable time source
// Auto select clock source to be PLL gyroscope reference if ready else
// else use the internal oscillator, bits 2:0 = 001
self.dev.write(Register::PWR_MGMT_1, 0x01)?;
// Enable all sensors
self.dev.write(Register::PWR_MGMT_2, 0x00)?;
// Set gyroscope full scale range
self._gyro_scale()?;
// Disable FSYNC and set thermometer and gyro bandwidth
self._gyro_temp_data_rate()?;
// Set accelerometer full-scale range configuration
self._accel_scale()?;
// Set accelerometer sample rate configuration
self._accel_data_rate()?;
// Set smplrt_div if present
self._sample_rate_divisor()?;
// Reset interrupts state
self.dev.write(Register::INT_ENABLE, 0x00)?;
Ok(())
}
fn reset_device<F>(self, f: F) -> Result<Self, Error<E>>
where F: FnOnce(DEV) -> Option<DEV>
{
let raw_mag_sensitivity_adjustments =
self.raw_mag_sensitivity_adjustments;
let mag_sensitivity_adjustments = self.mag_sensitivity_adjustments;
let gyro_scale = self.gyro_scale;
let accel_scale = self.accel_scale;
let mag_scale = self.mag_scale;
let accel_data_rate = self.accel_data_rate;
let gyro_temp_data_rate = self.gyro_temp_data_rate;
let sample_rate_divisor = self.sample_rate_divisor;
let dmp_configuration = self.dmp_configuration;
let packet_size = self.packet_size;
let _mode = self._mode;
if let Some(new_dev) = f(self.dev) {
Ok(Mpu9250 { dev: new_dev,
raw_mag_sensitivity_adjustments,
mag_sensitivity_adjustments,
gyro_scale,
accel_scale,
mag_scale,
accel_data_rate,
gyro_temp_data_rate,
sample_rate_divisor,
dmp_configuration,
packet_size,
_mode })
} else {
Err(Error::ReInitError)
}
}
fn scale_accel(&self, buffer: &[u8], offset: usize) -> [f32; 3] {
let resolution = self.accel_scale.resolution();
let scale = G * resolution;
let raw = self.to_vector(buffer, offset);
[raw[0] as f32 * scale, raw[1] as f32 * scale, raw[2] as f32 * scale]
}
fn scale_gyro(&self, buffer: &[u8], offset: usize) -> [f32; 3] {
let resolution = self.gyro_scale.resolution();
let scale = PI_180 * resolution;
let raw = self.to_vector(buffer, offset);
[raw[0] as f32 * scale, raw[1] as f32 * scale, raw[2] as f32 * scale]
}
fn scale_temp(&self, buffer: &[u8], offset: usize) -> f32 {
let rt = (u16(buffer[offset + 1]) << 8) | u16(buffer[offset + 2]);
let t = rt as f32;
(t - TEMP_ROOM_OFFSET) / TEMP_SENSITIVITY + TEMP_DIFF
}
/// Get enabled interrupts
pub fn get_enabled_interrupts(&mut self) -> Result<InterruptEnable, E> {
let bits = self.dev.read(Register::INT_ENABLE)?;
Ok(InterruptEnable::from_bits_truncate(bits))
}
/// Get interrupt status
pub fn get_interrupt_status(&mut self) -> Result<InterruptEnable, E> {
let bits = self.dev.read(Register::INT_STATUS)?;
Ok(InterruptEnable::from_bits_truncate(bits))
}
/// Enable specific interrupts
pub fn enable_interrupts(&mut self, ie: InterruptEnable) -> Result<(), E> {
self.dev.modify(Register::INT_ENABLE, |r| r | ie.bits())
}
/// Disable specific interrupts
pub fn disable_interrupts(&mut self, ie: InterruptEnable) -> Result<(), E> {
self.dev.modify(Register::INT_ENABLE, |r| r & !ie.bits())
}
/// Get interrupt configurtion
pub fn get_interrupt_config(&mut self) -> Result<InterruptConfig, E> {
let bits = self.dev.read(Register::INT_PIN_CFG)?;
Ok(InterruptConfig::from_bits_truncate(bits))
}
/// *Overwrites* current interrupt configuration
pub fn interrupt_config(&mut self, ic: InterruptConfig) -> Result<(), E> {
self.dev.write(Register::INT_PIN_CFG, ic.bits())
}
/// Reset the internal FIFO
pub fn reset_fifo<D>(&mut self, delay: &mut D) -> Result<(), Error<E>>
where D: DelayMs<u8>
{
self.dev.write(Register::INT_ENABLE, 0)?;
self.dev.write(Register::FIFO_EN, 0)?;
self.dev.write(Register::USER_CTRL, 0)?;
self.dev.write(Register::USER_CTRL, 0x0c)?;
delay.delay_ms(3);
self.dev.write(Register::USER_CTRL, 0xc0)?;
self.dev.write(Register::INT_ENABLE, 0x02)?;
self.dev.write(Register::FIFO_EN, 0)?;
Ok(())
}
/// 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
pub fn read_fifo(&mut self, data: &mut [u8]) -> Result<isize, Error<E>> {
let mut buffer: [u8; 3] = [0; 3];
self.dev.read_many(Register::FIFO_COUNT_H, &mut buffer)?;
let count = (buffer[1] as usize) << 8 | buffer[2] as usize;
if data.len() <= count + 1 {
self.dev.read_many(Register::FIFO_RW, &mut data[..])?;
}
Ok(count as isize - data.len() as isize + 1)
}
/// Reads and returns unscaled accelerometer measurements (LSB).
pub fn unscaled_accel<T>(&mut self) -> Result<T, E>
where T: From<[i16; 3]>
{
let buffer = &mut [0; 7];
self.dev.read_many(Register::ACCEL_XOUT_H, buffer)?;
Ok(self.to_vector(buffer, 0).into())
}
/// Reads and returns accelerometer measurements scaled and converted to g.
pub fn accel<T>(&mut self) -> Result<T, E>
where T: From<[f32; 3]>
{
let buffer = &mut [0; 7];
self.dev.read_many(Register::ACCEL_XOUT_H, buffer)?;
Ok(self.scale_accel(buffer, 0).into())
}
/// Reads and returns unsacled Gyroscope measurements (LSB).
pub fn unscaled_gyro<T>(&mut self) -> Result<T, E>
where T: From<[i16; 3]>
{
let buffer = &mut [0; 7];
self.dev.read_many(Register::GYRO_XOUT_H, buffer)?;
Ok(self.to_vector(buffer, 0).into())
}
/// Reads and returns gyroscope measurements scaled and converted to rad/s.
pub fn gyro<T>(&mut self) -> Result<T, E>
where T: From<[f32; 3]>
{
let buffer = &mut [0; 7];
self.dev.read_many(Register::GYRO_XOUT_H, buffer)?;
Ok(self.scale_gyro(buffer, 0).into())
}
/// Configures accelerometer data rate config ([`AccelDataRate`]).
///
/// [`AccelDataRate`]: ./conf/enum.AccelDataRate.html
pub fn accel_data_rate(&mut self,
accel_data_rate: AccelDataRate)
-> Result<(), E> {
self.accel_data_rate = accel_data_rate;
self._accel_data_rate()
}
fn _accel_data_rate(&mut self) -> Result<(), E> {
let bits = self.accel_data_rate.accel_config_bits();
self.dev.write(Register::ACCEL_CONFIG_2, bits)?;
Ok(())
}
/// Configures accelerometer full reading scale ([`Accel scale`]).
///
/// [`Accel scale`]: ./conf/enum.AccelScale.html
pub fn accel_scale(&mut self, scale: AccelScale) -> Result<(), E> {
self.accel_scale = scale;
self._accel_scale()
}
fn _accel_scale(&mut self) -> Result<(), E> {
let scale = self.accel_scale as u8;
self.dev.modify(Register::ACCEL_CONFIG, |r|
// Clear AFS bits [4:3]
(r & !0x18)
// Set full scale range for accel
| (scale << 3))?;
Ok(())
}
/// Configures gyroscope and temperatures data rate config
/// ([`GyroTempDataRate`]).
///
/// [`GyroTempDataRate`]: ./conf/enum.GyroTempDataRate.html
pub fn gyro_temp_data_rate(&mut self,
data_rate: GyroTempDataRate)
-> Result<(), E> {
self.gyro_temp_data_rate = data_rate;
self._gyro_temp_data_rate()
}
fn _gyro_temp_data_rate(&mut self) -> Result<(), E> {
let fchoice_bits = self.gyro_temp_data_rate.fchoice_b_bits();
let dlpf_bits = self.gyro_temp_data_rate.dlpf_bits();
// Clear Fchoice bits [1:0] and set them
self.dev
.modify(Register::GYRO_CONFIG, |r| (r & !0b11) | fchoice_bits)?;
// Clear and update DLPF_CFG
self.dev.modify(Register::CONFIG, |r| (r & !0b111) | dlpf_bits)?;
Ok(())
}
/// Configures gyroscope full reading scale ([`Gyro scale`]).
///
/// [`Gyro scale`]: ./conf/enum.GyroScale.html
pub fn gyro_scale(&mut self, scale: GyroScale) -> Result<(), E> {
self.gyro_scale = scale;
self._gyro_scale()
}
fn _gyro_scale(&mut self) -> Result<(), E> {
let scale = self.gyro_scale as u8;
self.dev.modify(Register::GYRO_CONFIG, |r|
// Clear GFS bits [4:3]
(r & !0x18)
// Set full scale range for the gyro
| (scale << 3))?;
Ok(())
}
/// Reads and returns raw unscaled temperature sensor measurements (LSB).
pub fn raw_temp(&mut self) -> Result<i16, E> {
let buffer = &mut [0; 3];
self.dev.read_many(Register::TEMP_OUT_H, buffer)?;
let t = (u16(buffer[1]) << 8) | u16(buffer[2]);
Ok(t as i16)
}
/// Reads and returns adjusted temperature measurements converted to C.
pub fn temp(&mut self) -> Result<f32, E> {
let buffer = &mut [0; 3];
self.dev.read_many(Register::TEMP_OUT_H, buffer)?;
Ok(self.scale_temp(buffer, 0))
}
/// 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).
///
/// [`GyroTempDataRate`]: ./conf/enum.GyroTempDataRate.html
pub fn sample_rate_divisor(&mut self, smplrt_div: u8) -> Result<(), E> {
self.sample_rate_divisor = Some(smplrt_div);
self.dev.write(Register::SMPLRT_DIV, smplrt_div)?;
Ok(())
}
fn _sample_rate_divisor(&mut self) -> Result<(), E> {
if let Some(sample_rate_div) = self.sample_rate_divisor {
self.dev.write(Register::SMPLRT_DIV, sample_rate_div)?;
}
Ok(())
}
fn _calibrate_at_rest<D>(&mut self,
delay: &mut D)
-> Result<[f32; 3], Error<E>>
where D: DelayMs<u8>
{
// First save current values, as we reset them below
let orig_gyro_scale = self.gyro_scale;
let orig_accel_scale = self.accel_scale;
let orig_gyro_temp_data_rate = self.gyro_temp_data_rate;
let orig_accel_data_rate = self.accel_data_rate;
let orig_sample_rate_divisor = self.sample_rate_divisor;
// reset device
self.dev.write(Register::PWR_MGMT_1, 0x80)?;
// get stable time source;
// Auto select clock source to be PLL gyroscope reference if ready
// else use the internal oscillator, bits 2:0 = 001
self.dev.write(Register::PWR_MGMT_1, 0x01)?;
// Enable all sensors
self.dev.write(Register::PWR_MGMT_2, 0x00)?;
delay.delay_ms(200);
// Configure device for bias calculation
// Disable all interrupts
self.dev.write(Register::INT_ENABLE, 0x00)?;
// Disable FIFO
self.dev.write(Register::FIFO_EN, 0x00)?;
// Turn on internal clock source
self.dev.write(Register::PWR_MGMT_1, 0x00)?;
// Disable I2C
self.dev.write(Register::I2C_MST_CTRL, 0x00)?;
// Disable FIFO and I2C master modes
self.dev.write(Register::USER_CTRL, 0x00)?;
// Reset FIFO and DMP
self.dev.write(Register::USER_CTRL, 0x0C)?;
delay.delay_ms(15);
// Configure MPU6050 gyro and accelerometer for bias calculation
// Set low-pass filter to 184Hz
self.gyro_temp_data_rate(GyroTempDataRate::DlpfConf(Dlpf::_1))?;
self.sample_rate_divisor(0)?;
// Set gyro full-scale to 250 degrees per second, maximum sensitivity
// self.gyro_scale(GyroScale::_250DPS)?;
// Set accelerometer low pass filter to
self.accel_data_rate(AccelDataRate::DlpfConf(Dlpf::_1))?;
// Set accelerometer full-scale to 2g, maximum sensitivity
self.accel_scale(AccelScale::_2G)?;
// Configure FIFO to capture accelerometer and gyro data for bias
// calculation
self.dev.write(Register::USER_CTRL, 0x40)?;
// Enable FIFO
self.dev.write(Register::FIFO_EN, 0x78)?;
// Enable gyro and accelerometer sensors for FIFO
// (max size 512 bytes in MPU-9150)
// accumulate 40 samples in 40 milliseconds =480 bytes
delay.delay_ms(40);
// At end of sample accumulation, turn off FIFO sensor read
// Disable gyro and accelerometer sensors for FIFO
self.dev.write(Register::FIFO_EN, 0x00)?;
// read FIFO sample count
let buffer = &mut [0; 13]; // larger buffer is used later
self.dev.read_many(Register::FIFO_COUNT_H, &mut buffer[0..3])?;
let fifo_count = ((u16(buffer[1]) << 8) | u16(buffer[2])) as i16;
// Aim for at least half
// How many sets of full gyro and accelerometer data for averaging
let packet_count = (fifo_count / 12) as i32;
if packet_count < 20 {
return Err(Error::CalibrationError);
}
let mut accel_biases = [0; 3];
let mut gyro_biases = [0; 3];
for _ in 0..packet_count {
self.dev.read_many(Register::FIFO_RW, buffer)?;
let accel_temp = self.to_vector(buffer, 0);
let gyro_temp = self.to_vector(buffer, 6);
for i in 0..3 {
accel_biases[i] += accel_temp[i] as i32;
gyro_biases[i] += gyro_temp[i] as i32;
}
}
for i in 0..3 {
accel_biases[i] /= packet_count;
gyro_biases[i] /= packet_count;
}
// Construct the gyro biases and push them to the hardware gyro bias
// registers, which are reset to zero upon device startup.
// Divide by 4 to get 32.9 LSB per deg/s to conform to expected bias
// input format.
// Biases are additive, so change sign on
// calculated average gyro biases
self.set_unscaled_gyro_bias(false,
[(gyro_biases[0] / -4) as i16,
(gyro_biases[1] / -4) as i16,
(gyro_biases[2] / -4) as i16])?;
// Compute accelerometer biases to be returned
let resolution = self.accel_scale.resolution();
let scale = G * resolution;
// Set original values back and re-init device
self.gyro_scale = orig_gyro_scale;
self.accel_scale = orig_accel_scale;
self.gyro_temp_data_rate = orig_gyro_temp_data_rate;
self.accel_data_rate = orig_accel_data_rate;
self.sample_rate_divisor = orig_sample_rate_divisor;
self.init_mpu(delay)?;
Ok([accel_biases[0] as f32 * scale,
accel_biases[1] as f32 * scale,
accel_biases[2] as f32 * scale])
}
/// Get unscaled gyroscope biases.
/// Output format is +-1000dps
fn get_unscaled_gyro_bias(&mut self) -> Result<[i16; 3], Error<E>> {
Ok([(self.dev.read(Register::XG_OFFSET_H)? as i16) << 8
| self.dev.read(Register::XG_OFFSET_L)? as i16,
(self.dev.read(Register::YG_OFFSET_H)? as i16) << 8
| self.dev.read(Register::YG_OFFSET_L)? as i16,
(self.dev.read(Register::ZG_OFFSET_H)? as i16) << 8
| self.dev.read(Register::ZG_OFFSET_L)? as i16])
}
/// Get scaled gyroscope biases.
pub fn get_gyro_bias<T>(&mut self) -> Result<T, Error<E>>
where T: From<[f32; 3]>
{
let biases = self.get_unscaled_gyro_bias()?;
let scale = GyroScale::_1000DPS.resolution();
Ok([biases[0] as f32 * scale,
biases[1] as f32 * scale,
biases[2] as f32 * scale].into())
}
/// Set unscaled gyroscope biases.
/// In relative mode it will add the new biases to the existing ones instead
/// of replacing them. Input format is +-1000dps
fn set_unscaled_gyro_bias(&mut self,
relative: bool,
biases: [i16; 3])
-> Result<(), Error<E>> {
let mut new_biases = biases;
if relative {
let old_biases = self.get_unscaled_gyro_bias()?;
for i in 0..3 {
new_biases[i] += old_biases[i];
}
}
self.dev.write(Register::XG_OFFSET_H,
((new_biases[0] >> 8) & 0xFF) as u8)?;
self.dev.write(Register::XG_OFFSET_L, (new_biases[0] & 0xFF) as u8)?;
self.dev.write(Register::YG_OFFSET_H,
((new_biases[1] >> 8) & 0xFF) as u8)?;
self.dev.write(Register::YG_OFFSET_L, (new_biases[1] & 0xFF) as u8)?;
self.dev.write(Register::ZG_OFFSET_H,
((new_biases[2] >> 8) & 0xFF) as u8)?;
self.dev.write(Register::ZG_OFFSET_L, (new_biases[2] & 0xFF) as u8)?;
Ok(())
}
/// Set scaled gyro biases.
/// In relative mode it will add the new biases to the existing ones instead
/// of replacing them.
pub fn set_gyro_bias<T>(&mut self,
relative: bool,
biases: T)
-> Result<(), Error<E>>
where T: Into<[f32; 3]>
{
let biases = biases.into();
let scale = GyroScale::_1000DPS.resolution();
self.set_unscaled_gyro_bias(relative,
[(biases[0] / scale) as i16,
(biases[1] / scale) as i16,
(biases[2] / scale) as i16])
}
/// Get unscaled accelerometer biases.
/// Output format is +-16G
fn get_unscaled_accel_bias(&mut self) -> Result<[i16; 3], Error<E>> {
Ok([(self.dev.read(Register::XA_OFFSET_H)? as i16) << 8
| self.dev.read(Register::XA_OFFSET_L)? as i16,
(self.dev.read(Register::YA_OFFSET_H)? as i16) << 8
| self.dev.read(Register::YA_OFFSET_L)? as i16,
(self.dev.read(Register::ZA_OFFSET_H)? as i16) << 8
| self.dev.read(Register::ZA_OFFSET_L)? as i16])
}
/// Get scaled accelerometer biases.
pub fn get_accel_bias<T>(&mut self) -> Result<T, Error<E>>
where T: From<[f32; 3]>
{
let biases = self.get_unscaled_accel_bias()?;
let scale = G * AccelScale::_16G.resolution();
Ok([biases[0] as f32 * scale,
biases[1] as f32 * scale,
biases[2] as f32 * scale].into())
}
/// Set unscaled 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. Input format is +-16G.
fn set_unscaled_accel_bias(&mut self,
relative: bool,
biases: [i16; 3])
-> Result<(), Error<E>> {
let mut new_biases = self.get_unscaled_accel_bias()?;
// Do not touch the last bit
for i in 0..3 {
if !relative {
new_biases[i] &= 1
}
new_biases[i] += biases[i] & !1;
}
self.dev.write(Register::XA_OFFSET_H,
((new_biases[0] >> 8) & 0xFF) as u8)?;
self.dev.write(Register::XA_OFFSET_L, (new_biases[0] & 0xFF) as u8)?;
self.dev.write(Register::YA_OFFSET_H,
((new_biases[1] >> 8) & 0xFF) as u8)?;
self.dev.write(Register::YA_OFFSET_L, (new_biases[1] & 0xFF) as u8)?;
self.dev.write(Register::ZA_OFFSET_H,
((new_biases[2] >> 8) & 0xFF) as u8)?;
self.dev.write(Register::ZA_OFFSET_L, (new_biases[2] & 0xFF) as u8)?;
Ok(())
}
/// 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.
pub fn set_accel_bias<T>(&mut self,
relative: bool,
biases: T)
-> Result<(), Error<E>>
where T: Into<[f32; 3]>
{
let biases = biases.into();
let scale = G * AccelScale::_16G.resolution();
self.set_unscaled_accel_bias(relative,
[(biases[0] / scale) as i16,
(biases[1] / scale) as i16,
(biases[2] / scale) as i16])
}
fn to_vector(&self, buffer: &[u8], offset: usize) -> [i16; 3] {
[((u16(buffer[offset + 1]) << 8) | u16(buffer[offset + 2])) as i16,
((u16(buffer[offset + 3]) << 8) | u16(buffer[offset + 4])) as i16,
((u16(buffer[offset + 5]) << 8) | u16(buffer[offset + 6])) as i16]
}
fn to_vector_inverted(&self, buffer: &[u8], offset: usize) -> [i16; 3] {
[((u16(buffer[offset + 2]) << 8) + u16(buffer[offset + 1])) as i16,
((u16(buffer[offset + 4]) << 8) + u16(buffer[offset + 3])) as i16,
((u16(buffer[offset + 6]) << 8) + u16(buffer[offset + 5])) as i16]
}
/// Reads the WHO_AM_I register; should return `0x71`
pub fn who_am_i(&mut self) -> Result<u8, E> {
self.dev.read(Register::WHO_AM_I)
}
}
// Any device, any mode, no possible errors
impl<DEV, MODE> Mpu9250<DEV, MODE> {
/// Returns Accelerometer resolution.
pub fn accel_resolution(&self) -> f32 {
self.accel_scale.resolution()
}
/// Returns Gyroscope resolution.
pub fn gyro_resolution(&self) -> f32 {
self.gyro_scale.resolution()
}
/// Returns Magnetometer resolution.
pub fn mag_resolution(&self) -> f32 {
self.mag_scale.resolution()
}
}
/// SPI mode
pub const MODE: Mode = Mode { polarity: Polarity::IdleHigh,
phase: Phase::CaptureOnSecondTransition };
#[allow(dead_code)]
#[allow(non_camel_case_types)]
#[derive(Clone, Copy)]
#[doc(hidden)]
pub enum Register {
ACCEL_CONFIG = 0x1c,
ACCEL_CONFIG_2 = 0x1d,
ACCEL_XOUT_H = 0x3b,
ACCEL_YOUT_H = 0x3d,
CONFIG = 0x1a,
XG_OFFSET_H = 0x13, // User-defined trim values for gyroscope
XG_OFFSET_L = 0x14,
YG_OFFSET_H = 0x15,
YG_OFFSET_L = 0x16,
ZG_OFFSET_H = 0x17,
ZG_OFFSET_L = 0x18,
EXT_SENS_DATA_00 = 0x49,
EXT_SENS_DATA_01 = 0x4a,
EXT_SENS_DATA_02 = 0x4b,
EXT_SENS_DATA_03 = 0x4c,
EXT_SENS_DATA_04 = 0x4d,
GYRO_CONFIG = 0x1b,
SMPLRT_DIV = 0x19,
GYRO_XOUT_H = 0x43,
FIFO_EN = 0x23,
I2C_MST_CTRL = 0x24,
I2C_MST_STATUS = 0x36,
I2C_SLV0_ADDR = 0x25,
I2C_SLV0_CTRL = 0x27,
I2C_SLV0_DO = 0x63,
I2C_SLV0_REG = 0x26,
I2C_SLV4_ADDR = 0x31,
I2C_SLV4_CTRL = 0x34,
I2C_SLV4_DI = 0x35,
I2C_SLV4_DO = 0x33,
I2C_SLV4_REG = 0x32,
INT_PIN_CFG = 0x37,
INT_ENABLE = 0x38,
INT_STATUS = 0x3a,
PWR_MGMT_1 = 0x6b,
PWR_MGMT_2 = 0x6c,
TEMP_OUT_H = 0x41,
USER_CTRL = 0x6a,
BANK_SEL = 0x6d,
MEM_ADDR = 0x6e,
MEM_RW = 0x6f,
DMP_START_ADDR = 0x70,
FIFO_COUNT_H = 0x72,
FIFO_RW = 0x74,
WHO_AM_I = 0x75,
XA_OFFSET_H = 0x77,
XA_OFFSET_L = 0x78,
YA_OFFSET_H = 0x7A,
YA_OFFSET_L = 0x7B,
ZA_OFFSET_H = 0x7D,
ZA_OFFSET_L = 0x7E,
}
const R: u8 = 1 << 7;
const W: u8 = 0 << 7;
impl Register {
fn read_address(&self) -> u8 {
*self as u8 | R
}
fn write_address(&self) -> u8 {
*self as u8 | W
}
}
#[allow(dead_code)]
#[allow(non_camel_case_types)]
#[derive(Clone, Copy)]
#[doc(hidden)]
pub enum DmpMemory {
CFG_LP_QUAT = 2712,
END_ORIENT_TEMP = 1866,
CFG_27 = 2742,
CFG_20 = 2224,
CFG_23 = 2745,
CFG_FIFO_ON_EVENT = 2690,
END_PREDICTION_UPDATE = 1761,
CGNOTICE_INTR = 2620,
X_GRT_Y_TMP = 1358,
CFG_DR_INT = 1029,
CFG_AUTH = 1035,
UPDATE_PROP_ROT = 1835,
END_COMPARE_Y_X_TMP2 = 1455,
SKIP_X_GRT_Y_TMP = 1359,
SKIP_END_COMPARE = 1435,
FCFG_3 = 1088,
FCFG_2 = 1066,
FCFG_1 = 1062,
END_COMPARE_Y_X_TMP3 = 1434,
FCFG_7 = 1073,
FCFG_6 = 1106,
FLAT_STATE_END = 1713,
SWING_END_4 = 1616,
SWING_END_2 = 1565,
SWING_END_3 = 1587,
SWING_END_1 = 1550,
CFG_8 = 2718,
CFG_15 = 2727,
CFG_16 = 2746,
CFG_EXT_GYRO_BIAS = 1189,
END_COMPARE_Y_X_TMP = 1407,
DO_NOT_UPDATE_PROP_ROT = 1839,
CFG_7 = 1205,
FLAT_STATE_END_TEMP = 1683,
END_COMPARE_Y_X = 1484,
SKIP_SWING_END_1 = 1551,
SKIP_SWING_END_3 = 1588,
SKIP_SWING_END_2 = 1566,
TILTG75_START = 1672,
CFG_6 = 2753,
TILTL75_END = 1669,
END_ORIENT = 1884,
CFG_FLICK_IN = 2573,
TILTL75_START = 1643,
CFG_MOTION_BIAS = 1208,
X_GRT_Y = 1408,
TEMPLABEL = 2324,
CFG_ANDROID_ORIENT_INT = 1853,
CFG_GYRO_RAW_DATA = 2722,
X_GRT_Y_TMP2 = 1379,
D_0_22 = 22 + 512,
D_0_24 = 24 + 512,
D_0_36 = 36,
//D_0_52 = 52, // Same as D_TILT1_H
D_0_96 = 96,
D_0_104 = 104,
D_0_108 = 108,
D_0_163 = 163,
D_0_188 = 188,
D_0_192 = 192,
D_0_224 = 224,
D_0_228 = 228,
D_0_232 = 232,
D_0_236 = 236,
D_1_2 = 256 + 2,
D_1_4 = 256 + 4,
D_1_8 = 256 + 8,
D_1_10 = 256 + 10,
D_1_24 = 256 + 24,
D_1_28 = 256 + 28,
D_1_36 = 256 + 36,
D_1_40 = 256 + 40,
D_1_44 = 256 + 44,
D_1_72 = 256 + 72,
D_1_74 = 256 + 74,
D_1_79 = 256 + 79,
D_1_88 = 256 + 88,
D_1_90 = 256 + 90,
D_1_92 = 256 + 92,
D_1_96 = 256 + 96,
D_1_98 = 256 + 98,
D_1_106 = 256 + 106,
D_1_108 = 256 + 108,
D_1_112 = 256 + 112,
D_1_128 = 256 + 144,
D_1_152 = 256 + 12,
D_1_160 = 256 + 160,
D_1_176 = 256 + 176,
D_1_178 = 256 + 178,
D_1_218 = 256 + 218,
D_1_232 = 256 + 232,
D_1_236 = 256 + 236,
D_1_240 = 256 + 240,
D_1_244 = 256 + 244,
D_1_250 = 256 + 250,
D_1_252 = 256 + 252,
D_2_12 = 512 + 12,
D_2_96 = 512 + 96,
D_2_108 = 512 + 108,
D_2_208 = 512 + 208,
D_2_224 = 512 + 224,
//D_2_236 = 512 + 236, // Same as FLICK_UPPER
D_2_244 = 512 + 244,
D_2_248 = 512 + 248,
D_2_252 = 512 + 252,
CPASS_BIAS_X = 35 * 16 + 4,
CPASS_BIAS_Y = 35 * 16 + 8,
CPASS_BIAS_Z = 35 * 16 + 12,
CPASS_MTX_00 = 36 * 16,
CPASS_MTX_01 = 36 * 16 + 4,
CPASS_MTX_02 = 36 * 16 + 8,
CPASS_MTX_10 = 36 * 16 + 12,
CPASS_MTX_11 = 37 * 16,
CPASS_MTX_12 = 37 * 16 + 4,
CPASS_MTX_20 = 37 * 16 + 8,
CPASS_MTX_21 = 37 * 16 + 12,
CPASS_MTX_22 = 43 * 16 + 12,
D_EXT_GYRO_BIAS_X = 61 * 16,
D_EXT_GYRO_BIAS_Y = 61 * 16 + 4,
D_EXT_GYRO_BIAS_Z = 61 * 16 + 8,
D_ACT0 = 40 * 16,
D_ACSX = 40 * 16 + 4,
D_ACSY = 40 * 16 + 8,
D_ACSZ = 40 * 16 + 12,
FLICK_MSG = 45 * 16 + 4,
FLICK_COUNTER = 45 * 16 + 8,
FLICK_LOWER = 45 * 16 + 12,
FLICK_UPPER = 46 * 16 + 12,
D_AUTH_OUT = 992,
D_AUTH_IN = 996,
D_AUTH_A = 1000,
D_AUTH_B = 1004,
D_PEDSTD_BP_B = 768 + 0x1C,
D_PEDSTD_HP_A = 768 + 0x78,
D_PEDSTD_HP_B = 768 + 0x7C,
D_PEDSTD_BP_A4 = 768 + 0x40,
D_PEDSTD_BP_A3 = 768 + 0x44,
D_PEDSTD_BP_A2 = 768 + 0x48,
D_PEDSTD_BP_A1 = 768 + 0x4C,
D_PEDSTD_INT_THRSH = 768 + 0x68,
D_PEDSTD_CLIP = 768 + 0x6C,
D_PEDSTD_SB = 768 + 0x28,
D_PEDSTD_SB_TIME = 768 + 0x2C,
D_PEDSTD_PEAKTHRSH = 768 + 0x98,
D_PEDSTD_TIML = 768 + 0x2A,
D_PEDSTD_TIMH = 768 + 0x2E,
D_PEDSTD_PEAK = 768 + 0x94,
D_PEDSTD_STEPCTR = 768 + 0x60,
D_PEDSTD_TIMECTR = 964,
D_PEDSTD_DECI = 768 + 0xA0,
//D_HOST_NO_MOT = 976, // Same as D_EXT_GYRO_BIAS_X
D_ACCEL_BIAS = 660,
D_ORIENT_GAP = 76,
D_TILT0_H = 48,
D_TILT0_L = 50,
D_TILT1_H = 52,
D_TILT1_L = 54,
D_TILT2_H = 56,
D_TILT2_L = 58,
D_TILT3_H = 60,
D_TILT3_L = 62,
}
impl Into<u16> for DmpMemory {
fn into(self) -> u16 {
self as u16
}
}
/// Unscaled IMU measurements (LSB)
#[derive(Clone, Copy, Debug)]
pub struct UnscaledImuMeasurements<T> {
/// Accelerometer measurements (LSB)
pub accel: T,
/// Gyroscope measurements (LSB)
pub gyro: T,
/// Temperature sensor measurement (LSB)
pub temp: i16,
}
/// Scaled IMU measurements converted to units
#[derive(Clone, Copy, Debug)]
pub struct ImuMeasurements<T> {
/// Accelerometer measurements (g)
pub accel: T,
/// Gyroscope measurements (rad/s)
pub gyro: T,
/// Temperature sensor measurement (C)
pub temp: f32,
}
/// Unscaled MARG measurements (LSB)
#[derive(Copy, Clone, Debug)]
pub struct UnscaledMargMeasurements<T> {
/// Accelerometer measurements (LSB)
pub accel: T,
/// Gyroscope measurements (LSB)
pub gyro: T,
/// Magnetometer measurements (LSB)
pub mag: T,
/// Temperature sensor measurement (LSB)
pub temp: i16,
}
/// MARG measurements scaled with respective scales and converted
/// to appropriate units.
#[derive(Copy, Clone, Debug)]
pub struct MargMeasurements<T> {
/// Accelerometer measurements (g)
pub accel: T,
/// Gyroscope measurements (rad/s)
pub gyro: T,
/// Magnetometer measurements (μT)
pub mag: T,
/// Temperature sensor measurement (C)
pub temp: f32,
}
/// DMP measurement scaled with respective scales and converted
/// to appropriate units. Each measurement will be present only
/// if the corresponding features is activated in [`dmp features`]
///
/// [`dmp features`]: ./struct.DmpFeatures.html
#[derive(Copy, Clone, Debug)]
pub struct UnscaledDmpMeasurement<T1, T2> {
/// raw quaternion (LSB)
pub quaternion: Option<T2>,
/// Accelerometer measurements (LSB)
pub accel: Option<T1>,
/// Gyroscope measurements (LSB)
pub gyro: Option<T1>,
}
/// DMP measurement scaled with respective scales and converted
/// to appropriate units. Each measurement will be present only
/// if the corresponding features is activated in [`dmp features`]
///
/// [`dmp features`]: ./struct.DmpFeatures.html
#[derive(Copy, Clone, Debug)]
pub struct DmpMeasurement<T1, T2> {
/// Normalized quaternion
pub quaternion: Option<T2>,
/// Accelerometer measurements (g)
pub accel: Option<T1>,
/// Gyroscope measurements (rad/s)
pub gyro: Option<T1>,
}
fn transpose<T, E>(o: Option<Result<T, E>>) -> Result<Option<T>, E> {
match o {
Some(Ok(x)) => Ok(Some(x)),
Some(Err(e)) => Err(e),
None => Ok(None),
}
}
fn u16(u: u8) -> u16 {
return u as u16;
}