kriswiner / MPU9250

Arduino sketches for MPU9250 9DoF with AHRS sensor fusion
1.02k stars 469 forks source link

Two MPU9250s Quaternion Issue #296

Open benbrown2456 opened 6 years ago

benbrown2456 commented 6 years ago

Hi Kris,

I am using two MPUs in the I2C arrangement by switching the AD0 bit to obtain two addresses (0x68 and 0x69). i altered the libraary you have written to ignore the #DEFINE MPU9250_ADDRESS and instead use a variable called 'address' as an input so I can read two at the same time. ]

Example altered library function: _void MPU9250::readGyroData(int16_t * destination, uint8_t address) { uint8_t rawData[6]; // x/y/z gyro register data stored here readBytes(address, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array destination[0] = ((int16_t)rawData[0] << 8) | rawData[1] ; // Turn the MSB and LSB into a signed 16-bit value destination[1] = ((int16_t)rawData[2] << 8) | rawData[3] ;
destination[2] = ((int16t)rawData[4] << 8) | rawData[5] ; }

This worked well but as alot of people in this issues section have found the magnetometer readings were the same so I solved this using your suggestion of enabling/disabling the INT_PIN_CFG register to bypass the magnetometer on the IMU I do not want so that it reads the one I do want. This seems to have worked and I am getting different values on the magnetometer for each IMU.

Altered function: _void MPU9250::readMagData(int16_t * destination, uint8_t address) { //Pick the correct magnetometer if (address == 0x68) { writeByte(0x68, INT_PIN_CFG, 0x22); writeByte(0x69, INT_PIN_CFG, 0x20); } else { writeByte(0x68, INT_PIN_CFG, 0x20); writeByte(0x69, INT_PIN_CFG, 0x22); } // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of // data acquisition uint8_t rawData[7]; // Wait for magnetometer data ready bit to be set if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // Read the six raw data and ST2 registers sequentially into data array readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]); uint8_t c = rawData[6]; // End data read by reading ST2 register // Check if magnetic sensor overflow set, if not then report data if(!(c & 0x08)) { // Turn the MSB and LSB into a signed 16-bit value destination[0] = ((int16_t)rawData[1] << 8) | rawData[0]; // Data stored as little Endian destination[1] = ((int16_t)rawData[3] << 8) | rawData[2]; destination[2] = ((int16_t)rawData[5] << 8) | rawData[4]; } } // Enable both magnetometers at the end just in case writeByte(0x68, INT_PIN_CFG, 0x22); writeByte(0x69, INT_PINCFG, 0x22); }

Now however I am having trouble with the quaternions as my values are the same for each IMU. Here is the code I am using (sorry for the length it also uses an ESP8266 to send the data as a JSON - feel free to use this anyone its mostly amalgamations of code available online).

My theory is that the Quaternion Update might use previously sampled data in which case I might be using the data from both magnetometers to work out the quaternions rather than individually for each however this is not immediately obvious from the quaternionfilters.h library. Maybe I could solve this (if it were the problem by using a pointer in the function to set which MPU9250 object I want to assign each part of the data too rather than currently where I say frontMPU9250 = myMPU9250 however I am not sure how I would do this.

Could you shed any light on this issue?

_#include "quaternionFilters.h"

include "MPU9250.h"

include // Enables the ESP8266 to connect to the local network (via WiFi)

include // Allows us to connect to, and publish to the MQTT broker

// Set Up WiFi const char ssid = "xyz"; const char wifi_password = "Obviously not going to post that here!";

// MQTT const char mqtt_server = "10.144.34.224"; const char mqtt_username = "benbrown"; const char mqtt_password = "letmein"; const char clientID = "IMU";

// Initialise the WiFi and MQTT Client objects WiFiClient wifiClient; PubSubClient client(mqtt_server, 1883, wifiClient); // 1883 is the listener port for the Broker

// Set up two IMUs // The front IMU has address 0x68 as AD0 is held to ground // The rear IMU has address 0x69 as AD0 is held to Vcc // Controlled by bridge SJ2 which comes connected to ground and must be switched // to be wired up to Vcc MPU9250 myIMU; MPU9250 frontIMU; MPU9250 rearIMU; int intPin = 12; // These can be changed, 2 and 3 are the Arduinos ext int pins

// WHERE ARE YOU?!?! - fill this bit in (if you want the calculations) // Need to tell magnetometer the value of declination so that it can line up magnetic north with actual north // Go on google maps and find your location in latitude/longitude // Fill these in to https://www.ngdc.noaa.gov/geomag-web/#declination // Use WMM model and put in degrees minutes seconds // If answer is given in degrees minutes seconds then remember 60 minutes in a degree so degrees/60 for the decimal point // Put answer in the following float: 'declination' // Dyson D9 is 1.09 (or there abouts as it doesnt exist on google maps float declination = 1.09;

define calculations false

int status;

// Initiate Hall Effect pin int HEpin = 12; int closecount;

// Variables for frequency long starttime; long overallstart;

int firsttime;

void setup() { Serial.begin(115200); while (!Serial) {}

// Connect to the WiFi WiFi.begin(ssid, wifi_password); // Wait until the connection has been confirmed before continuing while (WiFi.status() != WL_CONNECTED) { delay(500); Serial.print("."); } Serial.println("WiFi connected");

// // Connect to MQTT Broker // // client.connect returns a boolean value to let us know if the connection was successful. // // If the connection is failing, make sure you are using the correct MQTT Username and Password (Setup Earlier in the Instructable) // if (client.connect(clientID, mqtt_username, mqtt_password)) { // Serial.println("Connected to MQTT Broker!"); // } // else { // Serial.println("Connection to MQTT Broker failed..."); // }

// Attach the Hall Effect Interupt and set it to trigger when the HE pin falls to 0 (magnet present) pinMode(HEpin, INPUT); attachInterrupt(digitalPinToInterrupt(HEpin), pole, FALLING); closecount = 0;

// Set up front IMU IMUsetup("front"); IMUsetup("rear");

overallstart = millis();

firsttime = 1; }

void loop() { // if (!client.connected()) { // reconnect(); // }

starttime = millis();

getIMUData("front"); getIMUData("rear"); //sendDataWiFi(); printData();

while (millis() - starttime < 20) { 1 == 1; } }

void pole() { closecount = closecount + 1; }

void sendDataWiFi() { // Front accelerometer String payload = "{\"AXF\":" + String((int)1000 frontIMU.ax) + ",\"AYF\":" + String((int)1000 frontIMU.ay) + ",\"AZF\":" + String((int)1000 * frontIMU.az) + "} "; client.publish("TestRig/IMUF/A", payload.c_str()); client.loop();

delay(1);

// Front gyroscope payload = "{\"GXF\":" + String(frontIMU.gx) + ",\"GYF\":" + String(frontIMU.gy) + ",\"GZF\":" + String(frontIMU.gz) + "} "; client.publish("TestRig/IMUF/G", payload.c_str()); client.loop();

delay(1);

// Front magnetometer payload = "{\"MXF\":" + String(frontIMU.mx) + ",\"MYF\":" + String(frontIMU.my) + ",\"MZF\":" + String(frontIMU.mz) + "} "; client.publish("TestRig/IMUF/M", payload.c_str()); client.loop();

delay(1);

// Rear accelerometer payload = "{\"AXR\":" + String((int)1000 rearIMU.ax) + ",\"AYR\":" + String((int)1000 rearIMU.ay) + ",\"AZR\":" + String((int)1000 * rearIMU.ax) + "} "; client.publish("TestRig/IMUR/A", payload.c_str()); client.loop();

delay(1);

// Rear gyroscope payload = "{\"GXR\":" + String(rearIMU.gx) + ",\"GYR\":" + String(rearIMU.gy) + ",\"GZR\":" + String(rearIMU.gz) + "} "; client.publish("TestRig/IMUR/G", payload.c_str()); client.loop();

delay(1);

// Rear magnetometer payload = "{\"MXR\":" + String(frontIMU.mx) + ",\"MYR\":" + String(frontIMU.my) + ",\"MZR\":" + String(frontIMU.mz) + "} "; client.publish("TestRig/IMUR/M", payload.c_str()); client.loop();

delay(1);

// Other stuff payload = "{\"HE\":" + String(closecount) + ",\"Time\":" + String(millis() - overallstart) + "} "; client.publish("TestRig/Other", payload.c_str()); client.loop();

delay(1); }

void reconnect() { // Loop until we're reconnected while (!client.connected()) { Serial.print("Attempting MQTT connection..."); // Create a random client ID String clientId = "ESP8266Client-"; clientId += String(random(0xffff), HEX); // Attempt to connect if (client.connect(clientId.c_str())) { Serial.println("connected"); // Once connected, publish an announcement... client.publish("outTopic", "hello world"); // ... and resubscribe client.subscribe("inTopic"); } else { Serial.print("failed, rc="); Serial.print(client.state()); Serial.println(" try again in 5 seconds"); // Wait 5 seconds before retrying delay(5000); } } }

void IMUsetup(String location) { // Determine correct address based on location uint8_t address;

if (location == "front") { address = 0x68; Serial.println("Setting up front IMU"); } else if (location == "rear") { address = 0x69; Serial.println("Setting up rear IMU"); } else { Serial.println("Learn to type!"); while (1); }

// Initialise I2C Wire.begin();

// Set up the interrupt pin, its set as active high, push-pull pinMode(intPin, INPUT); digitalWrite(intPin, LOW);

// Read the WHO_AM_I register, this is a good test of communication byte c = myIMU.readByte(address, WHO_AM_I_MPU9250); // Serial.print("MPU9250 "); Serial.print("I AM "); Serial.print(c, HEX); // Serial.print(" I should be "); Serial.println(0x71, HEX);

if (c == 0x71) // WHO_AM_I should always be 0x68 { Serial.println("MPU9250 is online...");

// Start by performing self test and reporting values
myIMU.MPU9250SelfTest(myIMU.SelfTest, address);
Serial.print("x-axis self test: acceleration trim within : ");
Serial.print(myIMU.SelfTest[0], 1); Serial.println("% of factory value");
Serial.print("y-axis self test: acceleration trim within : ");
Serial.print(myIMU.SelfTest[1], 1); Serial.println("% of factory value");
Serial.print("z-axis self test: acceleration trim within : ");
Serial.print(myIMU.SelfTest[2], 1); Serial.println("% of factory value");
Serial.print("x-axis self test: gyration trim within : ");
Serial.print(myIMU.SelfTest[3], 1); Serial.println("% of factory value");
Serial.print("y-axis self test: gyration trim within : ");
Serial.print(myIMU.SelfTest[4], 1); Serial.println("% of factory value");
Serial.print("z-axis self test: gyration trim within : ");
Serial.print(myIMU.SelfTest[5], 1); Serial.println("% of factory value");

// Calibrate gyro and accelerometers, load biases in bias registers
myIMU.calibrateMPU9250(myIMU.gyroBias, myIMU.accelBias, address);

myIMU.initMPU9250(address);
// Initialize device for active mode read of acclerometer, gyroscope, and
// temperature
Serial.println("MPU9250 initialized for active data mode....");

// Read the WHO_AM_I register of the magnetometer, this is a good test of
// communication
byte d = myIMU.readByte(AK8963_ADDRESS, WHO_AM_I_AK8963);
//    Serial.print("AK8963 "); Serial.print("I AM "); Serial.print(d, HEX);
//    Serial.print(" I should be "); Serial.println(0x48, HEX);

// Get magnetometer calibration from AK8963 ROM
myIMU.initAK8963(myIMU.magCalibration, address);
// Initialize device for active mode read of magnetometer
Serial.println("AK8963 initialized for active data mode....");

} // if (c == 0x71) else { Serial.print("Could not connect to MPU9250: 0x"); Serial.println(c, HEX); while (1) ; // Loop forever if communication doesn't happen }

// Assign all the values of myIMU to front or rear IMUs if (location == "front") { frontIMU = myIMU; } else //(location == "rear") { rearIMU = myIMU; } }

void getIMUData(String location) { // Determine correct address based on location uint8_t address;

if (location == "front") { address = 0x68; } else //(location == "rear") { address = 0x69; }

// If intPin goes high, all data registers have new data // On interrupt, check if data ready interrupt if (myIMU.readByte(address, INT_STATUS) & 0x01) { myIMU.readAccelData(myIMU.accelCount, address); // Read the x/y/z adc values myIMU.getAres();

// Now we'll calculate the accleration value into actual g's
// This depends on scale being set
myIMU.ax = (float)myIMU.accelCount[0] * myIMU.aRes; // - accelBias[0];
myIMU.ay = (float)myIMU.accelCount[1] * myIMU.aRes; // - accelBias[1];
myIMU.az = (float)myIMU.accelCount[2] * myIMU.aRes; // - accelBias[2];

myIMU.readGyroData(myIMU.gyroCount, address);  // Read the x/y/z adc values
myIMU.getGres();

// Calculate the gyro value into actual degrees per second
// This depends on scale being set
myIMU.gx = (float)myIMU.gyroCount[0] * myIMU.gRes;
myIMU.gy = (float)myIMU.gyroCount[1] * myIMU.gRes;
myIMU.gz = (float)myIMU.gyroCount[2] * myIMU.gRes;

myIMU.readMagData(myIMU.magCount, address);  // Read the x/y/z adc values
myIMU.getMres();
// User environmental x-axis correction in milliGauss, should be
// automatically calculated
myIMU.magbias[0] = +470.;
// User environmental x-axis correction in milliGauss TODO axis??
myIMU.magbias[1] = +120.;
// User environmental x-axis correction in milliGauss
myIMU.magbias[2] = +125.;

// Calculate the magnetometer values in milliGauss
// Include factory calibration per data sheet and user environmental
// corrections
// Get actual magnetometer value, this depends on scale being set
myIMU.mx = (float)myIMU.magCount[0] * myIMU.mRes * myIMU.magCalibration[0] -
           myIMU.magbias[0];
myIMU.my = (float)myIMU.magCount[1] * myIMU.mRes * myIMU.magCalibration[1] -
           myIMU.magbias[1];
myIMU.mz = (float)myIMU.magCount[2] * myIMU.mRes * myIMU.magCalibration[2] -
           myIMU.magbias[2];

} // if (readByte(MPU9250_ADDRESS, INT_STATUS) & 0x01)

// Must be called before updating quaternions! myIMU.updateTime();

// Sensors x (y)-axis of the accelerometer is aligned with the y (x)-axis of // the magnetometer; the magnetometer z-axis (+ down) is opposite to z-axis // (+ up) of accelerometer and gyro! We have to make some allowance for this // orientationmismatch in feeding the output to the quaternion filter. For the // MPU-9250, we have chosen a magnetic rotation that keeps the sensor forward // along the x-axis just like in the LSM9DS0 sensor. This rotation can be // modified to allow any convenient orientation convention. This is ok by // aircraft orientation standards! Pass gyro rate as rad/s // MadgwickQuaternionUpdate(ax, ay, az, gxPI/180.0f, gyPI/180.0f, gzPI/180.0f, my, mx, mz); MahonyQuaternionUpdate(myIMU.ax, myIMU.ay, myIMU.az, myIMU.gx DEG_TO_RAD, myIMU.gy DEG_TO_RAD, myIMU.gz DEG_TO_RAD, myIMU.my, myIMU.mx, myIMU.mz, myIMU.deltat);

// Pitch, Roll and Yaw // Define output variables from updated quaternion---these are Tait-Bryan // angles, commonly used in aircraft orientation. In this coordinate system, // the positive z-axis is down toward Earth. Yaw is the angle between Sensor // x-axis and Earth magnetic North (or true North if corrected for local // declination, looking down on the sensor positive yaw is counterclockwise. // Pitch is angle between sensor x-axis and Earth ground plane, toward the // Earth is positive, up toward the sky is negative. Roll is angle between // sensor y-axis and Earth ground plane, y-axis up is positive roll. These // arise from the definition of the homogeneous rotation matrix constructed // from quaternions. Tait-Bryan angles as well as Euler angles are // non-commutative; that is, the get the correct orientation the rotations // must be applied in the correct order which for this configuration is yaw, // pitch, and then roll. // For more see // http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles // which has additional links.

if (calculations) { myIMU.yaw = atan2(2.0f ((getQ() + 1) (getQ() + 2) + getQ() (getQ() + 3)), getQ() getQ() + (getQ() + 1) *(getQ() + 1)

void printData() { if (firsttime == 1) { //Column titles Serial.println(); Serial.println(); Serial.print("Front X Acceleration"); Serial.print("Front Y Acceleration"); Serial.print("Front Z Acceleration"); Serial.print("Front X Gyro Rate"); Serial.print("Front Y Gyro Rate"); Serial.print("Front Z Gyro Rate"); Serial.print("Front X Mag Field"); Serial.print("Front Y Mag Field"); Serial.print("Front Z Mag Field"); Serial.print("Front q0"); Serial.print("\t"); Serial.print("Front qx"); Serial.print("\t"); Serial.print("Front qy"); Serial.print("\t"); Serial.print("Front qz"); Serial.print("\t"); if (calculations) { Serial.print("Front Pitch"); Serial.print("\t"); Serial.print("Front Roll"); Serial.print("\t"); Serial.print("Front Yaw"); Serial.print("\t"); } Serial.print("Front IMU Temperature"); Serial.print("Rear X Acceleration"); Serial.print("Rear Y Acceleration"); Serial.print("Rear Z Acceleration"); Serial.print("Rear X Gyro Rate"); Serial.print("Rear Y Gyro Rate"); Serial.print("Rear Z Gyro Rate"); Serial.print("Rear X Mag Field"); Serial.print("Rear Y Mag Field"); Serial.print("Rear Z Mag Field"); Serial.print("Rear q0"); Serial.print("\t"); Serial.print("Rear qx"); Serial.print("\t"); Serial.print("Rear qy"); Serial.print("\t"); Serial.print("Rear qz"); Serial.print("\t"); Serial.print("Rear IMU Temperature"); if (calculations) { Serial.print("Rear Pitch"); Serial.print("\t"); Serial.print("Rear Roll"); Serial.print("\t"); Serial.print("Rear Yaw"); Serial.print("\t"); } Serial.print("Open/Close Count"); Serial.println();

firsttime = 0;

}

// Print data // Front Accelerometer x, y, z Serial.print((int)1000 frontIMU.ax); Serial.print(" "); Serial.print("\t"); Serial.print("\t"); Serial.print((int)1000 frontIMU.ay); Serial.print(" "); Serial.print("\t"); Serial.print("\t"); Serial.print((int)1000 * frontIMU.az); Serial.print(" "); Serial.print("\t"); Serial.print("\t");

// Front Gyroscope x, y, z Serial.print( frontIMU.gx, 2); Serial.print("\t"); Serial.print("\t"); Serial.print( frontIMU.gy, 2); Serial.print("\t"); Serial.print("\t"); Serial.print( frontIMU.gz, 2); Serial.print("\t"); Serial.print("\t");

// Front Magnetometer x, y, z Serial.print( (int)frontIMU.mx ); Serial.print("\t"); Serial.print("\t"); Serial.print( (int)frontIMU.my ); Serial.print("\t"); Serial.print("\t"); Serial.print( (int)frontIMU.mz ); Serial.print("\t"); Serial.print("\t");

// Front Quaternions 0,x,y,z Serial.print(getQ()); Serial.print("\t"); Serial.print("\t"); Serial.print((getQ() + 1)); Serial.print("\t"); Serial.print("\t"); Serial.print((getQ() + 2)); Serial.print("\t"); Serial.print("\t"); Serial.print((getQ() + 3)); Serial.print("\t"); Serial.print("\t");

// Front IMU Temperature Serial.print(frontIMU.temperature, 1); Serial.print("\t"); Serial.print("\t");

// Front Pitch, Roll, Yaw if (calculations) { Serial.print(frontIMU.pitch, 2); Serial.print("\t"); Serial.print("\t"); Serial.print(frontIMU.roll, 2); Serial.print("\t"); Serial.print("\t"); Serial.print(frontIMU.yaw, 2); Serial.print("\t"); Serial.print("\t"); }

// Rear Accelerometer x, y, z Serial.print((int)1000 rearIMU.ax); Serial.print(" "); Serial.print("\t"); Serial.print("\t"); Serial.print((int)1000 rearIMU.ay); Serial.print(" "); Serial.print("\t"); Serial.print("\t"); Serial.print((int)1000 * rearIMU.az); Serial.print(" "); Serial.print("\t"); Serial.print("\t");

// Rear Gyroscope x, y, z Serial.print( rearIMU.gx, 2); Serial.print("\t"); Serial.print("\t"); Serial.print( rearIMU.gy, 2); Serial.print("\t"); Serial.print("\t"); Serial.print( rearIMU.gz, 2); Serial.print("\t"); Serial.print("\t");

// Rear Magnetometer x, y, z Serial.print( (int)rearIMU.mx ); Serial.print("\t"); Serial.print("\t"); Serial.print( (int)rearIMU.my ); Serial.print("\t"); Serial.print("\t"); Serial.print( (int)rearIMU.mz ); Serial.print("\t"); Serial.print("\t");

// Rear Quaternions 0,x,y,z Serial.print(getQ()); Serial.print("\t"); Serial.print("\t"); Serial.print((getQ() + 1)); Serial.print("\t"); Serial.print("\t"); Serial.print((getQ() + 2)); Serial.print("\t"); Serial.print("\t"); Serial.print((getQ() + 3)); Serial.print("\t"); Serial.print("\t");

// Rear IMU Temperature Serial.print(rearIMU.temperature, 1); Serial.print("\t"); Serial.print("\t");

// Rear Pitch, Roll, Yaw if (calculations) { Serial.print(rearIMU.pitch, 2); Serial.print("\t"); Serial.print("\t"); Serial.print(rearIMU.roll, 2); Serial.print("\t"); Serial.print("\t"); Serial.print(rearIMU.yaw, 2); Serial.print("\t"); Serial.print("\t"); }

Serial.print(closecount); Serial.print("\t"); Serial.print("\t");

Serial.println(); }_

benbrown2456 commented 6 years ago

Was just re-reading my code and I realise that when I print the quaternions I am actually printing the eact same thing GetQ(), GetQ()+1 etc which is clearly why I am printing the exact same values. Very obvious and annoyed at myself for not realising this earlier. However my question is now, where are the Quaternions stored and how would I go about storing and accessing the separate values?

kriswiner commented 6 years ago

Yes, you will need to have two (or n, if you have n MPU9250s on the bus) versions of the quaternion array q[2,4] to hold the quaternions from each sensor separately, etc. I don;t have an example of this, but you cam modify the code accordingly.

On Thu, Jul 12, 2018 at 3:00 AM, benbrown2456 notifications@github.com wrote:

Was just re-reading my code and I realise that when I print the quaternions I am actually printing the eact same thing GetQ(), GetQ()+1 etc which is clearly why I am printing the exact same values. Very obvious and annoyed at myself for not realising this earlier. However my question is now, where are the Quaternions stored and how would I go about storing and accessing the separate values?

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

benbrown2456 commented 6 years ago

Thanks Kris,

As far as I can see q[] is declared as a 1x4 array rather than a 2x4 (please correct me if I am wrong on that). Does the code remember the last quaternions from a previous update? I am wondering if I can simply put q1,2,3,4 into my own variables for the front or the rear before I declare getData() again so it saves them seperately. This would not work if the code took more than just the accel, gyro and mag values as inputs. I feel like it should take the previous quaternion values as inputs as it has a deltat input however I cannot see in the code exactly where it gets these values from.

On a separate note, does the rate at which I sample the values have an effect on the accuracy?

MitalPattani commented 6 years ago

Hey Kris I tried using 2 instances (myIMU [2]) for two IMUs, I am using an i2c multiplexer. Now I am not getting full rotation i.e, if I rotate along the pitch axis by 90 degrees I only get 45 degree on serial!

kriswiner commented 6 years ago

Yes, in the simple example there is only one quaternion. If you want to use multiple MPU9250 and carry multiple (different) quaternions you will have to modify the sketch to allow multple quaternions, as in q[n, 4] where n is the number of MPU9250 you want to track, etc. The quaternions are iterated in the code using the delta_t time variable.

" On a separate note, does the rate at which I sample the values have an effect on the accuaracy? "

Yes. Best results are achieved using accle/gyro rates of 1 kHz in my experience.

On Fri, Jul 13, 2018 at 12:27 AM, benbrown2456 notifications@github.com wrote:

Thanks Kris,

As far as I can see q[] is declared as a 1x4 array rather than a 2x4 (please correct me if I am wrong on that). Does the code remember the last quaternions from a previous update? I am wondering if I can simply put q1,2,3,4 into my own variables for the front or the rear before I declare getData() again so it saves them seperately. This would not work if the code took more than just the accel, gyro and mag values as inputs. I feel like it should take the previous quaternion values as inputs as it has a deltat input however I cannot see in the code exactly where it gets these values from.

On a separate note, does the rate at which I sample the values have an effect on the accuaracy?

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

kriswiner commented 6 years ago

Don't know what to tell you, are you using two separate quaternion arrays, one for each MPU9250?

On Fri, Jul 13, 2018 at 3:04 AM, MitalPattani notifications@github.com wrote:

Hey Kris I tried using 2 instances (myIMU [2]) for two IMUs, I am using an i2c multiplexer. Now I am not getting full rotation i.e, if I rotate along the pitch axis by 90 degrees I only get 45 degree on serial!

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

MitalPattani commented 6 years ago

That worked, thanks alot.

benbrown2456 commented 6 years ago

Having changed the quarternion code I believe it is working however the main issue is that to toggle the enable bypass bit for the magnetometer I am finding I require a minimum of a 55 millisecond delay between the toggling command and reading the magnetometer leading to my full code having a frequency of around 10 hertz. Any less and I read the wrong magnetometer on occasion (could be 100% of the time with no gap and 50% of the time with a gap of 10 milliseconds). Unless anyone has ever experienced this problem and got past it with some clever technique I have concluded that using SPI or the FIFO bus (not sure if that's the right nomenclature as I have never used it) is the only way to proceed.

kriswiner commented 6 years ago

Sounds like this is an MCU problem, not and MPU9250 problem per se. Which MCU are you using? Maybe switch to an STM32L4 https://www.tindie.com/products/TleraCorp/ladybug-stm32l432-development-board/ and run the I2C bus frequency at 1 MHz?

On Mon, Jul 16, 2018 at 5:00 AM, benbrown2456 notifications@github.com wrote:

Having changed the quarternion code I believe it is working however the main issue is that to toggle the enable bypass bit for the magnetometer I am finding I require a minimum of a 55 millisecond delay between the toggling command and reading the magnetometer leading to my full code having a frequency of around 10 hertz. Any less and I read the wrong magnetometer on occasion (could be 100% of the time with no gap and 50% of the time with a gap of 10 milliseconds). Unless anyone has ever experienced this problem and got past it with some clever technique I have concluded that using SPI or the FIFO bus (not sure if that's the right nomenclature as I have never used it) is the only way to proceed.

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