kriswiner / MPU9250

Arduino sketches for MPU9250 9DoF with AHRS sensor fusion
1.03k stars 471 forks source link

Demo/Request to use slave 0 to read Mag data into EXT_SENS_DATA #86

Open MikeFair opened 7 years ago

MikeFair commented 7 years ago

Hi all,

I thought I'd demo a different way to get the mag data from an MPU 9X5X. The current method uses the INT_BYPASS mode to access the mag data which works great if you only have 1 sensor connected; but as soon as you try using two it all breaks. It also requires two separate reads; one for the acel/gyro and one for the mag device.

Using the slaves you can make one request from the MPU and get all the data as 24 continuous bytes: 14 bytes for the accel/temp/gyro 2 bytes for info/status1 on mag 6 bytes for mag xyz 2 bytes for status2/control1 on mag

You could technically get away with only reading 7 bytes from the mag (xyz + status2), but by reading 10 bytes you also get the status1 register to examine and it keeps the whole buffer aligned on 16bit boundaries. Using the higher slaves to read other data, would place that data after this data. (The slave txns are executed in slave numeric order. So you can rearrange how the data gets laid out.)

An interesting feature of the slaves is they can automatically swap word bytes so that you can control the endianness of any 16bit word data being read.

====

The MPU units, as most of you are likely to be at least vaguely aware, can act as their own I2C master controller, reading/writing data to registers from their own mag as well as devices on the EDA/ECL bus. The read data is placed into EXT_SENS_DATA which are the 24 registers immediately above the Acc/Tmp/Gyr data.

For a complete picture there's two sets of slaves. Slaves 0-3 which effectively run every cycle and fill the data into EXT_SENS_DATA; and Slave 4 which is good for executing one time transactions.

I'm going to break these two things up into two comments. First configuring the I2C Master and Slaves 0-3, then a second comment on using Slave 4.

Configuring the I2C Master is pretty straight forward.

First disable INT_BYPASS, then configure the I2C master, then enable the I2C master:

void enableI2CMaster() {

    // First disable INT_BYPASS
    I2Cdev::writeByte(MPU9250_ADDRESS, INT_PIN_CONFIG, 0x00); // I prefer 0x30 or 0x20 here; but those values have nothing to do with I2C

    // Next configure the I2C Master
    // No other masters on the bus, unless there are (in which case switch this high bit)
    // Wait for external sensors to finish before data ready interrupt
    // No FIFO for Slave3 (which is actually about Slave3 and not the I2C Master)
    // Always issue a full stop, then a start when transitioning between slaves (instead of a restart)
    // Access the bus at 400kHz (see table in register map for other values)
    I2Cdev::writeByte(MPU9250_ADDRESS, I2C_MST_CTRL, 0x5D);

    // Lastly, enable the I2C Master on the MPU
    I2Cdev::writeByte(MPU9250_ADDRESS, USER_CTRL, 0x20);

}

Configuring the slaves is even less complicated; set the address, set the register, set the controls to tell the slave what to do. The only "tricky" part I found was that to read from a slave device address you need to set the high bit on the address slave_device_address = (0x80 | slave_device_address);.

A helper function makes setting up the slaves so much easier:

#define I2C_SLV_ENABLE_BIT      7
#define I2C_SLV_BYTESWP_BIT     6
#define I2C_SLV_REG_DIS_BIT     5
#define I2C_SLV_SWP_GRP_BIT     4
#define I2C_SLV_READ_LEN_BIT    3
#define I2C_SLV_READ_LEN_LENGTH 4

void setupSlave(uint8_t primary_address, uint8_t slave_id
            , uint8_t dev_addr, uint8_t reg_addr, bool is_read, uint8_t read_length
            , bool send_reg_addr, bool swap_bytes, bool odd_aligned
            , bool enable) 
{
    if (slave_id > 3) return;

    uint8_t I2C_SLV_START = I2C_SLV0_ADDR + slave_id*3;

    writeByte(primary_address, I2C_SLV_START + 2, 0x00); // Disable slave while we reconfigure it
    dev_addr = ((is_read) ? 0x80 : 0x00) | dev_addr); // Write(0x00) or Read(0x80) from device
    writeByte(primary_address, I2C_SLV_START + 0, dev_addr); // set the slave device address
    writeByte(primary_address, I2C_SLV_START + 1, reg_addr); // set the slave register address
    uint8_t slave_ctrl_byte = 
          (enable << I2C_SLV_ENABLE_BIT)
        | (swap_bytes << I2C_SLV_BYTESWP_BIT)
        | (!send_reg_addr << I2C_SLV_REG_DIS_BIT)
        | (odd_aligned << I2C_SLV_SWP_GRP_BIT)
        | (read_length % 16)
    ;
    writeByte(primary_address, I2C_SLV_START + 2, slave_ctrl_byte); // set the slave control byte
    // And we're done
}

To use that function to set up reading the mag into EXT_SENS_DATA using the functions in this library, you would do something like:

    mpu9250.initMPU9250(); 
    mpu9250.initAK8963(magCalibration);

    mpu9250.enableI2CMaster();
    mpu9250.setupSlave(
              0                   /* Setup Slave0 */
            , AK8963_ADDRESS      /* Read from the Mag device */
            , INFO                /* Start at the AK8963_INFO register -- this #define should be updated */
            , true                /* is_read */
            , 10                  /* read 10 bytes, most importantly this includes a read of STATUS2 */
            , true                /* send_reg_addr */
            , true                /* swap word bytes on read - make it the same endianness as MPU data*/
            , false               /* use even swap alignment */
            , true                /* enable it with this call */
    ); 

    uint8_t rawData[38];
    mpu9250.readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 38, rawData);

    // What you should notice is all the data coming in at byte 14 and above 
    Serial.print("[");
    for (int i = 0; i < 38; i += 2) {
        String b1 = String(rawData[i], HEX);
        String b2 = String(rawData[i+1], HEX);
        b1 = ((b1.length() < 2) ? "0" : "") + b1;
        b2 = ((b2.length() < 2) ? "0" : "") + b2;
        Serial.print("0x" +  b1 + b2 + ", ");
    }   
    Serial.println("]");
MikeFair commented 7 years ago

Moving on to explain how Slave4, the one I like to call the "immediate transaction slave" works. As you've probably guessed, this one doesn't poll every cycle; you enable it, it does its thing just like the other slaves, then disables itself.

There are flags in the I2C_MST_STATUS register for a NACK on each of the Slaves, I2C_SLV4_DONE, I2C_LOST_ARB, and whether or not the FSYNC interrupt has happend (FSYNC and PASS_THROUGH provide a way to pass interrupts from chips on the "hidden" i2c bus through to the host; ignored from here on).

Once SLV4 is enabled, it will begin working its txn. The I2C_SLV4_DONE flag will go high either when the txn completes or times out (SLV4_NACK also goes high). A control flag can enable the txn completion triggering an interrupt. While a slightly more advanced approach, and requiring an extra wire to the device, if you're thinking of doing a lot of Slave4 work, I think it's likely worth the effort. What I'm doing below are spin loops waiting for the done flag to get set.

Slave4 only works with one byte at a time.
While the others can write one byte or read up to 15 bytes; Slave4 has only two registers it works with. It gets the byte for a write txn from Register 0x33 (51) I2C_SLV4_DO. It puts the results of a read txn in Register 0x35 (53) I2C_SLV4_DI.

That all said, it configures in much the same way the other slaves do.
Set the device address, set the register, set the write byte if required, set the control flags, which includes enabling the slave and off it goes.

As Slave4 only works with single bytes a txn, there are no byte swapping or read length controls. There is an I2C_SLV4_REG_DIS (disable writing the register address at txn start) and a SLV4_DONE_INT_EN to trigger the interrupt when the txn completes. There is also an I2C_MST_DLY for all the slaves to alter the frequency of slave device polling, but I'm ignoring that for these comments.

Like the other Slaves, it helps to have a few helper functions to make working with the Slave easier:

#define I2C_SLV4_EN_BIT      7
#define SLV4_DONE_INT_EN_BIT 6
#define I2C_SLV4_REG_DIS_BIT 5
#define I2C_SLV4_DONE_BIT    6
#define I2C_SLV4_NACK_BIT    4

bool writeSlave4Byte(uint8_t primary_address, uint8_t dev_addr, uint8_t reg_addr, bool send_reg_addr, uint8_t data) {
  return execSlave4Txn(primary_address, dev_addr, reg_addr, send_reg_addr, false, 1, &data);
}

bool writeSlave4Bytes(uint8_t primary_address, uint8_t dev_addr, uint8_t reg_addr, bool send_reg_addr, uint8_t count, uint8_t* data) {
  return execSlave4Txn(primary_address, dev_addr, reg_addr, send_reg_addr, false, count, data);
}

bool readSlave4Byte(uint8_t primary_address, uint8_t dev_addr, uint8_t reg_addr, bool send_reg_addr, uint8_t* data) {
  return execSlave4Txn(primary_address, dev_addr, reg_addr, send_reg_addr, true, 1, data);
}

bool readSlave4Bytes(uint8_t primary_address, uint8_t dev_addr, uint8_t reg_addr, bool send_reg_addr, uint8_t count, uint8_t* data) {
  return execSlave4Txn(primary_address, dev_addr, reg_addr, send_reg_addr, true, count, data);
}

bool execSlave4Txn(uint8_t primary_address, uint8_t dev_addr, uint8_t reg_addr, bool send_reg_addr, bool is_read, uint8_t count, uint8_t *data) 
{
  // Use Slave4 to read/write from/to a device on the EDA/ECL bus
  dev_addr = ((is_read) ? 0x80 : 0x00) | dev_addr);     // Write(0x00) or Read(0x80) from device
  writeByte(primary_address, I2C_SLV4_ADDR, dev_addr);  // set the slave device address
  writeByte(primary_address, I2C_SLV4_REG, reg_addr);   // set the slave register address
  uint8_t slave_ctrl_byte = 
        (1 << I2C_SLV4_ENABLE_BIT)                // The whole point of this function is to execute txns
      //| (trg_int << SLV4_DONE_INT_EN_BIT)         // Because of spin loop, don't use the interrupt
      | (!send_reg_addr << I2C_SLV4_REG_DIS_BIT)  // Affects first txn only; does not send reg after that
      //| (i2c_mst_delay % 32)                      // Ignoring this; read it in the docs if you're curious
  ;

  uint8_t i2c_mst_status;                // Variable to watch the status on Slave4Done and Slave4NACK
  bool txnFailed = false;                // Did the txn fail (Save4Nack or timeout)?
  uint8_t nByte = 0;
  while (nByte < count) {
    if (!is_read) writeByte(primary_address, I2C_SLV4_DO, data[nByte]); // Upload the byte to write 

    writeByte(primary_address, I2C_SLV4_CTRL, slave_ctrl_byte);         // Kick off the txn
    slave_ctrl_byte = (1 << I2C_SLV4_ENABLE_BIT);  // Disable register send for all remaining txns

    long tsTimeout = millis() + 3000;  // Emergency timeout for txn (hard coded to 3 secs)
    bool slave4Done = false;
    while (!slave4Done) { 
      // Poll the I2C Master Status byte; this resets all NACK flags, the SLV4_Done, and LOST_ARB
      readByte(primary_addres, I2C_MST_STATUS, &i2c_mst_status);

      // Is the Slave4Done bit set or has timeout expired?
      slave4Done = ((i2c_mst_status & (1<< I2C_SLV4_DONE_BIT)) > 0) | (millis() > tsTimeout);

      //Print some debug status information to track the state while looping
      //Serial.print(slave4Done, HEX); Serial.print("\t");
      //Serial.print(i2c_mst_status & (1<< I2C_SLV4_NACK_BIT), HEX); Serial.print("\t");
      //Serial.println(i2c_mst_status, HEX);
    }
    // Is the Slave4NACK bit set or did the timeout expire?
    txnFailed = (i2c_mst_status & (1 << I2C_SLV4_NACK_BIT)) | (millis() > tsTimeout);
    if (txnFailed) break;                  // If txnFailed then stop looping and quit

    if (is_read) readByte(primary_addres, I2C_SLV4_DI, &data[nByte]);  // Fetch the byte that was read

    nByte++;
  }
  return !txnFailed;
}

Once we have those functions, we can work through Slave4 similarly to other normal I2C calls. This is useful for setting up things like the magnetometer or other devices without having to first rely on using the I2C_BYPASS.
Assuming the Bypass is disabled, and the I2C Master has been configured and enabled, to configure the AK8963 on an mpu925X is as simple as replacing the readByte(s)/writeByte(s) calls with the equivalent readSlave4Byte(s)/writeSlave4Byte(s) calls.

Using the current code from MPU9250.h in this repository would look something like this:

    void initAK8963(float * destination) {
        // First extract the factory calibration for each magnetometer axis
        uint8_t rawData[3];  // x/y/z gyro calibration data stored here
        writeSlave4Byte(MPU9250_ADDRESS, AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer  
        wait(0.01);
        writeSlave4Byte(MPU9250_ADDRESS, AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode
        wait(0.01);
        readSlave4Bytes(MPU9250_ADDRESS, AK8963_ADDRESS, AK8963_ASAX, 3, &rawData[0]);  // Read the x-, y-, and z-axis calibration values
        destination[0] =  (float)(rawData[0] - 128)/256.0f + 1.0f;   // Return x-axis sensitivity adjustment values, etc.
        destination[1] =  (float)(rawData[1] - 128)/256.0f + 1.0f;  
        destination[2] =  (float)(rawData[2] - 128)/256.0f + 1.0f; 
        writeSlave4Byte(MPU9250_ADDRESS, AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer  
        wait(0.01);
        // Configure the magnetometer for continuous read and highest resolution
        // set Mscale bit 4 to 1 (0) to enable 16 (14) bit resolution in CNTL register,
        // and enable continuous mode data acquisition Mmode (bits [3:0]), 0010 for 8 Hz and 0110 for 100 Hz sample rates
        writeSlave4Byte(MPU9250_ADDRESS, AK8963_ADDRESS, AK8963_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR
        wait(0.01);
}

Assuming Slave 0 had been configured during the MPU initialization, once this init routine is finished, the data will begin appearing in the EXT_SENS_DATA registers automatically.

You can dynamically enable/disable and reconfigure the Slaves at any time, and you can issue one-off requests using Slave 4. The only thing you can't really do is have Slaves loopback and request data from its own MPU; they are strictly downstream requests.

Hope that helps!

kriswiner commented 7 years ago

Excellent!

I will try this myself in the next few days and if (when?) successful post a new sketch on github capturing the method. Invensense really packed a lot of capability into the MPU9250 but it is rarely used well; even their own API is rather clunky in this regard. I hope their next 9 DoF motion sensor (ICS20948 http://www.invensense.com/wp-content/uploads/2016/06/ICM-20948-Product-Brief.pdf) is as well designed. I have asked them to include a separate interrupt for mag data ready (the AK magnetometers have one) for some other application that really needs it (using an external sensor hub to manage the three sensors) but using the slave registers ought to make this unnecessary as long as there is enough RAM in the sensor hub...

Great work!

Kris

MikeFair commented 7 years ago

Thanks!

The technique exists all the way back to the MPU6050s.

I think the slaves definitely make a huge difference; I'd want more EXT_SENS registers and the ability to submit I2C requests via a FIFO, then pick up the results from a different FIFO. That way I can read/write to slave devices more than 1 byte at a time and handle larger loads.

BTW there is a way to pass_through interrupts from downstream slave devices through to the host machine. And I think I saw references to enabling slave requests based on the incoming FSYNC interrupt... but that might just be wishful thinking on my part.

Like most things I also can't take full credit on this; I got the basic techniques from some code either in the FreeIMU project or another MPU[69]X5X library project here on GitHub I looked at. It just showed me the the basic method to configure a slave, I then took it from there to add all the extra stuff you saw above.

I really miss the ZERO_MOTION_DETECT feature of the 6050.

I couldn't really use the DETECT_MOTION features, but I used the ZERO_MOTION_DETECT to help with calibrating by ignoring any samples when motion was detected.

As for the slaves, at 24 bytes, I am currently getting 10 bytes from the mag (0x01 - 0x0A), and 14 bytes from an MPU6050 (G/A XYZ + temp). I can poll the status flags via Slave 4 but clearly it needs some work.

I look forward to hearing how you fare!

fereshtemohebbi commented 7 years ago

thanks for your explanation, I have question 1)mpu9250.readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 38, rawData); in the line that you have mentioned I use this line "mpu9250.readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 14, rawData)" to read accel and gyro raw values but why you use it to read data for magnetometer and would you explain how can I read mag[x],mag[y] and mag[z] and would it be ok to publish your code here

kriswiner commented 7 years ago

There are sketches that show how to do this at my repository.

fereshtemohebbi commented 7 years ago

I cant find in your sketches that you use EXT_SENS_DATA for multiple mpu

  1. I have problem for reading multiple i2c mag data due to that I want to use this EXT_SENS_DATA but I dont understand why he read ACCEL_XOUT_H and how can I get data for mag[x], mag[y] and mag[z] and also how can I have access to accel and gyro

On Sun, Mar 26, 2017 at 6:08 PM, Kris Winer notifications@github.com wrote:

There are sketches that show how to do this at my repository.

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU-9250/issues/86#issuecomment-289293892, or mute the thread https://github.com/notifications/unsubscribe-auth/AYU1ONn442bqgwUQj1K6aIINlz2vD3J0ks5rpo2SgaJpZM4KsD21 .

kriswiner commented 7 years ago

Don't know, ask Mike.

On Sun, Mar 26, 2017 at 9:22 AM, fereshtemohebbi notifications@github.com wrote:

I cant find in your sketches that you use EXT_SENS_DATA for multiple mpu

  1. I have problem for reading multiple i2c mag data due to that I want to use this EXT_SENS_DATA but I dont understand why he read ACCEL_XOUT_H and how can I get data for mag[x], mag[y] and mag[z] and also how can I have access to accel and gyro

On Sun, Mar 26, 2017 at 6:08 PM, Kris Winer notifications@github.com wrote:

There are sketches that show how to do this at my repository.

— You are receiving this because you commented. Reply to this email directly, view it on GitHub <https://github.com/kriswiner/MPU-9250/issues/86#issuecomment-289293892 , or mute the thread https://github.com/notifications/unsubscribe-auth/ AYU1ONn442bqgwUQj1K6aIINlz2vD3J0ks5rpo2SgaJpZM4KsD21 .

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU-9250/issues/86#issuecomment-289294677, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qmKA2UFOWgsr3ooUZpfixm9B1cU6ks5rppC8gaJpZM4KsD21 .

MikeFair commented 7 years ago

Hey guys! :)

I read 38 bytes starting at ACCEL_X because I am reading all the values in one fetch. The first 14 are as you expect, XYZ for Accel/Gyro + Temp for the MPU. (14 bytes)

The next 10 are status + XYZ for the Mag. (24 bytes)

The next 14 is data for a 2nd MPU6050 slave device. (34 bytes) I am reading data for 2 MPUs and the Magnetometer. If you look at the register layout the EXT_SENS_DATA registers are directly after the Accel/Temp/Gyro registers. So rather than make multiple smaller fetches; I fetch the whole thing in one call.

You have to have the settings preconfigured for that to work obviously. On Mar 26, 2017 2:57 AM, "fereshtemohebbi" notifications@github.com wrote:

thanks for your explanation, I have question 1)mpu9250.readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 38, rawData); in the line that you have mentioned I use this line "mpu9250.readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 14, rawData)" to read accel and gyro raw values but you use it to read data for magnetometer and how can I read data for accel and gyro and mag to use it sory I dont understand clearly

— You are receiving this because you authored the thread. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU-9250/issues/86#issuecomment-289269813, or mute the thread https://github.com/notifications/unsubscribe-auth/ACMqLd0hGduVwf0YD6PJPb37RUfozCITks5rpjZygaJpZM4KsD21 .

fereshtemohebbi commented 7 years ago

Hi could you let me know how can I have data for mag for two MPU 9250 cause I want mag data for both mpu?Is is possible whith this method ?

PatelKishanJ commented 6 years ago

hey winer,

I am using ur code.its working fine. but my issue is that i can not get constant/reliable data of yaw,pitch and roll even getting almost constant data of 9axis raw data.

i have attached one file of output what i had got. please,check it and if any suggestion please tell me.

i am waiting..... kris_winer_yaw_pitch_roll.xlsx

MikeFair commented 6 years ago

I didn't look at the files you attached, but one thing to keep in mind is the frequency of your requests.

The MPU has to poll the Magnetometer and get the response data. That's going to happen at a particular rate. IIRC, there is a state flag for each slave indicates new data has arrived in the ext_sens_data registers.

I don't recall if I mentioned that the status register on the magnetomoter has to be queried before the magnetometer will update its register values (though I think that behavior may be configurable).

You cannot collect data faster than new data is collected by the MPU from the magnetometer.

I don't know if either of those are what you are encountering, but definitely something to keep in mind.

Most of the speed/signalling parameters are configurable.

Don't forget you also have the ability to configure the Magnetometer settings via a similar mechanism (put the command/data you want in a register and then trigger slave4 to write it; you can technically use any slave, but slave4 is designated for "one-time" instant read/write operations (look for the status flag to see when it's completed).

I hope that helps.

Mike On Dec 4, 2017 4:55 AM, "jenextech" notifications@github.com wrote:

hey winer,

I am using ur code.its working fine. but my issue is that i can not get constant/reliable data of yaw,pitch and roll even getting almost constant data of 9axis raw data.

i have attached one file of output what i had got. please,check it and if any suggestion please tell me.

i am waiting..... kris_winer_yaw_pitch_roll.xlsx https://github.com/kriswiner/MPU9250/files/1527095/kris_winer_yaw_pitch_roll.xlsx

— You are receiving this because you authored the thread. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-348954470, or mute the thread https://github.com/notifications/unsubscribe-auth/ACMqLQ5hVE2BINmuIYJE2jhQWLQQiJBzks5s8-vNgaJpZM4KsD21 .

PatelKishanJ commented 6 years ago

Thanks Mike, I have used KrisWiner's firmware as it is. And here is also used status flag which indicate that new data has received.

I have not add any extra configuration,I can get 9-axis data to almost constant. So,is there any formula issue to calculate yaw,pitch and roll?.

Because,i could not get constant value even device is stable.

You should just check output reading which is attached in above file. If any configuration/calibration have to add,please tell me.

MikeFair commented 6 years ago

I'll leave you in the capable hands of others and forum docs.

One thing to keep in mind is callibrating your partlicular device; the factory provides an initial callibration but even if the device has been callibrated, I found "stable" is a relative term.

There is a clear, noticeable, and well known "wobble" in the raw data (and explanations for its origins online); I personally worked on some algorithms of my own to smooth this out, but never finished them in favor of using the more mature algorithms.

My older phone has consistently refused to open the xlsx file you attached; sorry about not taking a look at the data you provided.

If you haven't run a callibration program before, I recommend it to get some good offset values for your particular chip. I wouldn't expect to get a perfectly stable reading when the device is still.

There are motion algorithms available online you can use to make the readings smoother and take into account the magnetometer data.

If it looks like new data is coming in, and the numbers just look "jumpy"; I'd first look into running a callibration program on the chip. If the raw data seems reasonably stable but one axis continuously "drifts", then this sounds normal and incorporating the magnetometer data might help correct it. The magnetometer and the MPU are callibrated separately, I don't know if the code you have, collects and commits the callibration offsets using the slave registers. I didn't get that code working to my own satisfaction to submit it.

Let me know if you think I can help further, and I'll let others take a look to see if they can spot something more instructive/useful for your case.

Mike On Dec 4, 2017 8:43 PM, "jenextech" notifications@github.com wrote:

Thanks Mike, I have used KrisWiner's firmware as it is. And here is also used status flag which indicate that new data has received.

I have not add any extra configuration,I can get 9-axis data to almost constant. So,is there any formula issue to calculate yaw,pitch and roll?.

Because,i could not get constant value even device is stable.

You should just check output reading which is attached in above file. If any configuration/calibration have to add,please tell me.

— You are receiving this because you authored the thread. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-349193935, or mute the thread https://github.com/notifications/unsubscribe-auth/ACMqLfpxw5fGmlzUwRXXmFEWVH-QI3zBks5s9MnygaJpZM4KsD21 .

PatelKishanJ commented 6 years ago

Thanks Mike, I have update calibration value and 9-axis data as below.If you will got anything to calibrate,share it.

device_id=71 x gyro bias = -1.946565 y gyro bias = -15.259542 z gyro bias = 2.274809 x accel bias = 0.944153 y accel bias = -0.015198 z accel bias = 0.993713 MPU9250 initialized for active data mode....

device_id=48 AK8963 initialized for active data mode.... Accelerometer full-scale range = 2.000000 g Gyroscope full-scale range = 250.000000 deg/s Magnetometer resolution = 16 bits Magnetometer ODR = 100 Hz Accelerometer sensitivity is 16384.000000 LSB/g Gyroscope sensitivity is 131.072006 LSB/deg/s Magnetometer sensitivity is 0.666938 LSB/G

ax ay az gx gy gz mx my mz -1.062439 0.033142 -0.051453 0.001069 14.534749 -4.220304 -335.142792 -290.819122 15.427203

ax ay az gx gy gz mx my mz -1.062988 0.034180 -0.052734 0.115510 14.572896 -4.197416 -327.950409 -276.434357 22.361879

ax ay az gx gy gz mx my mz -1.063904 0.035156 -0.047119 -0.029448 14.336385 -4.258451 -317.161835 -301.607697 22.361879

ax ay az gx gy gz mx my mz -1.063293 0.033020 -0.051147 0.039216 14.481343 -4.266081 -318.959930 -285.424835 31.030218

ax ay az gx gy gz mx my mz -1.063416 0.032288 -0.049683 0.046846 14.542378 -4.212675 -331.546600 -290.819122 25.829210

ax ay az gx gy gz mx my mz -1.064758 0.033875 -0.047058 -0.059966 14.504231 -4.243193 -326.152313 -299.809601 27.562880

ax ay az gx gy gz mx my mz -1.064697 0.031311 -0.050537 0.031587 14.496602 -4.304228 -336.940887 -296.213409 20.628210 Thanks.

MikeFair commented 6 years ago

Just looking at the samples the Accel and Gyro data seems normal; the magnetometer data seems a little noisier than I'd expect. I'm not sure what the scale/reference point for the values is, but they look fairly consistent/stable to me.

If you decrease the sensistivity, do the numbers get more stable? If they do, that's a sign it's all working properly.

Are there any magnets nearby? Like external speakers, a microwave, a neodymium magnet based desktop toy, a magnetic catch on a desk drawer, a magnetic mount for something, or anything like that?

The device is pretty sensitive to those kinds of things.

The only other thing I see are that the numbers presented are float values, but the raw data from the device is always an integer. Something is dividing the raw values by the scale maximums to give you a float.

If possible it might be better to look at the raw integer data to see how much it fluctuates.

As for callibration, a GitHub search MPU9250 callibration should bring back a few programs you can work from...

Does that help? On Dec 4, 2017 10:37 PM, "jenextech" notifications@github.com wrote:

Thanks Mike, I have update calibration value and 9-axis data as below.If you will got anything to calibrate,share it.

device_id=71 x gyro bias = -1.946565 y gyro bias = -15.259542 z gyro bias = 2.274809 x accel bias = 0.944153 y accel bias = -0.015198 z accel bias = 0.993713 MPU9250 initialized for active data mode....

device_id=48 AK8963 initialized for active data mode.... Accelerometer full-scale range = 2.000000 g Gyroscope full-scale range = 250.000000 deg/s Magnetometer resolution = 16 bits Magnetometer ODR = 100 Hz Accelerometer sensitivity is 16384.000000 LSB/g Gyroscope sensitivity is 131.072006 LSB/deg/s Magnetometer sensitivity is 0.666938 LSB/G

ax ay az gx gy gz mx my mz -1.062439 0.033142 -0.051453 0.001069 14.534749 -4.220304 -335.142792 -290.819122 15.427203

ax ay az gx gy gz mx my mz -1.062988 0.034180 -0.052734 0.115510 14.572896 -4.197416 -327.950409 -276.434357 22.361879

ax ay az gx gy gz mx my mz -1.063904 0.035156 -0.047119 -0.029448 14.336385 -4.258451 -317.161835 -301.607697 22.361879

ax ay az gx gy gz mx my mz -1.063293 0.033020 -0.051147 0.039216 14.481343 -4.266081 -318.959930 -285.424835 31.030218

ax ay az gx gy gz mx my mz -1.063416 0.032288 -0.049683 0.046846 14.542378 -4.212675 -331.546600 -290.819122 25.829210

ax ay az gx gy gz mx my mz -1.064758 0.033875 -0.047058 -0.059966 14.504231 -4.243193 -326.152313 -299.809601 27.562880

ax ay az gx gy gz mx my mz -1.064697 0.031311 -0.050537 0.031587 14.496602 -4.304228 -336.940887 -296.213409 20.628210

Thanks.

— You are receiving this because you authored the thread. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-349210386, or mute the thread https://github.com/notifications/unsubscribe-auth/ACMqLUwZ4cShGqeQ_5RmNiPwO-CoPB8Aks5s9OTHgaJpZM4KsD21 .

PatelKishanJ commented 6 years ago

Thanks Mike, I measure reading by giving power_supply by my system.So,may be it makes noise. I will try by make distance from it and i will also check raw_data reading.

PatelKishanJ commented 6 years ago

I have check log as below: where, ax_r means raw data value,same for other 8 axis-data. ax means calibrated_final_data using KrisWiner code. I have also convert quaternion data to rotation_matrix...also display it.

Still required to calibrate,please tell. Because,i want to find distance and orientaton threw this reding.So,it should be fix and proper for me.

device_id=71 x gyro bias = -1.862595 y gyro bias = 0.732824 z gyro bias = -6.816794 x accel bias = 0.945557 y accel bias = -0.016174 z accel bias = 0.996094 MPU9250 initialized for active data mode....

device_id=48 AK8963 initialized for active data mode.... Accelerometer full-scale range = 2.000000 g Gyroscope full-scale range = 250.000000 deg/s Magnetometer resolution = 16 bits Magnetometer ODR = 100 Hz Accelerometer sensitivity is 16384.000000 LSB/g Gyroscope sensitivity is 131.072006 LSB/deg/s Magnetometer sensitivity is 0.666938 LSB/G

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 58 -818 15670 -257 -60 -247 -8 -142 100

ax ay az gx gy gz mx my mz -0.942017 -0.033752 -0.039673 -0.098159 -1.190588 4.932333 -484.384766 -375.329651 48.366909

yaw pitch roll 162.696152 24.822048 133.094376

ROTATION_MATRIX AS BELOW........

-0.905919 -0.264224 0.330901 0.055469 0.700660 0.711336 -0.419801 0.662768 -0.620085

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 79 -853 15648 -259 -70 -265 -16 -144 100

ax ay az gx gy gz mx my mz -0.940735 -0.035889 -0.041016 -0.113418 -1.266882 4.795004 -498.769531 -378.925842 48.366909

yaw pitch roll 48.345482 78.518448 -16.830492

ROTATION_MATRIX AS BELOW........

0.093003 -0.978840 0.182271 0.175989 0.196343 0.964612 -0.979989 -0.057634 0.190526

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 95 -878 15633 -277 -72 -258 -8 -144 100

ax ay az gx gy gz mx my mz -0.939758 -0.037415 -0.041931 -0.250747 -1.282141 4.848410 -484.384766 -378.925842 48.366909

yaw pitch roll -81.715759 87.354836 -150.316055

ROTATION_MATRIX AS BELOW........

0.017351 -0.991018 0.132599 -0.042765 0.131762 0.990358 -0.998935 -0.022855 -0.040095

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 88 -907 15647 -261 -92 -252 -11 -137 93

ax ay az gx gy gz mx my mz -0.940186 -0.039185 -0.041077 -0.128677 -1.434729 4.894186 -489.779053 -366.339172 36.231224

yaw pitch roll 45.921852 76.284050 -19.645824

ROTATION_MATRIX AS BELOW........

0.119550 -0.977997 0.170965 0.204764 0.192785 0.959638 -0.971483 -0.079717 0.223306

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 81 -884 15666 -259 -81 -258 -1 -139 103

ax ay az gx gy gz mx my mz -0.940613 -0.037781 -0.039917 -0.113418 -1.350805 4.848410 -471.798096 -369.935364 53.567917

yaw pitch roll -78.975075 87.570770 -147.332397

ROTATION_MATRIX AS BELOW........

0.017795 -0.990443 0.136772 -0.038467 0.136014 0.989960 -0.999101 -0.022877 -0.035679

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 81 -857 15635 -268 -85 -250 -1 -139 97

ax ay az gx gy gz mx my mz -0.940613 -0.036133 -0.041809 -0.182082 -1.381323 4.909445 -471.798096 -369.935364 43.165901

yaw pitch roll 49.303986 72.772797 -14.326246

ROTATION_MATRIX AS BELOW........

0.133975 -0.971010 0.197965 0.264125 0.227528 0.937267 -0.955138 -0.073283 0.286951

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 117 -908 15678 -284 -90 -248 -11 -147 101

ax ay az gx gy gz mx my mz -0.938416 -0.039246 -0.039185 -0.304153 -1.419470 4.924704 -489.779053 -384.320129 50.100578

yaw pitch roll -76.751038 87.531769 -145.528839

ROTATION_MATRIX AS BELOW........

0.019583 -0.991382 0.129527 -0.038354 0.128712 0.990940 -0.999072 -0.024374 -0.035502

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 104 -915 15674 -255 -60 -243 -2 -138 92

ax ay az gx gy gz mx my mz -0.939209 -0.039673 -0.039429 -0.082900 -1.190588 4.962851 -473.596191 -368.137268 34.497555

yaw pitch roll 38.578651 76.643295 -27.043373

ROTATION_MATRIX AS BELOW........

0.141019 -0.975499 0.168867 0.182976 0.193314 0.963924 -0.972951 -0.105033 0.205754

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 99 -886 15622 -260 -74 -246 -4 -146 96

ax ay az gx gy gz mx my mz -0.939514 -0.037903 -0.042603 -0.121047 -1.297400 4.939963 -477.192383 -382.522034 41.432232

yaw pitch roll -84.565193 87.042160 -153.172195

ROTATION_MATRIX AS BELOW........

0.016999 -0.991034 0.132527 -0.048721 0.131568 0.990109 -0.998668 -0.023288 -0.046047

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 114 -854 15649 -245 -68 -256 -8 -132 98

ax ay az gx gy gz mx my mz -0.938599 -0.035950 -0.040955 -0.006606 -1.251623 4.863669 -484.384766 -357.348663 44.899570

yaw pitch roll 45.130932 65.955505 -16.686594

ROTATION_MATRIX AS BELOW........

0.210271 -0.955801 0.205500 0.348996 0.269734 0.897466 -0.913229 -0.116993 0.390288

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 106 -851 15620 -258 -61 -248 -5 -141 99

ax ay az gx gy gz mx my mz -0.939087 -0.035767 -0.042725 -0.105788 -1.198218 4.924704 -478.990479 -373.531555 46.633240

yaw pitch roll -86.312508 87.166687 -154.622406

ROTATION_MATRIX AS BELOW........

0.014853 -0.990376 0.137606 -0.047145 0.136774 0.989480 -0.998778 -0.021185 -0.044660

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 110 -866 15603 -269 -72 -257 -9 -145 99

ax ay az gx gy gz mx my mz -0.938843 -0.036682 -0.043762 -0.189712 -1.282141 4.856040 -486.182861 -380.723938 46.633240

yaw pitch roll 38.425022 74.759277 -25.831165

ROTATION_MATRIX AS BELOW........

0.161027 -0.968964 0.187561 0.207782 0.219065 0.953329 -0.964830 -0.114540 0.236609

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 115 -864 15642 -253 -56 -253 -6 -140 104

ax ay az gx gy gz mx my mz -0.938538 -0.036560 -0.041382 -0.067641 -1.160071 4.886557 -480.788574 -371.733459 55.301586

yaw pitch roll -83.092056 87.432037 -150.956024

ROTATION_MATRIX AS BELOW........

0.015842 -0.989262 0.145288 -0.041907 0.144522 0.988614 -0.998996 -0.021750 -0.039168

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 108 -825 15658 -264 -84 -250 -4 -134 102

ax ay az gx gy gz mx my mz -0.938965 -0.034180 -0.040405 -0.151565 -1.373694 4.909445 -477.192383 -360.944855 51.834248

yaw pitch roll 21.539698 79.833984 -44.448318

ROTATION_MATRIX AS BELOW........

0.143978 -0.975190 0.168148 0.102092 0.183650 0.977676 -0.984300 -0.123598 0.126001

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 86 -841 15701 -275 -92 -254 -13 -149 99

ax ay az gx gy gz mx my mz -0.940308 -0.035156 -0.037781 -0.235488 -1.434729 4.878928 -493.375244 -387.916321 46.633240

yaw pitch roll -78.734177 87.837242 -148.151001

ROTATION_MATRIX AS BELOW........

0.015988 -0.992841 0.118369 -0.034183 0.117772 0.992452 -0.999288 -0.019913 -0.032056

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 81 -875 15666 -285 -91 -246 -12 -148 102

ax ay az gx gy gz mx my mz -0.940613 -0.037231 -0.039917 -0.311782 -1.427099 4.939963 -491.577148 -386.118225 51.834248

yaw pitch roll -123.668327 77.509277 165.112457

ROTATION_MATRIX AS BELOW........

-0.073505 -0.994157 0.079048 -0.203407 0.092541 0.974711 -0.976331 0.055567 -0.209021

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 73 -870 15599 -268 -81 -240 -13 -151 117

ax ay az gx gy gz mx my mz -0.941101 -0.036926 -0.044006 -0.182082 -1.350805 4.985739 -493.375244 -391.512512 77.839287

yaw pitch roll -71.746681 88.273186 -138.794189

ROTATION_MATRIX AS BELOW........

0.015992 -0.987110 0.159243 -0.025540 0.158808 0.986979 -0.999546 -0.019851 -0.022671

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 92 -872 15608 -265 -68 -251 -5 -135 97

ax ay az gx gy gz mx my mz -0.939941 -0.037048 -0.043457 -0.159194 -1.251623 4.901816 -478.990479 -362.742981 43.165901

yaw pitch roll -130.233780 77.424515 157.998917

ROTATION_MATRIX AS BELOW........

-0.096923 -0.993008 0.067387 -0.194962 0.085336 0.977091 -0.976010 0.081565 -0.201870

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 82 -886 15576 -247 -66 -242 -10 -136 96

ax ay az gx gy gz mx my mz -0.940552 -0.037903 -0.045410 -0.021865 -1.236364 4.970480 -487.980957 -364.541077 41.432232

yaw pitch roll -84.469070 87.183800 -153.429642

ROTATION_MATRIX AS BELOW........

0.016264 -0.991849 0.126374 -0.046361 0.125507 0.991009 -0.998792 -0.021976 -0.043942

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 100 -896 15565 -252 -72 -259 -7 -139 103

ax ay az gx gy gz mx my mz -0.939453 -0.038513 -0.046082 -0.060012 -1.282141 4.840781 -482.586670 -369.935364 53.567917

yaw pitch roll 37.427292 61.402271 -21.983044

ROTATION_MATRIX AS BELOW........

0.299751 -0.928773 0.218014 0.373179 0.324463 0.869173 -0.878002 -0.179177 0.443856

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 104 -872 15613 -241 -61 -251 -19 -131 113

ax ay az gx gy gz mx my mz -0.939209 -0.037048 -0.043152 0.023911 -1.198218 4.901816 -504.163818 -355.550568 70.904610

yaw pitch roll -81.950302 87.749176 -148.819092

ROTATION_MATRIX AS BELOW........

0.014616 -0.986619 0.162387 -0.036451 0.161770 0.986155 -0.999228 -0.020333 -0.033598

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 96 -864 15623 -250 -76 -247 -14 -142 94

ax ay az gx gy gz mx my mz -0.939697 -0.036560 -0.042542 -0.044753 -1.312658 4.932333 -495.173340 -375.329651 37.964893

yaw pitch roll -78.085617 79.334633 -148.448456

ROTATION_MATRIX AS BELOW........

0.080300 -0.990893 0.108089 -0.166745 0.093557 0.981552 -0.982725 -0.096842 -0.157713

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 81 -858 15680 -268 -70 -259 -10 -138 100

ax ay az gx gy gz mx my mz -0.940613 -0.036194 -0.039062 -0.182082 -1.266882 4.840781 -487.980957 -368.137268 48.366909

yaw pitch roll -66.023987 88.180374 -134.119827

ROTATION_MATRIX AS BELOW........

0.019451 -0.989792 0.141188 -0.025098 0.140687 0.989736 -0.999496 -0.022795 -0.022105

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 99 -835 15662 -262 -74 -246 -15 -145 99

ax ay az gx gy gz mx my mz -0.939514 -0.034790 -0.040161 -0.136306 -1.297400 4.939963 -496.971436 -380.723938 46.633240

yaw pitch roll -45.178703 82.953766 -112.375626

ROTATION_MATRIX AS BELOW........

0.104729 -0.981717 0.158942 -0.063873 0.152851 0.986183 -0.992447 -0.113434 -0.046698

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 98 -830 15666 -272 -85 -258 -6 -144 102

ax ay az gx gy gz mx my mz -0.939575 -0.034485 -0.039917 -0.212600 -1.381323 4.848410 -480.788574 -378.925842 51.834248

yaw pitch roll 41.931934 87.180191 -24.668131

ROTATION_MATRIX AS BELOW........

0.027698 -0.985712 0.166148 0.040653 0.167185 0.985087 -0.998789 -0.020531 0.044703

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 109 -886 15631 -273 -84 -261 -12 -142 102

ax ay az gx gy gz mx my mz -0.938904 -0.037903 -0.042053 -0.220229 -1.373694 4.825522 -491.577148 -375.329651 51.834248

yaw pitch roll -72.955688 87.005653 -141.900375

ROTATION_MATRIX AS BELOW........

0.026782 -0.991561 0.126842 -0.044848 0.125568 0.991071 -0.998635 -0.032231 -0.041106

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 72 -909 15606 -264 -76 -255 -3 -145 97

ax ay az gx gy gz mx my mz -0.941162 -0.039307 -0.043579 -0.151565 -1.312658 4.871298 -475.394287 -380.723938 43.165901

yaw pitch roll 44.928894 82.317543 -20.909254

ROTATION_MATRIX AS BELOW........

0.069394 -0.982029 0.175512 0.114263 0.182602 0.976525 -0.991024 -0.047710 0.124881

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 92 -846 15600 -275 -76 -262 -3 -139 105

ax ay az gx gy gz mx my mz -0.939941 -0.035461 -0.043945 -0.235488 -1.312658 4.817893 -475.394287 -369.935364 57.035255

yaw pitch roll -83.726097 87.351662 -152.017715

ROTATION_MATRIX AS BELOW........

0.015860 -0.990317 0.137913 -0.043400 0.137119 0.989604 -0.998932 -0.021681 -0.040805

MikeFair commented 6 years ago

These outputs all look very normal to me. Lots of numbers that stay within a very close range to each other.

I'm not sure you'll get good results trying to create a meaningful rotation matrix because of the noise.

The Invensense IMUs are difficult to get an accurate "distance travelled" from. Many people around the internet have created projects to do AHRS with them and found them unreliable at measuring "distance travelled"; there is simply too much noise. Lots of correction/averaging, and quite frankly error, has to be introduced to get something that looks stable.

The IMUs are great for "macro direction travelled", "orientation", "moving versus standing still versus spinning", but not for "distance moved".

If you were to try it, keep track of several readings worth of values and average them together. And look up the Madgwick and other MPU Motion packages out there that incorporate the magnetometer data to try and stabilize the output by making it more "internally consistent" to itself and prior readings.

You still can't get very accurate distances travelled.

In the code I was working on, where I knew someone was holding the unit, I decreased the sensitivity, averaged the last ten readings together, and threw away small changes in values. This stabilized the output, especially for the minor vibrations of people's hands moving while they are holding still, but gave up detecting small movements.

To my knowledge, no one has yet found a reliable way to distinguish the difference between small movements and sensor data noise.

As for doing the callibration, try this thread: https://github.com/kriswiner/MPU9250/issues/120

The program expects the chip to be oriented "up" when it runs; it simply tests a number of offsets to get as close to 0 as it can for gyro/accel (except for the vertical direction which it tries to match gravity at 1.0 or 16384). I don't recall how it determines the magnetometer offsets.

The point of the callibration is to compensate for any unique variations in the manufacturing process for that specific chip. It's similar to the idea of a "tare weight" if you're familiar with that term from weighing boxes (you want to subtract the weight of the box itself).

Callibration will not make the output numbers more stable. It simply provides an offset to get as close to zero as it can while the object is at rest. Unfortunately, an accurate offset changes with chip temperature. The documentation has more on that.

The output of the callibration progeam will give you a series of numbers to use as offsets for the IMU and Magnetometer. You take those numbers, and load them to the chip's offset registers. I believe the magnetometer is stored in a persistent RAM that remembers across power cycles, and the accel/gyro are remembered across "soft resets" but not across power cycles. (I had a sketch/hardware that would draw too much power and "brown out" the MPU, causing it to require reinitialization while running.)

FWIW, the data you are receiving looks normal to me. Try reading online and find some YouTube videos on AHRS with Invensense MPU9250 and MPU6050. You'll want to see how others have approached compensating for the noise (including taking readings from multiple IMUs in different orientations and averaging the two that are closest to each other).

Mike On Dec 5, 2017 6:11 AM, "jenextech" notifications@github.com wrote:

I have check log as below: where, ax_r means raw data value,same for other 8 axis-data. ax means calibrated_final_data using KrisWiner code. I have also convert quaternion data to rotation_matrix...also display it.

Still required to calibrate,please tell. Because,i want to find distance and orientaton threw this reding.So,it should be fix and proper for me.

device_id=71 x gyro bias = -1.862595 y gyro bias = 0.732824 z gyro bias = -6.816794 x accel bias = 0.945557 y accel bias = -0.016174 z accel bias = 0.996094 MPU9250 initialized for active data mode....

device_id=48 AK8963 initialized for active data mode.... Accelerometer full-scale range = 2.000000 g Gyroscope full-scale range = 250.000000 deg/s Magnetometer resolution = 16 bits Magnetometer ODR = 100 Hz Accelerometer sensitivity is 16384.000000 LSB/g Gyroscope sensitivity is 131.072006 LSB/deg/s Magnetometer sensitivity is 0.666938 LSB/G

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 58 -818 15670 -257 -60 -247 -8 -142 100

ax ay az gx gy gz mx my mz -0.942017 -0.033752 -0.039673 -0.098159 -1.190588 4.932333 -484.384766 -375.329651 48.366909

yaw pitch roll 162.696152 24.822048 133.094376

ROTATION_MATRIX AS BELOW........

-0.905919 -0.264224 0.330901 0.055469 0.700660 0.711336 -0.419801 0.662768 -0.620085

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 79 -853 15648 -259 -70 -265 -16 -144 100

ax ay az gx gy gz mx my mz -0.940735 -0.035889 -0.041016 -0.113418 -1.266882 4.795004 -498.769531 -378.925842 48.366909

yaw pitch roll 48.345482 78.518448 -16.830492

ROTATION_MATRIX AS BELOW........

0.093003 -0.978840 0.182271 0.175989 0.196343 0.964612 -0.979989 -0.057634 0.190526

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 95 -878 15633 -277 -72 -258 -8 -144 100

ax ay az gx gy gz mx my mz -0.939758 -0.037415 -0.041931 -0.250747 -1.282141 4.848410 -484.384766 -378.925842 48.366909

yaw pitch roll -81.715759 87.354836 -150.316055

ROTATION_MATRIX AS BELOW........

0.017351 -0.991018 0.132599 -0.042765 0.131762 0.990358 -0.998935 -0.022855 -0.040095

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 88 -907 15647 -261 -92 -252 -11 -137 93

ax ay az gx gy gz mx my mz -0.940186 -0.039185 -0.041077 -0.128677 -1.434729 4.894186 -489.779053 -366.339172 36.231224

yaw pitch roll 45.921852 76.284050 -19.645824

ROTATION_MATRIX AS BELOW........

0.119550 -0.977997 0.170965 0.204764 0.192785 0.959638 -0.971483 -0.079717 0.223306

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 81 -884 15666 -259 -81 -258 -1 -139 103

ax ay az gx gy gz mx my mz -0.940613 -0.037781 -0.039917 -0.113418 -1.350805 4.848410 -471.798096 -369.935364 53.567917

yaw pitch roll -78.975075 87.570770 -147.332397

ROTATION_MATRIX AS BELOW........

0.017795 -0.990443 0.136772 -0.038467 0.136014 0.989960 -0.999101 -0.022877 -0.035679

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 81 -857 15635 -268 -85 -250 -1 -139 97

ax ay az gx gy gz mx my mz -0.940613 -0.036133 -0.041809 -0.182082 -1.381323 4.909445 -471.798096 -369.935364 43.165901

yaw pitch roll 49.303986 72.772797 -14.326246

ROTATION_MATRIX AS BELOW........

0.133975 -0.971010 0.197965 0.264125 0.227528 0.937267 -0.955138 -0.073283 0.286951

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 117 -908 15678 -284 -90 -248 -11 -147 101

ax ay az gx gy gz mx my mz -0.938416 -0.039246 -0.039185 -0.304153 -1.419470 4.924704 -489.779053 -384.320129 50.100578

yaw pitch roll -76.751038 87.531769 -145.528839

ROTATION_MATRIX AS BELOW........

0.019583 -0.991382 0.129527 -0.038354 0.128712 0.990940 -0.999072 -0.024374 -0.035502

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 104 -915 15674 -255 -60 -243 -2 -138 92

ax ay az gx gy gz mx my mz -0.939209 -0.039673 -0.039429 -0.082900 -1.190588 4.962851 -473.596191 -368.137268 34.497555

yaw pitch roll 38.578651 76.643295 -27.043373

ROTATION_MATRIX AS BELOW........

0.141019 -0.975499 0.168867 0.182976 0.193314 0.963924 -0.972951 -0.105033 0.205754

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 99 -886 15622 -260 -74 -246 -4 -146 96

ax ay az gx gy gz mx my mz -0.939514 -0.037903 -0.042603 -0.121047 -1.297400 4.939963 -477.192383 -382.522034 41.432232

yaw pitch roll -84.565193 87.042160 -153.172195

ROTATION_MATRIX AS BELOW........

0.016999 -0.991034 0.132527 -0.048721 0.131568 0.990109 -0.998668 -0.023288 -0.046047

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 114 -854 15649 -245 -68 -256 -8 -132 98

ax ay az gx gy gz mx my mz -0.938599 -0.035950 -0.040955 -0.006606 -1.251623 4.863669 -484.384766 -357.348663 44.899570

yaw pitch roll 45.130932 65.955505 -16.686594

ROTATION_MATRIX AS BELOW........

0.210271 -0.955801 0.205500 0.348996 0.269734 0.897466 -0.913229 -0.116993 0.390288

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 106 -851 15620 -258 -61 -248 -5 -141 99

ax ay az gx gy gz mx my mz -0.939087 -0.035767 -0.042725 -0.105788 -1.198218 4.924704 -478.990479 -373.531555 46.633240

yaw pitch roll -86.312508 87.166687 -154.622406

ROTATION_MATRIX AS BELOW........

0.014853 -0.990376 0.137606 -0.047145 0.136774 0.989480 -0.998778 -0.021185 -0.044660

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 110 -866 15603 -269 -72 -257 -9 -145 99

ax ay az gx gy gz mx my mz -0.938843 -0.036682 -0.043762 -0.189712 -1.282141 4.856040 -486.182861 -380.723938 46.633240

yaw pitch roll 38.425022 74.759277 -25.831165

ROTATION_MATRIX AS BELOW........

0.161027 -0.968964 0.187561 0.207782 0.219065 0.953329 -0.964830 -0.114540 0.236609

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 115 -864 15642 -253 -56 -253 -6 -140 104

ax ay az gx gy gz mx my mz -0.938538 -0.036560 -0.041382 -0.067641 -1.160071 4.886557 -480.788574 -371.733459 55.301586

yaw pitch roll -83.092056 87.432037 -150.956024

ROTATION_MATRIX AS BELOW........

0.015842 -0.989262 0.145288 -0.041907 0.144522 0.988614 -0.998996 -0.021750 -0.039168

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 108 -825 15658 -264 -84 -250 -4 -134 102

ax ay az gx gy gz mx my mz -0.938965 -0.034180 -0.040405 -0.151565 -1.373694 4.909445 -477.192383 -360.944855 51.834248

yaw pitch roll 21.539698 79.833984 -44.448318

ROTATION_MATRIX AS BELOW........

0.143978 -0.975190 0.168148 0.102092 0.183650 0.977676 -0.984300 -0.123598 0.126001

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 86 -841 15701 -275 -92 -254 -13 -149 99

ax ay az gx gy gz mx my mz -0.940308 -0.035156 -0.037781 -0.235488 -1.434729 4.878928 -493.375244 -387.916321 46.633240

yaw pitch roll -78.734177 87.837242 -148.151001

ROTATION_MATRIX AS BELOW........

0.015988 -0.992841 0.118369 -0.034183 0.117772 0.992452 -0.999288 -0.019913 -0.032056

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 81 -875 15666 -285 -91 -246 -12 -148 102

ax ay az gx gy gz mx my mz -0.940613 -0.037231 -0.039917 -0.311782 -1.427099 4.939963 -491.577148 -386.118225 51.834248

yaw pitch roll -123.668327 77.509277 165.112457

ROTATION_MATRIX AS BELOW........

-0.073505 -0.994157 0.079048 -0.203407 0.092541 0.974711 -0.976331 0.055567 -0.209021

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 73 -870 15599 -268 -81 -240 -13 -151 117

ax ay az gx gy gz mx my mz -0.941101 -0.036926 -0.044006 -0.182082 -1.350805 4.985739 -493.375244 -391.512512 77.839287

yaw pitch roll -71.746681 88.273186 -138.794189

ROTATION_MATRIX AS BELOW........

0.015992 -0.987110 0.159243 -0.025540 0.158808 0.986979 -0.999546 -0.019851 -0.022671

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 92 -872 15608 -265 -68 -251 -5 -135 97

ax ay az gx gy gz mx my mz -0.939941 -0.037048 -0.043457 -0.159194 -1.251623 4.901816 -478.990479 -362.742981 43.165901

yaw pitch roll -130.233780 77.424515 157.998917

ROTATION_MATRIX AS BELOW........

-0.096923 -0.993008 0.067387 -0.194962 0.085336 0.977091 -0.976010 0.081565 -0.201870

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 82 -886 15576 -247 -66 -242 -10 -136 96

ax ay az gx gy gz mx my mz -0.940552 -0.037903 -0.045410 -0.021865 -1.236364 4.970480 -487.980957 -364.541077 41.432232

yaw pitch roll -84.469070 87.183800 -153.429642

ROTATION_MATRIX AS BELOW........

0.016264 -0.991849 0.126374 -0.046361 0.125507 0.991009 -0.998792 -0.021976 -0.043942

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 100 -896 15565 -252 -72 -259 -7 -139 103

ax ay az gx gy gz mx my mz -0.939453 -0.038513 -0.046082 -0.060012 -1.282141 4.840781 -482.586670 -369.935364 53.567917

yaw pitch roll 37.427292 61.402271 -21.983044

ROTATION_MATRIX AS BELOW........

0.299751 -0.928773 0.218014 0.373179 0.324463 0.869173 -0.878002 -0.179177 0.443856

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 104 -872 15613 -241 -61 -251 -19 -131 113

ax ay az gx gy gz mx my mz -0.939209 -0.037048 -0.043152 0.023911 -1.198218 4.901816 -504.163818 -355.550568 70.904610

yaw pitch roll -81.950302 87.749176 -148.819092

ROTATION_MATRIX AS BELOW........

0.014616 -0.986619 0.162387 -0.036451 0.161770 0.986155 -0.999228 -0.020333 -0.033598

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 96 -864 15623 -250 -76 -247 -14 -142 94

ax ay az gx gy gz mx my mz -0.939697 -0.036560 -0.042542 -0.044753 -1.312658 4.932333 -495.173340 -375.329651 37.964893

yaw pitch roll -78.085617 79.334633 -148.448456

ROTATION_MATRIX AS BELOW........

0.080300 -0.990893 0.108089 -0.166745 0.093557 0.981552 -0.982725 -0.096842 -0.157713

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 81 -858 15680 -268 -70 -259 -10 -138 100

ax ay az gx gy gz mx my mz -0.940613 -0.036194 -0.039062 -0.182082 -1.266882 4.840781 -487.980957 -368.137268 48.366909

yaw pitch roll -66.023987 88.180374 -134.119827

ROTATION_MATRIX AS BELOW........

0.019451 -0.989792 0.141188 -0.025098 0.140687 0.989736 -0.999496 -0.022795 -0.022105

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 99 -835 15662 -262 -74 -246 -15 -145 99

ax ay az gx gy gz mx my mz -0.939514 -0.034790 -0.040161 -0.136306 -1.297400 4.939963 -496.971436 -380.723938 46.633240

yaw pitch roll -45.178703 82.953766 -112.375626

ROTATION_MATRIX AS BELOW........

0.104729 -0.981717 0.158942 -0.063873 0.152851 0.986183 -0.992447 -0.113434 -0.046698

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 98 -830 15666 -272 -85 -258 -6 -144 102

ax ay az gx gy gz mx my mz -0.939575 -0.034485 -0.039917 -0.212600 -1.381323 4.848410 -480.788574 -378.925842 51.834248

yaw pitch roll 41.931934 87.180191 -24.668131

ROTATION_MATRIX AS BELOW........

0.027698 -0.985712 0.166148 0.040653 0.167185 0.985087 -0.998789 -0.020531 0.044703

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 109 -886 15631 -273 -84 -261 -12 -142 102

ax ay az gx gy gz mx my mz -0.938904 -0.037903 -0.042053 -0.220229 -1.373694 4.825522 -491.577148 -375.329651 51.834248

yaw pitch roll -72.955688 87.005653 -141.900375

ROTATION_MATRIX AS BELOW........

0.026782 -0.991561 0.126842 -0.044848 0.125568 0.991071 -0.998635 -0.032231 -0.041106

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 72 -909 15606 -264 -76 -255 -3 -145 97

ax ay az gx gy gz mx my mz -0.941162 -0.039307 -0.043579 -0.151565 -1.312658 4.871298 -475.394287 -380.723938 43.165901

yaw pitch roll 44.928894 82.317543 -20.909254

ROTATION_MATRIX AS BELOW........

0.069394 -0.982029 0.175512 0.114263 0.182602 0.976525 -0.991024 -0.047710 0.124881

ax_r ay_r az_r gx_r gy_r gz_r mx_r my_r mz_r 92 -846 15600 -275 -76 -262 -3 -139 105

ax ay az gx gy gz mx my mz -0.939941 -0.035461 -0.043945 -0.235488 -1.312658 4.817893 -475.394287 -369.935364 57.035255

yaw pitch roll -83.726097 87.351662 -152.017715

ROTATION_MATRIX AS BELOW........

0.015860 -0.990317 0.137913 -0.043400 0.137119 0.989604 -0.998932 -0.021681 -0.040805

— You are receiving this because you authored the thread. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-349315173, or mute the thread https://github.com/notifications/unsubscribe-auth/ACMqLRVoeYuvy_uA1FPiPNq9ezq6r48nks5s9U8RgaJpZM4KsD21 .

PatelKishanJ commented 6 years ago

Thanks Mikes, Your reply has very meaningful for me. I will follow your suggestion.

PatelKishanJ commented 6 years ago

Hello Mike, I have one doubt is how can find declination angle? I have find equations online. you can see it by link as below.

http://www.pveducation.org/pvcdrom/properties-of-sunlight/declination-angle

But,as i think declination angle will different for different location. So,any formula to find it for specific location.

utpalban commented 6 years ago

I am new to this IoT programming. What is maximum sample rate I can achive from MPU9250. I am using SimpleLink TI2650. Let me what need to do to in stack and app of the source code from TI. Thanks in advance

kriswiner commented 6 years ago

Depends on what you want to sample. 100 Hz for the mag, 8 kHz for the gyro, 1 kHz for the accel. Read the data sheet.

On Mon, Feb 12, 2018 at 5:53 AM, utpalban notifications@github.com wrote:

I am new to this IoT programming. What is maximum sample rate I can achive from MPU9250. I am using SimpleLink TI2650. Let me what need to do to in stack and app of the source code from TI. Thanks in advance

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-364928654, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qpA0fYH2-Oyzp3jXegtRKpNy4pItks5tUEJtgaJpZM4KsD21 .

noega33 commented 6 years ago

Hi, I'm trying to put together a system made of 4 MPU9255 that are connected to a Teensy 3.2 board. I'm using both I2C buses each one using 2 MPU addresses (0x68 & 0x69) . In order to access all four magnetomer readings, I need to use Mikefair technic (using FIFO). For the time being I'm not successful making it work (I tried to assemble the different software blocs as explained by Mikefaire but this is not working). My question: Is there somewhere a complete code that wil get magnetometer values to the serial monitor? Note: even if it is made of one sensor only Thank you in advance Noega33

kriswiner commented 6 years ago

https://github.com/kriswiner/MPU9250/blob/master/MPU9250_MS5637_AHRS_t3.ino

you might need to strip out the parts you don't want/need.

On Sun, Feb 18, 2018 at 3:18 AM, noega33 notifications@github.com wrote:

Hi, I'm trying to put together a system made of 4 MPU9255 that are connected to a Teensy 3.2 board. I'm using both I2C buses each one using 2 MPU addresses (0x68 & 0x69) . In order to access all four magnetomer readings, I need to use Mikefair technic (using FIFO). For the time being I'm not successful making it work (I tried to assemble the different software blocs as explained by Mikefaire but this is not working). My question: Is there somewhere a complete code that wil get magnetometer values to the serial monitor? Note: even if it is made of one sensor only Thank you in advance Noega33

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-366508819, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qqxNnKp1xUp-RzNACiKc1deIJCaHks5tWAb0gaJpZM4KsD21 .

noega33 commented 6 years ago

Thank you Kris I've already used some of your code. But this does not solve my issue of getting data from 4 MPU9250 (including 4 magnétométers data) into one teensy 3.2 Rgds

MikeFair commented 6 years ago

@noega33

I provided initialization code helper functions in my first posts.

One thing about my example code to handle your case is that you probably need to make sure you are telling the MPU and the helper functions which i2c bus and which MPU primary_address to talk on. You have to initialize each of the 4 MPUs individually, and poll them each individually.

You might run into an issue trying to initialize MAG devices on an i2c bus with multiple MAGs because they have the exact same i2c address (completely separated from the MPU addresses). You must either configure the MPUs to enable the I2C_PASSTHROUGH on only 1 MAG on the bus at a time; or configure the MAG via the I2C_Master and Slaves on each MPU (I give code for that in my second comment).

This piece of sample code from the original posts demonstrates setting up the MPU and reading the full data set:

    mpu9250.initMPU9250(); 
    mpu9250.initAK8963(magCalibration);

    mpu9250.enableI2CMaster();
    mpu9250.setupSlave(
              0                   /* Setup Slave0 */
            , AK8963_ADDRESS      /* Read from the Mag device */
            , INFO                /* Start at the AK8963_INFO register -- this #define should be updated */
            , true                /* is_read */
            , 10                  /* read 10 bytes, most importantly this includes a read of STATUS2 */
            , true                /* send_reg_addr */
            , true                /* swap word bytes on read - make it the same endianness as MPU data*/
            , false               /* use even swap alignment */
            , true                /* enable it with this call */
    ); 

    uint8_t rawData[38];
    mpu9250.readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 38, rawData);

    // What you should notice is all the data coming in at byte 14 and above 
    Serial.print("[");
    for (int i = 0; i < 38; i += 2) {
        String b1 = String(rawData[i], HEX);
        String b2 = String(rawData[i+1], HEX);
        b1 = ((b1.length() < 2) ? "0" : "") + b1;
        b2 = ((b2.length() < 2) ? "0" : "") + b2;
        Serial.print("0x" +  b1 + b2 + ", ");
    }   
    Serial.println("]");

You'll have to play with this code, and the whole library to make your case work.

You have two i2c busses, you'll want to ensure the code is properly talking on the MPUs respective bus. You have two MAGs on each bus which have the same i2c address; the library's default code cannot initialize the MAGs that way (you have to either disconnect one of the MAGs by disabling the I2C_PASSTHROUGH on the other MPU, or you have to first enable both MPUs to have their I2C Master working and configure each MAG through the Slave4).


I recommend you use the following procedure. 1) Turn off the I2C_PASSTHROUGH on the 0x68 MPU to make sure its MAG can't see the i2c bus 2) Initialize the 0x69 MPU using the library's normal code 3) Call mpu9250.initAK8963(magCalibration); on the 0x69 MPU 4) Initialize the slave devices on the 0x69 MPU (turning off the I2C_PASSTHROUGH) 5) Initialize the 0x68 MPU9250 using the library's normal code (this reeanables the I2C_PASSTHROUGH) 6) Call mpu9250.initAK8963(magCalibration); on the 0x68 MPU 7) Initialize the slave devices on 0x68 MPU (turning off the I2C_PASSTHROUGH)

At that point the MAG should be appearing in the EXT_SENS_DATA fields on each MPU.

kriswiner commented 6 years ago

Thanks Mike, much more detailed answer than I was going to provide.

The key here is the pass through mode. You need to disable pass through mode on all MPU250s except the one whose mag you want to talk with on 0x0C. Your protocol will have to enable, read, disable, repeat. If you are using 2 I2C busses, then this should be rather straightforward since you only have two mags on each bus and you can create two functions, passthroughenable(address) and passthroughdisable(address).

Then any operation to read/configure the mag requires:

passthroughenable(0x68); ...configure or read mag on 0x0C passthroughdisable(0x68);

passthroughenable(0x69); ...configure or read mag on 0x0C passthroughdisable(0x69);

etc

If you had more than two devices on an I2C bus you could use the same procedure but would have to slew through all of the devices one at a time, using the ADO to set all of their addresses to 0x68 except for the one you want to talk with, this would be 0x69. Then read/configure as above, reset address to 0x68 and move on to the next, set its address to 0x69, etc.

On Mon, Feb 19, 2018 at 9:36 AM, Mike Fair notifications@github.com wrote:

@noega33 https://github.com/noega33

I provided initialization code helper functions in my first posts.

One thing about my example code to handle your case is that you probably need to make sure you are telling the MPU and the helper functions which i2c bus and which MPU primary_address to talk on. You have to initialize each of the 4 MPUs individually, and poll them each individually.

You might run into an issue trying to initialize MAG devices on an i2c bus with multiple MAGs because they have the exact same i2c address (completely separated from the MPU addresses). You must either configure the MPUs to enable the I2C_PASSTHROUGH or only 1 MAG on the bus at a time; or configure the MAG via the I2C_Master and Slaves on each MPU (I give code for that in my second comment).

This piece of sample code from the original posts demonstrates setting up the MPU and reading the full data set:

mpu9250.initMPU9250();
mpu9250.initAK8963(magCalibration);

mpu9250.enableI2CMaster();
mpu9250.setupSlave(
          0                   /* Setup Slave0 */
        , AK8963_ADDRESS      /* Read from the Mag device */
        , INFO                /* Start at the AK8963_INFO register -- this #define should be updated */
        , true                /* is_read */
        , 10                  /* read 10 bytes, most importantly this includes a read of STATUS2 */
        , true                /* send_reg_addr */
        , true                /* swap word bytes on read - make it the same endianness as MPU data*/
        , false               /* use even swap alignment */
        , true                /* enable it with this call */
);

uint8_t rawData[38];
mpu9250.readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 38, rawData);

// What you should notice is all the data coming in at byte 14 and above
Serial.print("[");
for (int i = 0; i < 38; i += 2) {
    String b1 = String(rawData[i], HEX);
    String b2 = String(rawData[i+1], HEX);
    b1 = ((b1.length() < 2) ? "0" : "") + b1;
    b2 = ((b2.length() < 2) ? "0" : "") + b2;
    Serial.print("0x" +  b1 + b2 + ", ");
} 
Serial.println("]");

You'll have to play with this code, and the whole library to make your case work. You have two i2c busses, you'll want to ensure the code is properly talking on the MPUs respective bus. You have two MAGs on each bus which have the same i2c address; the libraries default code cannot initialize the MAGs that way (you have to either disconnect one of the MAGs by disabling the I2C_PASSTHROUGH on the other MPU, or you have to first both MPUs to have their I2C Master working and configure each MAG through the Slave4).

I recommend you use the following procedure.

  1. Turn off the I2C_PASSTHROUGH on the 0x68 MPU to make sure its MAG can't see the i2c bus
  2. Initialize the 0x69 MPU using the library's normal code
  3. Call mpu9250.initAK8963(magCalibration); on the 0x69 MPU
  4. Initialize the slave devices on the 0x69 MPU (turning off the I2C_PASSTHROUGH)
  5. Initialize the 0x68 MPU9250 using the library's normal code (this reeanables the I2C_PASSTHROUGH)
  6. Call mpu9250.initAK8963(magCalibration); on the 0x68 MPU
  7. Initialize the slave devices on 0x68 MPU (turning off the I2C_PASSTHROUGH)

    • repeat the above for each i2c bus

At that point the MAG should be appearing in the EXT_SENS_DATA fields.

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-366760624, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qo9ttZG5WlJctK5MRleNVnSyTgC3ks5tWbEhgaJpZM4KsD21 .

MikeFair commented 6 years ago

This situation does bring up a good point, I was wondering if it would help to add a "PASSTHROUGH enable" boolean to the MPU9250 initialize function (default true). Inside the MPU9250 class this would set a boolean flag that indicates if PASSTHROUGH should be "usually on" or "usually off" for the IMU.

Then mpu9250.initAK8963(magCalibration); uses this flag to enable PASSTHROUGH if required, initialize the MAG, then disable it again if required. If all the MAG interaction functions were bookended by these wrapper functions I think people dealing with a couple IMUs on a bus would have a much easier time. I haven't looked lately, but it'd also be nice if my "configure slave" helper functions were added to the class.

I'm not saying that the code should go all the way to fully supporting a "Read MAG from MPU" and support two modes for reading the MAG data; simply a few direct methods for configuring and reading from the slave devices and their EXT_SENS_DATA.

On Mon, Feb 19, 2018 at 9:49 AM, Kris Winer notifications@github.com wrote:

Thanks Mike, much more detailed answer than I was going to provide.

The key here is the pass through mode. You need to disable pass through mode on all MPU250s except the one whose mag you want to talk with on 0x0C. Your protocol will have to enable, read, disable, repeat. If you are using 2 I2C busses, then this should be rather straightforward since you only have two mags on each bus and you can create two functions, passthroughenable(address) and passthroughdisable(address).

Then any operation to read/configure the mag requires:

passthroughenable(0x68); ...configure or read mag on 0x0C passthroughdisable(0x68);

passthroughenable(0x69); ...configure or read mag on 0x0C passthroughdisable(0x69);

etc

If you had more than two devices on an I2C bus you could use the same procedure but would have to slew through all of the devices one at a time, using the ADO to set all of their addresses to 0x68 except for the one you want to talk with, this would be 0x69. Then read/configure as above, reset address to 0x68 and move on to the next, set its address to 0x69, etc.

On Mon, Feb 19, 2018 at 9:36 AM, Mike Fair notifications@github.com wrote:

@noega33 https://github.com/noega33

I provided initialization code helper functions in my first posts.

One thing about my example code to handle your case is that you probably need to make sure you are telling the MPU and the helper functions which i2c bus and which MPU primary_address to talk on. You have to initialize each of the 4 MPUs individually, and poll them each individually.

You might run into an issue trying to initialize MAG devices on an i2c bus with multiple MAGs because they have the exact same i2c address (completely separated from the MPU addresses). You must either configure the MPUs to enable the I2C_PASSTHROUGH or only 1 MAG on the bus at a time; or configure the MAG via the I2C_Master and Slaves on each MPU (I give code for that in my second comment).

This piece of sample code from the original posts demonstrates setting up the MPU and reading the full data set:

mpu9250.initMPU9250(); mpu9250.initAK8963(magCalibration);

mpu9250.enableI2CMaster(); mpu9250.setupSlave( 0 / Setup Slave0 / , AK8963_ADDRESS / Read from the Mag device / , INFO / Start at the AK8963_INFO register -- this #define should be updated / , true / is_read / , 10 / read 10 bytes, most importantly this includes a read of STATUS2 / , true / send_reg_addr / , true / swap word bytes on read - make it the same endianness as MPU data/ , false / use even swap alignment / , true / enable it with this call / );

uint8_t rawData[38]; mpu9250.readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 38, rawData);

// What you should notice is all the data coming in at byte 14 and above Serial.print("["); for (int i = 0; i < 38; i += 2) { String b1 = String(rawData[i], HEX); String b2 = String(rawData[i+1], HEX); b1 = ((b1.length() < 2) ? "0" : "") + b1; b2 = ((b2.length() < 2) ? "0" : "") + b2; Serial.print("0x" + b1 + b2 + ", "); } Serial.println("]");

You'll have to play with this code, and the whole library to make your case work. You have two i2c busses, you'll want to ensure the code is properly talking on the MPUs respective bus. You have two MAGs on each bus which have the same i2c address; the libraries default code cannot initialize the MAGs that way (you have to either disconnect one of the MAGs by disabling the I2C_PASSTHROUGH on the other MPU, or you have to first both MPUs to have their I2C Master working and configure each MAG through the Slave4).

I recommend you use the following procedure.

  1. Turn off the I2C_PASSTHROUGH on the 0x68 MPU to make sure its MAG can't see the i2c bus
  2. Initialize the 0x69 MPU using the library's normal code
  3. Call mpu9250.initAK8963(magCalibration); on the 0x69 MPU
  4. Initialize the slave devices on the 0x69 MPU (turning off the I2C_PASSTHROUGH)
  5. Initialize the 0x68 MPU9250 using the library's normal code (this reeanables the I2C_PASSTHROUGH)
  6. Call mpu9250.initAK8963(magCalibration); on the 0x68 MPU
  7. Initialize the slave devices on 0x68 MPU (turning off the I2C_PASSTHROUGH)
  • repeat the above for each i2c bus

At that point the MAG should be appearing in the EXT_SENS_DATA fields.

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-366760624, or mute the thread https://github.com/notifications/unsubscribe-auth/ AGY1qo9ttZG5WlJctK5MRleNVnSyTgC3ks5tWbEhgaJpZM4KsD21 .

— You are receiving this because you authored the thread. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-366763609, or mute the thread https://github.com/notifications/unsubscribe-auth/ACMqLZvv77vtg0Rpy5G2Tw1lGVxzCnjvks5tWbQrgaJpZM4KsD21 .

kriswiner commented 6 years ago

I am certainly not opposed. In the end this really isn't that hard for someone who is familiar with Arduino (C++) and the MPU9250. Maybe this is a smaller universe of people's than I might have thought.

I think what would be very valuable (I don't have the patience for it) would be a simple example showing how to read two MPU9250's (mags and all) on a single I2C bus. The downside is a lot of people want a black box and don't want to take the trouble to understand what they are doing, so I can imagine a lot of people will complain that the example doesn't work for them and/or their specific use case. Yet if it were well-commented and constructed for pedagogical purposes, this might go a long way to answering the need.

On Mon, Feb 19, 2018 at 2:05 PM, Mike Fair notifications@github.com wrote:

This situation does bring up a good point, I was wondering if it would help to add a "PASSTHROUGH enable" boolean to the MPU9250 initialize function (default true). Inside the MPU9250 class this would set a boolean flag that indicates if PASSTHROUGH should be "usually on" or "usually off" for the IMU.

Then mpu9250.initAK8963(magCalibration); uses this flag to enable PASSTHROUGH if required, initialize the MAG, then disable it again if required. If all the MAG interaction functions were bookended by these wrapper functions I think people dealing with a couple IMUs on a bus would have a much easier time. I haven't looked lately, but it'd also be nice if my "configure slave" helper functions were added to the class.

I'm not saying that the code should go all the way to fully supporting a "Read MAG from MPU" and support two modes for reading the MAG data; simply a few direct methods for configuring and reading from the slave devices and their EXT_SENS_DATA.

On Mon, Feb 19, 2018 at 9:49 AM, Kris Winer notifications@github.com wrote:

Thanks Mike, much more detailed answer than I was going to provide.

The key here is the pass through mode. You need to disable pass through mode on all MPU250s except the one whose mag you want to talk with on 0x0C. Your protocol will have to enable, read, disable, repeat. If you are using 2 I2C busses, then this should be rather straightforward since you only have two mags on each bus and you can create two functions, passthroughenable(address) and passthroughdisable(address).

Then any operation to read/configure the mag requires:

passthroughenable(0x68); ...configure or read mag on 0x0C passthroughdisable(0x68);

passthroughenable(0x69); ...configure or read mag on 0x0C passthroughdisable(0x69);

etc

If you had more than two devices on an I2C bus you could use the same procedure but would have to slew through all of the devices one at a time, using the ADO to set all of their addresses to 0x68 except for the one you want to talk with, this would be 0x69. Then read/configure as above, reset address to 0x68 and move on to the next, set its address to 0x69, etc.

On Mon, Feb 19, 2018 at 9:36 AM, Mike Fair notifications@github.com wrote:

@noega33 https://github.com/noega33

I provided initialization code helper functions in my first posts.

One thing about my example code to handle your case is that you probably need to make sure you are telling the MPU and the helper functions which i2c bus and which MPU primary_address to talk on. You have to initialize each of the 4 MPUs individually, and poll them each individually.

You might run into an issue trying to initialize MAG devices on an i2c bus with multiple MAGs because they have the exact same i2c address (completely separated from the MPU addresses). You must either configure the MPUs to enable the I2C_PASSTHROUGH or only 1 MAG on the bus at a time; or configure the MAG via the I2C_Master and Slaves on each MPU (I give code for that in my second comment).

This piece of sample code from the original posts demonstrates setting up the MPU and reading the full data set:

mpu9250.initMPU9250(); mpu9250.initAK8963(magCalibration);

mpu9250.enableI2CMaster(); mpu9250.setupSlave( 0 / Setup Slave0 / , AK8963_ADDRESS / Read from the Mag device / , INFO / Start at the AK8963_INFO register -- this #define should be updated / , true / is_read / , 10 / read 10 bytes, most importantly this includes a read of STATUS2 / , true / send_reg_addr / , true / swap word bytes on read - make it the same endianness as MPU data/ , false / use even swap alignment / , true / enable it with this call / );

uint8_t rawData[38]; mpu9250.readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 38, rawData);

// What you should notice is all the data coming in at byte 14 and above Serial.print("["); for (int i = 0; i < 38; i += 2) { String b1 = String(rawData[i], HEX); String b2 = String(rawData[i+1], HEX); b1 = ((b1.length() < 2) ? "0" : "") + b1; b2 = ((b2.length() < 2) ? "0" : "") + b2; Serial.print("0x" + b1 + b2 + ", "); } Serial.println("]");

You'll have to play with this code, and the whole library to make your case work. You have two i2c busses, you'll want to ensure the code is properly talking on the MPUs respective bus. You have two MAGs on each bus which have the same i2c address; the libraries default code cannot initialize the MAGs that way (you have to either disconnect one of the MAGs by disabling the I2C_PASSTHROUGH on the other MPU, or you have to first both MPUs to have their I2C Master working and configure each MAG through the Slave4).

I recommend you use the following procedure.

  1. Turn off the I2C_PASSTHROUGH on the 0x68 MPU to make sure its MAG can't see the i2c bus
  2. Initialize the 0x69 MPU using the library's normal code
  3. Call mpu9250.initAK8963(magCalibration); on the 0x69 MPU
  4. Initialize the slave devices on the 0x69 MPU (turning off the I2C_PASSTHROUGH)
  5. Initialize the 0x68 MPU9250 using the library's normal code (this reeanables the I2C_PASSTHROUGH)
  6. Call mpu9250.initAK8963(magCalibration); on the 0x68 MPU
  7. Initialize the slave devices on 0x68 MPU (turning off the I2C_PASSTHROUGH)
  • repeat the above for each i2c bus

At that point the MAG should be appearing in the EXT_SENS_DATA fields.

— You are receiving this because you commented. Reply to this email directly, view it on GitHub <https://github.com/kriswiner/MPU9250/issues/86#issuecomment-366760624 , or mute the thread https://github.com/notifications/unsubscribe-auth/ AGY1qo9ttZG5WlJctK5MRleNVnSyTgC3ks5tWbEhgaJpZM4KsD21 .

— You are receiving this because you authored the thread. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-366763609, or mute the thread https://github.com/notifications/unsubscribe-auth/ ACMqLZvv77vtg0Rpy5G2Tw1lGVxzCnjvks5tWbQrgaJpZM4KsD21

.

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-366813524, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qsn-0ECt9y8kJOxoCnl6n2tAwlpkks5tWfAXgaJpZM4KsD21 .

noega33 commented 6 years ago

Thank you Kris and Mike,

It's late in Europe, I'll try you suggestions this week.... what I would like to achieve is adding displacement measurement to a previously developped and working system, see: http://golf-swing-timing-master.com/STM_EN_V00.php (in this one, I was only measuring rotations on all for segments) That is why I need to get gyroscope, accelerometer and magnetometer data from 4 MPUs and determine displacement measurement at least from Two MPUs during a rather short period of time (2 seconds) Cheers Noega33

noega33 commented 6 years ago

PS: http://golf-swing-timing-master.com/STM_EN_V00.php is my own development!

kriswiner commented 6 years ago

Accurate displacement with just an IMU is going to be very challenging...

On Mon, Feb 19, 2018 at 2:46 PM, noega33 notifications@github.com wrote:

PS: http://golf-swing-timing-master.com/STM_EN_V00.php is my own development!

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-366820417, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qnDiC15kNGfqbU08joazKdKiqJ_gks5tWfm1gaJpZM4KsD21 .

noega33 commented 6 years ago

You are right Kris, But I'm betting on the fact that I only need to measure the displacements during the time it takes to perform a golf swing (around 2 seconds from address to follow-through) and that I'm starting from a "fix" position (address). the other challenge that I'll have to overcome is that I need to sample at around 200 Hz (and the magnetometer max rate is 100 Hz).... I'll be measuring displacement only on 2 MPUs out of 4 Any idea you may have will be welcome (filtering,averaging, etc.etc.) Thank you Rgds

MikeFair commented 6 years ago

(1) I did a lot by simply detecting the "Changes in Sign" of the acceleration axes as "edges";

FWIW, I was never able to pick up a box, move it away for 2 seconds then place it back where it was, and have its ending position be near enough to its starting point to consider it a "satisfactory" result.


As for reading the MAGs from EXT_SENS_DATA, once you understand how to make it work for one MPU (namely I2C_PASSTHROUGH and ENABLE_I2C_MASTER) understanding what you need to do for the others should be easier. Again, I recommend disabling the PASSTHROUGH on one MPU, letting the library fully configure the other, enable slave reading on the other (which disables the PASSTHROUGH), then enabling PASSTHROUGH on the first MPU and repeating the configuration process.

On Mon, Feb 19, 2018 at 11:54 PM, noega33 notifications@github.com wrote:

You are right Kris, But I'm betting on the fact that I only need to measure the displacements during the time it takes to perform a golf swing (around 2 seconds from address to follow-through) and that I'm starting from a "fix" position (address). the other challenge that I'll have to overcome is that I need to sample at around 200 Hz (and the magnetometer max rate is 100 Hz).... I'll be measuring displacement only on 2 MPUs out of 4 Any idea you may have will be welcome (filtering,averaging, etc.etc.) Thank you Rgds

— You are receiving this because you authored the thread. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-366894120, or mute the thread https://github.com/notifications/unsubscribe-auth/ACMqLXZJ4xFR23SU2izo7xgCy-U2zInYks5tWnpPgaJpZM4KsD21 .

kriswiner commented 6 years ago

I think this is hopeless rather than challenging using IMUs alone. However, If I were assigned this task, I would use one well-calibrated MPU9250 and one of these https://www.tindie.com/products/onehorse/pmw3901-optical-flow-sensor/.

Then I would have a good measure of the gravity vector as well as x and y velocity at 100 Hz from which I could extract arc distance traveled over much of the club trajectory with pretty good accuracy.

On Tue, Feb 20, 2018 at 12:36 AM, Mike Fair notifications@github.com wrote:

(1) I did a lot by simply detecting the "Changes in Sign" of the acceleration axes as "edges";

  • You know a lot about the predicted path of the swing, you might able to mark certain "points" on that path using the changes in the direction of gravity.
  • You also know the time elapsed between those points and that the club is a rigid body. You might be able to make some inferences from that. (2) I'd honestly suggest adding some more super inexpensive controller chips to make "flight recorders" with a constant 3-5s dedicated i2c buffer.
  • Then make each of those an i2c Slave device to the Teensy, and pull the data results from each chip's memory "after the fact".
  • I wanted to do this for a couple ESP8266s I had, but I couldn't get the i2c slave code to work properly on the firmware. (3) I'd stay away from the float values until the final processing; and I'd give the "lower sensitivity" settings a try, especially on the accelerometer.
  • It seems like things will go much smoother for you if you simply collected a lot of integers, then crunched the raw data at the end.

FWIW, I was never able to pick up a box, move it away for 2 seconds then place it back where it was, and have its ending position be near enough to its starting point to consider it a "satisfactory" result.


As for reading the MAGs from EXT_SENS_DATA, once you understand how to make it work for one MPU (namely I2C_PASSTHROUGH and ENABLE_I2C_MASTER) understanding what you need to do for the others should be easier. Again, I recommend disabling the PASSTHROUGH on one MPU, letting the library fully configure the other, enable slave reading on the other (which disables the PASSTHROUGH), then enabling PASSTHROUGH on the first MPU and repeating the configuration process.

On Mon, Feb 19, 2018 at 11:54 PM, noega33 notifications@github.com wrote:

You are right Kris, But I'm betting on the fact that I only need to measure the displacements during the time it takes to perform a golf swing (around 2 seconds from address to follow-through) and that I'm starting from a "fix" position (address). the other challenge that I'll have to overcome is that I need to sample at around 200 Hz (and the magnetometer max rate is 100 Hz).... I'll be measuring displacement only on 2 MPUs out of 4 Any idea you may have will be welcome (filtering,averaging, etc.etc.) Thank you Rgds

— You are receiving this because you authored the thread. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-366894120, or mute the thread https://github.com/notifications/unsubscribe-auth/ ACMqLXZJ4xFR23SU2izo7xgCy-U2zInYks5tWnpPgaJpZM4KsD21 .

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-366904031, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qjpoJidov5170F0ixNC6YWFOaXCHks5tWoQXgaJpZM4KsD21 .

noega33 commented 6 years ago

@kriswiner , Kris, yesterday I bought 5 of your BNO055 nano boards on Tindie on the bases of your comment " The software sensor fusion responds at an update rate between 300 and 400 Hz when the Teensy 3.1 processor speed is set to 48 MHz depending on the amount of data output requested." because I need around 200/250 Hz refresh rate. But when I read The BNO055 specs, it does not seem that the sensors output rate can go that high in frequency. So, I'm a little puzzle? Could you please me what is the maximum output rate I could from all three sensors? rgds

kriswiner commented 6 years ago

For the BNO055, you can use the scaled sensor data and run fusion on the host (Teensy) in which case the fusion rate is limited by the processor speed. In the comment above, I was getting a few hundred Hz on the Teensy 3.1. You would probably get a few kHz using the Teensy 3.6 or STM32L4. This is what is meant by software sensor fusion in the comment your referenced.

The BNO055 can also provide fused data (quaternions) using hardware sensor fusion, that is doing the fusion on the BNO055's embedded Cortex M0 processor, in which case the fusion rate is fixed at 100 Hz.

This is one reason I don;t use the BNO055 (or MPU9250 DMP) since the fusion rate is fixed. For "hardware" sensor fusion I use the EM7180 which can update the quaternions at the gyro rate up to 400 Hz. If this is what you require, I would recommend this https://www.tindie.com/products/onehorse/ultimate-sensor-fusion-solution/.

On Fri, Feb 23, 2018 at 12:05 AM, noega33 notifications@github.com wrote:

@kriswiner https://github.com/kriswiner , Kris, yesterday I bought 5 of your BNO055 nano boards on Tindie on the bases of your comment " The software sensor fusion responds at an update rate between 300 and 400 Hz when the Teensy 3.1 processor speed is set to 48 MHz depending on the amount of data output requested." because I need around 200/250 Hz refresh rate. But when I read The BNO055 specs, it does not seem that the sensors output rate can go that high in frequency. So, I'm a little puzzle? Could you please me what is the maximum output rate I could from all three sensors? rgds

— You are receiving this because you were mentioned. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-367937980, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qsejl-CQ7iLHnzUIG6mLXRnexk5bks5tXnE9gaJpZM4KsD21 .

noega33 commented 6 years ago

@kriswiner Kris, Thank you for the clarification, but it does not completely answer my question about the maximum data output rate (for all three sensors) from the BNO055 that will feed the teensy for fusion computation. I could not find a clear data output rate value in the component specifications Thank you in advance

kriswiner commented 6 years ago

For the mag it is 30 Hz max, for the gyro and accel the sensor data rates are not explicitly given but are controlled via the bandwidth setting. So if you want high sample rate use a high bandwidth.

For specific sample rate settings i suppose you will have to ask Bosch.

On Fri, Feb 23, 2018 at 9:57 AM, noega33 notifications@github.com wrote:

@kriswiner https://github.com/kriswiner Kris, Thank you for the clarification, but it does not completely answer my question about the maximum data output rate (for all three sensors) from the BNO055 that will feed the teensy for fusion computation. I could not find a clear data output rate value in the component specifications Thank you in advance

— You are receiving this because you were mentioned. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-368088492, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qqnGmZUi-f5sPcAIXE_dlgxu_olUks5tXvwEgaJpZM4KsD21 .

utpalban commented 6 years ago

I am using TI CC 2560 board with MPU9250. While reading data from CONFIG register of MPU9250. I am getting assertion. Here are is my code snippet: bool  SensorMpu9250_smplrate(void) // New Function: Utpal{ uint8_t regval = 0;        ST_ASSERT(SensorMpu9250_powerIsOn());     if (!SENSOR_SELECT())     { return false;     }     //--------------------------------------------- // Step-1: Configure Accelerometer. Set Frequency 1kHz, Max delay 4.9ms. // This produces a slightly greater than 200Hz max output rate.     ST_ASSERT(SensorI2C_readReg(CONFIG, &regval, 1)); regval &= 0b11111000; // Clear Bit2-0 = 000b     regval |= 0b00000011; // Set Bit2-0 = 011b     ST_ASSERT(SensorI2C_writeReg(CONFIG, &regval, 1));     //DELAY_MS(100);     //------------------------------------------ // Step-2: Set sample rate = frequency / (1 + SMPLRT_DIV)   regval = 0x04;     ST_ASSERT(SensorI2C_writeReg(SMPLRT_DIV, &regval, 1)); //DELAY_MS(100);     //------------------------------------------ // Step-3: Set Full Scale range in Gyroscope. regval = 0x00;     ST_ASSERT(SensorI2C_writeReg(GYRO_CONFIG, &regval, 1)); //DELAY_MS(100); //--------------------------------------------- // Step-4: Set Full Scale range in Accelerometer. regval = 0x00;     ST_ASSERT(SensorI2C_writeReg(ACCEL_CONFIG, &regval, 1)); //DELAY_MS(100); //--------------------------------------------- // Step-5: Configure Accelerometer Sample Rate. regval = 0x03; // Bit7-3 = 00000b, Bit2-0 = 011b ST_ASSERT(SensorI2C_writeReg(ACCEL_CONFIG_2, &regval, 1)); //DELAY_MS(100); SENSOR_DESELECT();     //--------end of configure sample rate. return true;}It is getting assertion in highlighted line. Where  am I making a mistake. Any suggestion ?Thanks in advanceUtpal Kolkata :- 2A, Sadhu Tara Charan Road Calcutta - 700026 West Bengal, India.  Cell #: +91-98304-01946

On Friday, 23 February, 2018, 11:27:26 PM IST, noega33 <notifications@github.com> wrote:  

@kriswiner Kris, Thank you for the clarification, but it does not completely answer my question about the maximum data output rate (for all three sensors) from the BNO055 that will feed the teensy for fusion computation. I could not find a clear data output rate value in the component specifications Thank you in advance

— You are receiving this because you commented. Reply to this email directly, view it on GitHub, or mute the thread.

kriswiner commented 6 years ago

No idea, maybe ask TI?

On Fri, Feb 23, 2018 at 10:23 AM, utpalban notifications@github.com wrote:

I am using TI CC 2560 board with MPU9250. While reading data from CONFIG register of MPU9250. I am getting assertion. Here are is my code snippet: bool SensorMpu9250_smplrate(void) // New Function: Utpal{ uint8_t regval = 0; ST_ASSERT(SensorMpu9250_powerIsOn()); if (!SENSOR_SELECT()) { return false; } //--------------------------------------------- // Step-1: Configure Accelerometer. Set Frequency 1kHz, Max delay 4.9ms. // This produces a slightly greater than 200Hz max output rate. ST_ASSERT(SensorI2C_readReg(CONFIG, &regval, 1)); regval &= 0b11111000; // Clear Bit2-0 = 000b regval |= 0b00000011; // Set Bit2-0 = 011b ST_ASSERT(SensorI2C_writeReg(CONFIG, &regval, 1)); //DELAY_MS(100); //------------------------------------------ // Step-2: Set sample rate = frequency / (1 + SMPLRT_DIV) regval = 0x04; ST_ASSERT(SensorI2C_writeReg(SMPLRT_DIV, &regval, 1)); //DELAY_MS(100); //------------------------------------------ // Step-3: Set Full Scale range in Gyroscope. regval = 0x00; ST_ASSERT(SensorI2C_writeReg(GYRO_CONFIG, &regval, 1)); //DELAY_MS(100); //--------------------------------------------- // Step-4: Set Full Scale range in Accelerometer. regval = 0x00; ST_ASSERT(SensorI2C_writeReg(ACCEL_CONFIG, &regval, 1)); //DELAY_MS(100); //--------------------------------------------- // Step-5: Configure Accelerometer Sample Rate. regval = 0x03; // Bit7-3 = 00000b, Bit2-0 = 011b ST_ASSERT(SensorI2C_writeReg(ACCEL_CONFIG_2, &regval, 1)); //DELAY_MS(100); SENSOR_DESELECT(); //--------end of configure sample rate. return true;}It is getting assertion in highlighted line. Where am I making a mistake. Any suggestion ?Thanks in advanceUtpal Kolkata :- 2A, Sadhu Tara Charan Road Calcutta - 700026 West Bengal, India https://maps.google.com/?q=2A,+Sadhu+Tara+Charan+Road+Calcutta+-+700026+West+Bengal,+India&entry=gmail&source=g. Cell #: +91-98304-01946 <+91%2098304%2001946>

On Friday, 23 February, 2018, 11:27:26 PM IST, noega33 < notifications@github.com> wrote:

@kriswiner Kris, Thank you for the clarification, but it does not completely answer my question about the maximum data output rate (for all three sensors) from the BNO055 that will feed the teensy for fusion computation. I could not find a clear data output rate value in the component specifications Thank you in advance

— You are receiving this because you commented.

Reply to this email directly, view it on GitHub, or mute the thread.

— You are receiving this because you were mentioned. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-368095466, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1quOnSDWvrqw_MOqcD_NeGPkdaM9Wks5tXwINgaJpZM4KsD21 .

noega33 commented 6 years ago

@kriswiner So Kris, how could you advertise " The software sensor fusion responds at an update rate between 300 and 400 Hz when the Teensy 3.1 processor speed is set to 48 MHz depending on the amount of data output requested." when the update rate rate from one of the sensors is 30Hz? This is what confused me and ordered BNO055 rather than your MPU9250 (my purchase of 5 of these is now useless) rgds

kriswiner commented 6 years ago

" The software sensor fusion responds at an update rate between 300 and 400 Hz when the Teensy 3.1 processor speed is set to 48 MHz "

As I explained, this is the host fusion rate; I made no claims or advertisements about the sensor sample rates. The BNO055 data sheet is available, linked from the Tindie store, and should be consulted prior to purchase to make sure the product will meet your needs.

If you relied on my comment above about the host fusion rate as an indication of magnetometer data rate instead of asking me directly prior to purchase or looking for yourself there's not much I can do.

In addition, I don't think the BNO055 will be wasted. absolute orientation estimation is dominated by the gyro rate; the accel and mag are simply helpers to correct gyro drify. So you need to simply try these in your application to see if they will provide the response you require.

But I would recommend that next time you consider buying something new, ask about criticalfeatures you are not sure about and maybe buy one to test before you buy five.

On Fri, Feb 23, 2018 at 10:35 AM, noega33 notifications@github.com wrote:

@kriswiner https://github.com/kriswiner So Kris, how could you advertise " The software sensor fusion responds at an update rate between 300 and 400 Hz when the Teensy 3.1 processor speed is set to 48 MHz depending on the amount of data output requested." when the update rate rate from one of the sensors is 30Hz? This is what confused me and ordered BNO055 rather than your MPU9250 (my purchase of 5 of these is now useless) rgds

— You are receiving this because you were mentioned. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-368098971, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qk0zKJiTb5765L78e8Yibj2rzRQPks5tXwTrgaJpZM4KsD21 .

noega33 commented 6 years ago

@kriswiner

When a seller says "update rate between 300 and 400Hz" I don't have any reason to doubt or questione I'm expecting this rate with no other further question...

AlexOrlo commented 5 years ago

Please help I'm use STM32F1 with HAL drivers. Try to read all data with DMA by interrupt pin. Now I can do it for 14 bytes of ACC+TEMP+GYR I'm try to adjust slave0 to read magnetometer.. but no result. By manual, I also can write ( with adjust register 0x63 ) data to slave device So I send reset command to CNTL2 Send Continue mod 2 (100Hz) and 16 bit mod. But I can't read it.

Adjust MPU for Master:

HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, INT_PIN_CONFIG, 1, 0x00, 1, 1);
HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, MST_CTRL, 1, 0x5D, 1, 1);
HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, USER_CTRL, 1, 0x20, 1, 1);

HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x25, 1, MAG_ADDRESS, 1, 1);  //set address of slave device (write)
//reset compass :
HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x26, 1, 0x0B, 1, 1);  //register address from where begin write data - CNTL2
HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x27, 1, 0x81, 1, 1); //  configure for 1 byte
HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x63, 1, 0x01, 1, 1); // send 0x01 to slave with I2C_SLV0_DO register   ????

//set continues mod2 and 16bit
HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x26, 1, 0x0A, 1, 1);   //CNTL1
HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x27, 1, 0x81, 1, 1); // 1 byte
HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x63, 1, 0x16, 1, 1); // send 0x16 to slave

//config to read 6 bytes
HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x25, 1, 0x80 | MAG_ADDRESS, 1, 1);  //set address of slave device (read) 
HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x26, 1, 0x03, 1, 1);  //Read from 0x03 register
HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x27, 1, 0x86, 1, 1); // read 6 byte

So EXT sens data still 0...

AlexOrlo commented 5 years ago

So I found solution... I don't understand why, but If to start read from reg status1 to reg status2 (8 bytes with 6 byte of mag data), it's work..

MikeFair commented 5 years ago

I couldn't quite get through all your posted code to see if this was happening or not, but in order to have the MAG detect that you read its data and to load new data into its registers, you have to read STATUS2. It doesn't care if you read status1 or not, but reading status2 is what triggers the MAG to load the other registers with new data.

(At least I'm fairly confident it's status2, it's whatever status register is at the higher end, after all the data registers.)

If you don't read that register, the MAG will not update its data registers with new information.

On Sun, Jan 20, 2019 at 2:33 AM AlexOrlo notifications@github.com wrote:

So I found solution... I don't understand why, but If to start read from reg status1 to reg status2 (8 bytes with 6 byte of mag data), it's work..

— You are receiving this because you authored the thread. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-455854670, or mute the thread https://github.com/notifications/unsubscribe-auth/ACMqLRSg2Ul1ImE3EWWUCMSUvAmFAQSDks5vFEYPgaJpZM4KsD21 .

kriswiner commented 5 years ago

Amazing what one can learn by teading the darasheet...

On Sun, Jan 20, 2019 at 4:06 AM Mike Fair notifications@github.com wrote:

I couldn't quite get through all your posted code to see if this was happening or not, but in order to have the MAG detect that you read its data and to load new data into its registers, you have to read STATUS2. It doesn't care if you read status1 or not, but reading status2 is what triggers the MAG to load the other registers with new data.

(At least I'm fairly confident it's status2, it's whatever status register is at the higher end, after all the data registers.)

If you don't read that register, the MAG will not update its data registers with new information.

On Sun, Jan 20, 2019 at 2:33 AM AlexOrlo notifications@github.com wrote:

So I found solution... I don't understand why, but If to start read from reg status1 to reg status2 (8 bytes with 6 byte of mag data), it's work..

— You are receiving this because you authored the thread. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-455854670, or mute the thread < https://github.com/notifications/unsubscribe-auth/ACMqLRSg2Ul1ImE3EWWUCMSUvAmFAQSDks5vFEYPgaJpZM4KsD21

.

— You are receiving this because you were mentioned. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-455860885, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qgnTZ8fKWFdi2TvmbR0jY6E342ONks5vFFuxgaJpZM4KsD21 .

AlexOrlo commented 5 years ago

Thank for answer. So this is my working code:

HAL_Delay(50); HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, PWR_MGMT_1, 1, 0, 1, 1); HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, PWR_MGMT_2, 1, 0, 1, 1); HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, SMPLRT_DIV, 1, 0, 1, 1);//main F devider HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, USER_CTRL, 1, 0x20, 1, 1);

HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x24, 1, 0x4D, 1, 1); //Wait for Data at Slave0 HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x25, 1, 80 | MAG_ADRESS, 1, 1); //Set i2c address at slave0 for read HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x26, 1, 0x02, 1, 1); // set first register HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x27, 1, 0x88, 1, 1); // amount data to be readed (8 bytes)

HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x28, 1, MAG_ADRESS, 1, 1); // set i2c address for slave 1 for write HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x29, 1, 0x0A , 1, 1); // Mag register address HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x2A, 1, 0x81 , 1, 1); // just one register HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x64, 1, 0x16 , 1, 1); // overvride register HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x67, 1, 0x03 , 1, 1); // set delay HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x01, 1, 0x80 , 1, 1); //

HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x6A, 1, 0x20 , 1, 1); //enable master i2c mode

HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, CONFIG, 1, 0x00, 1, 1); //LPF disabled HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, GYRO_CONFIG, 1, 0x00, 1, 1); /// 0x00 +250 0x08 +500 0x10 +1000 0x18 +2000 HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, ACCEL_CONFIG, 1, 0x10, 1, 1); //+- 8g HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, ACCEL_CONFIG1, 1, 0x00, 1, 1); //Acc filter dis HAL_Delay(50); HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, INTERRUPT, 1, 1, 1, 1); //Data ready interrupt enable HAL_Delay(50);

After it need just to use
HAL_I2C_Mem_Read_DMA(&hi2c1, GYRO_ADDRESS, ACCEL_XOUT_H, 1, (void *)MpuBufferDMA, 21); in Interrupt of int pin. And them to do routine in HAL_I2C_MasterRxCpltCallback. (Before it need to Enable transfer complete and disable half transfer Interrupt for i2c dma )

So processor not use any thing to MPU communication

kriswiner commented 5 years ago

What is the question?

On Sun, Jan 20, 2019 at 9:43 AM AlexOrlo notifications@github.com wrote:

Thank for answer. So this is my working code:

HAL_Delay(50); HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, PWR_MGMT_1, 1, 0, 1, 1); HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, PWR_MGMT_2, 1, 0, 1, 1); HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, SMPLRT_DIV, 1, 0, 1, 1);//main F devider HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, USER_CTRL, 1, 0x20, 1, 1);

HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x24, 1, 0x4D, 1, 1); //Wait for Data at Slave0 HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x25, 1, 80 | MAG_ADRESS, 1, 1); //Set i2c address at slave0 for read HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x26, 1, 0x02, 1, 1); // set first register HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x27, 1, 0x88, 1, 1); // amount data to be readed (8 bytes)

HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x28, 1, MAG_ADRESS, 1, 1); // set i2c address for slave 1 for write HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x29, 1, 0x0A , 1, 1); // Mag register address HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x2A, 1, 0x81 , 1, 1); // just one register HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x64, 1, 0x16 , 1, 1); // overvride register HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x67, 1, 0x03 , 1, 1); // set delay HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x01, 1, 0x80 , 1, 1); //

HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, 0x6A, 1, 0x20 , 1, 1); //enable master i2c mode

HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, CONFIG, 1, 0x00, 1, 1); //LPF disabled HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, GYRO_CONFIG, 1, 0x00, 1, 1); /// 0x00 +250 0x08 +500 0x10 +1000 0x18 +2000 HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, ACCEL_CONFIG, 1, 0x10, 1, 1); //+- 8g HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, ACCEL_CONFIG1, 1, 0x00, 1, 1); //Acc filter dis HAL_Delay(50); HAL_I2C_Mem_Write(&hi2c1, GYRO_ADDRESS, INTERRUPT, 1, 1, 1, 1); //Data ready interrupt enable HAL_Delay(50);

After it need just to use HAL_I2C_Mem_Read_DMA(&hi2c1, GYRO_ADDRESS, ACCEL_XOUT_H, 1, (void *)MpuBufferDMA, 21); in Interrupt of int pin. And them to do routine in HAL_I2C_MasterRxCpltCallback. (Before it need to Enable transfer complete and disable half transfer Interrupt for i2c dma )

So processor not use any thing to MPU communication

— You are receiving this because you were mentioned. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/86#issuecomment-455886407, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1quhQU89uOeMc5iaitfU07iM0c_1Jks5vFKq1gaJpZM4KsD21 .