Closed asinghnu closed 2 years ago
Please ensure that you're using the latest version of this library (i.e. v5.6.0) downloaded directly from GitHub and let me know if you're still having issues.
yes i have used latest version as mentioned above ,still issue remains same
Which sensor breakout are you using? Some sensor breakouts have resistors that must be removed in order to use SPI.
Hi Brian,
I am running into similar problems getting this to work on a teensy 4.1, I have mine hooked up in the same manner as the original comment. I am using the board in the image below, which from my understanding doesn't need resistors removed?
When using slower clock speeds (#63) I still have issues, with only 24MHz not giving the IMU initialization error, but it never prints anything to the serial monitor at all at that clock speed.
Can you please ensure that you're using the latest version of this library downloaded from GitHub and let us know if you're still having issues? I use the MPU-9250 with a Teensy 4.1 often now, but the library had some code changes to enable everything to work.
I have downloaded the library from GitHub and replaced the Arduino copy with the up to date GitHub copy already and I am using the SPI example code given.
Can you replace the Begin method in mpu9250.cpp with the version below and let me know what error number is printed?
bool Mpu9250::Begin() {
if (iface_ == SPI) {
pinMode(dev_, OUTPUT);
/* Toggle CS pin to lock in SPI mode */
digitalWrite(dev_, LOW);
delay(1);
digitalWrite(dev_, HIGH);
delay(1);
}
/* 1 MHz for config */
spi_clock_ = SPI_CFG_CLOCK_;
/* Select clock source to gyro */
if (!WriteRegister(PWR_MGMNT_1_, CLKSEL_PLL_)) {
Serial.println("ERROR 1");
return false;
}
/* Enable I2C master mode */
if (!WriteRegister(USER_CTRL_, I2C_MST_EN_)) {
Serial.println("ERROR 2");
return false;
}
/* Set the I2C bus speed to 400 kHz */
if (!WriteRegister(I2C_MST_CTRL_, I2C_MST_CLK_)) {
Serial.println("ERROR 3");
return false;
}
/* Set AK8963 to power down */
WriteAk8963Register(AK8963_CNTL1_, AK8963_PWR_DOWN_);
/* Reset the MPU9250 */
WriteRegister(PWR_MGMNT_1_, H_RESET_);
/* Wait for MPU-9250 to come back up */
delay(1);
/* Reset the AK8963 */
WriteAk8963Register(AK8963_CNTL2_, AK8963_RESET_);
/* Select clock source to gyro */
if (!WriteRegister(PWR_MGMNT_1_, CLKSEL_PLL_)) {
Serial.println("ERROR 4");
return false;
}
/* Check the WHO AM I byte */
if (!ReadRegisters(WHOAMI_, sizeof(who_am_i_), &who_am_i_)) {
Serial.println("ERROR 5");
return false;
}
if ((who_am_i_ != WHOAMI_MPU9250_) && (who_am_i_ != WHOAMI_MPU9255_)) {
Serial.println("ERROR 6");
return false;
}
/* Enable I2C master mode */
if (!WriteRegister(USER_CTRL_, I2C_MST_EN_)) {
Serial.println("ERROR 7");
return false;
}
/* Set the I2C bus speed to 400 kHz */
if (!WriteRegister(I2C_MST_CTRL_, I2C_MST_CLK_)) {
Serial.println("ERROR 8");
return false;
}
/* Check the AK8963 WHOAMI */
if (!ReadAk8963Registers(AK8963_WHOAMI_, sizeof(who_am_i_), &who_am_i_)) {
Serial.println("ERROR 9");
return false;
}
if (who_am_i_ != WHOAMI_AK8963_) {
Serial.println("ERROR 10");
return false;
}
/* Get the magnetometer calibration */
/* Set AK8963 to power down */
if (!WriteAk8963Register(AK8963_CNTL1_, AK8963_PWR_DOWN_)) {
Serial.println("ERROR 11");
return false;
}
delay(100); // long wait between AK8963 mode changes
/* Set AK8963 to FUSE ROM access */
if (!WriteAk8963Register(AK8963_CNTL1_, AK8963_FUSE_ROM_)) {
Serial.println("ERROR 12");
return false;
}
delay(100); // long wait between AK8963 mode changes
/* Read the AK8963 ASA registers and compute magnetometer scale factors */
if (!ReadAk8963Registers(AK8963_ASA_, sizeof(asa_buff_), asa_buff_)) {
Serial.println("ERROR 13");
return false;
}
mag_scale_[0] = ((static_cast<float>(asa_buff_[0]) - 128.0f)
/ 256.0f + 1.0f) * 4912.0f / 32760.0f;
mag_scale_[1] = ((static_cast<float>(asa_buff_[1]) - 128.0f)
/ 256.0f + 1.0f) * 4912.0f / 32760.0f;
mag_scale_[2] = ((static_cast<float>(asa_buff_[2]) - 128.0f)
/ 256.0f + 1.0f) * 4912.0f / 32760.0f;
/* Set AK8963 to power down */
if (!WriteAk8963Register(AK8963_CNTL1_, AK8963_PWR_DOWN_)) {
Serial.println("ERROR 14");
return false;
}
/* Set AK8963 to 16 bit resolution, 100 Hz update rate */
if (!WriteAk8963Register(AK8963_CNTL1_, AK8963_CNT_MEAS2_)) {
Serial.println("ERROR 15");
return false;
}
delay(100); // long wait between AK8963 mode changes
/* Select clock source to gyro */
if (!WriteRegister(PWR_MGMNT_1_, CLKSEL_PLL_)) {
Serial.println("ERROR 16");
return false;
}
/* Set the accel range to 16G by default */
if (!ConfigAccelRange(ACCEL_RANGE_16G)) {
Serial.println("ERROR 17");
return false;
}
/* Set the gyro range to 2000DPS by default*/
if (!ConfigGyroRange(GYRO_RANGE_2000DPS)) {
Serial.println("ERROR 18");
return false;
}
/* Set the DLPF to 184HZ by default */
if (!ConfigDlpfBandwidth(DLPF_BANDWIDTH_184HZ)) {
Serial.println("ERROR 19");
return false;
}
/* Set the SRD to 0 by default */
if (!ConfigSrd(0)) {
Serial.println("ERROR 20");
return false;
}
return true;
}
I'm getting Error 1
Can you post a diagram or picture of your wiring? Also are there any other devices on that SPI bus?
It isn't the best picture, but it is now coming up with Error 3. If it is hard to see the pin numbers, NCS is connected to 10, SDO is connected to 11, SDI is connected to 12, and SCL is connected to 13. The MPU9250 is powered from a separate 3.3v power supply, with its ground tied to the Teensy.
Can you try replacing the write and read register methods with these? I've been using Teensy 4.1 on a PCB with the MPU-9250 and think I may have to loosen up the timing a bit for jumper wires.
bool Mpu9250::WriteRegister(uint8_t reg, uint8_t data) {
uint8_t ret_val;
if (iface_ == I2C) {
i2c_->beginTransmission(dev_);
i2c_->write(reg);
i2c_->write(data);
i2c_->endTransmission();
} else {
spi_->beginTransaction(SPISettings(spi_clock_, MSBFIRST, SPI_MODE3));
#if defined(TEENSYDUINO)
digitalWriteFast(dev_, LOW);
#else
digitalWrite(dev_, LOW);
#endif
#if defined(__IMXRT1062__)
delayNanoseconds(75);
#endif
spi_->transfer(reg);
spi_->transfer(data);
#if defined(TEENSYDUINO)
digitalWriteFast(dev_, HIGH);
#else
digitalWrite(dev_, HIGH);
#endif
#if defined(__IMXRT1062__)
delayNanoseconds(75);
#endif
spi_->endTransaction();
}
delay(10);
ReadRegisters(reg, sizeof(ret_val), &ret_val);
if (data == ret_val) {
return true;
} else {
return false;
}
}
bool Mpu9250::ReadRegisters(uint8_t reg, uint8_t count, uint8_t *data) {
if (iface_ == I2C) {
i2c_->beginTransmission(dev_);
i2c_->write(reg);
i2c_->endTransmission(false);
bytes_rx_ = i2c_->requestFrom(static_cast<uint8_t>(dev_), count);
if (bytes_rx_ == count) {
for (std::size_t i = 0; i < count; i++) {
data[i] = i2c_->read();
}
return true;
} else {
return false;
}
} else {
spi_->beginTransaction(SPISettings(spi_clock_, MSBFIRST, SPI_MODE3));
#if defined(TEENSYDUINO)
digitalWriteFast(dev_, LOW);
#else
digitalWrite(dev_, LOW);
#endif
#if defined(__IMXRT1062__)
delayNanoseconds(75);
#endif
spi_->transfer(reg | SPI_READ_);
spi_->transfer(data, count);
#if defined(TEENSYDUINO)
digitalWriteFast(dev_, HIGH);
#else
digitalWrite(dev_, HIGH);
#endif
#if defined(__IMXRT1062__)
delayNanoseconds(75);
#endif
spi_->endTransaction();
return true;
}
}
I have replaced the code with yours, which didn't work, but increasing the delayNanoseconds value to 100 got it to work about 50% of the time, with errors 7 and 20 the other half, and increasing it to 125 seems to make it work every time.
Updated to 125 ns delay on Teensy 4.1
I'm using the dRehm flight software which uses this MPU9250 library and I can not get the SPI2 to work properly with Teensy 4.1. I had everything working with Teensy 4.0 hardware, but with the 4.1 the magnetometer data freezes after running for a short time but the gyro and accel data read properly. I've read this thread but could not understand if the issue has been solved and if so, where is the updated MPU9250 library? I downloaded the latest MPU9250 source code but it has the same problem I described.
@mlbco, I use a Teensy 4.1 for my flight control system and don't experience magnetometer freezing. Are you sure that you're using SPI2? According to the Teensy pinout SPI2 is located with either the SD card or QSPI memory - both somewhat difficult to access and I have to admit that I didn't test with either. Most testing is with the SPI object (i.e. pins 10 - 13).
@flybrianfly I did solder to the connections on the SD card and I'm using SPI2. I'm using pins 42-45. I think the connections are good because all the other sensors work fine. Is it possible that one line affects the compass only and could have a bad connection? In this thread you mention some code changes and the code listed doesn't match anything in the libraries that came with the dRehm downloads. You mentioned changes in the library to make this work in your June 29 comment, but there's no mention of version numbers or where to find the latest code. A link to the latest MPU9250 code would be helpful, I'm new to GitHub and not good at figuring things out without clear instructions.
I did try using pins 10-13 and I commented out all the LED stuff that previously used pin 13, but then the Teensy 4.1 could not talk to the MPU9250 at all (Error initializing communication with IMU). I'm only using the 4 pins mentioned connected to SCK2, MOSI2, MISO2, CS2
@flybrianfly I solved my issues by abandoning the SPI ports and used the I2C ports instead. everything works now on Teensy 4.1
Glad you got it working. Just for reference:
The magnetometer with this MPU9250 library is accessed by writing and reading registers in the MPU9250, there is no direct access to the magnetometer by the host microcontroller.
Teensy 4.x code changes involved adding and adjusting the value of delayNanoseconds in the write and read register methods .
Latest code is here: https://github.com/bolderflight/invensense-imu
my i2c program works correctly but spi communication is showing "Error initializing communication with IMU" on serial monitor.i have used example program "spi".my connections are as follows