<- Back

IMU selection for Ariwoo

while I am still waiting for MT6701 and TMAG5273 to arrive, and then conduct experiment with it to decide which encoder to use for our Ariwoo, the module LSM6DS3 has arrived.

I was not happy with the results we got for using as5600. It is getting distorted. As this asks for another log post, lets focus on looking into the IMU that we chose for Ariwoo.

There are Several reasons to look for better Inertial measurement units for Ariwoo.

  1. The current prototype, made with FR-4 plates is now installed with MPU6500. when the bot is in stable position, the bot struggles a lot. It as a bit of characteristic noise that I noticed before as well.
  2. MPU6500 is obsolete. I could not find ICs in major manufacturer’s sourcing websites.

I also took time to read Slime VR’s web page. they really have good explanation behind choosing each IMUs. It resonated with my thoughts well. I have seen in some of the reels in instagram that people tend suggest to use BMI270. But, LSM6DSR can do better than most of these.

Accelaration noise was around 0.000g to 0.0007g, which is LSM 3-4 times quieter compared to MPU6500. The headline is the accelerometer. Gravity is a known 1.000 g reference, and accel is independent of how the chip is oriented. So the fact that the LSM reads 1.007 g while the MPU reads 0.705 g for the same gravity isn’t noise or mounting, it’s a real scale error. I will be attaching 3 logs of LSM6DS3 here:

  1. log1.txt
  2. log2.txt
  3. log3.txt

For a balancer that integrates the gyro and leans on the accel for its level reference, that directly buys me a steadier angle with less filtering lag. The gyro bias on both is normal and gets removed by the startup calibration.



/* 
 * I have compared MPU6500 as well, and the performance of MPU6500 was not that great compared to LSM6DS3. 
 * This code is going to be LSM6DS3TR-C standalone I2C verification sketch. (for our ESP32-S3-Wroom-1-n16R8.)
 * 
 *     GPIO 38 = SDA I am also designing PCB, and I will address these pins with a pull up resistor.
 *     GPIO 39 = SCL
 *     I2C address:  0x6A (SA0/SDO to GND)   or   0x6B (SA0/SDO to 3V3)
 *     WHO_AM_I (0x0F) must read back 0x6A for the LSM6DS3TR-C.
 *     (0x69 = original LSM6DS3,  0x6C = LSM6DSO  different parts.)
 *
 *     Pull-ups: 4.7 kΩ to 3V3 on SDA + SCL (breakout boards had these; gonnabe following the same approach in PCB design.)
 *
 * Serial Monitor at 115200.
 */

#include <Wire.h>

// so I have finalised using 3 I2Cs.
// one will be software based bit bang, and other 2 will be hardwired I2Cs.
// as the project grows further, I will update more details.
#define IMU_SDA 38
#define IMU_SCL 39
#define I2C_HZ 400000

// LSM6DS3TR-C registers 
#define LSM_ADDR_LOW 0x6A   // SA0 = GND
#define LSM_ADDR_HIGH 0x6B  // SA0 = 3V3
#define REG_WHO_AM_I 0x0F   // 0x6A
#define REG_CTRL1_XL 0x10   // accelerometer config
#define REG_CTRL2_G 0x11    // gyroscope config
#define REG_CTRL3_C 0x12    // BDU + register auto-increment
#define REG_OUT_TEMP_L 0x20 // temperature, 2 bytes
#define REG_OUTX_L_G 0x22   // gyro  X..Z (6 bytes)
#define REG_OUTX_L_XL 0x28  // accel X..Z (6 bytes)
#define WHO_AM_I_VAL 0x6A

// Sensitivities for the settings configured below
#define ACC_MG_PER_LSB 0.061f   // ±2 g, mg/LSB
#define GYR_MDPS_PER_LSB 8.75f    // 250 dps, mdps/LSB

uint8_t imuAddr = 0x00; // gonna be resolved at runtime

// tiny register helpers 
bool imuWrite(uint8_t reg, uint8_t val) {
    Wire.beginTransmission(imuAddr);
    Wire.write(reg);
    Wire.write(val);
    return Wire.endTransmission() == 0;
}

uint8_t imuRead(uint8_t reg) {
    Wire.beginTransmission(imuAddr);
    Wire.write(reg);
    if (Wire.endTransmission(false) != 0) return 0; // repeated start
    Wire.requestFrom((uint8_t)imuAddr, (uint8_t)1);
    return Wire.available() ? Wire.read() : 0;
}

// burst-read n bytes starting at reg (IF_INC auto-increments the pointer)
bool imuReadBytes(uint8_t reg, uint8_t *buf, uint8_t n) {
    Wire.beginTransmission(imuAddr);
    Wire.write(reg);
    if (Wire.endTransmission(false) != 0) return false;
    if (Wire.requestFrom((uint8_t)imuAddr, n) != n) return false;
    for (uint8_t i = 0; i < n; i++) buf[i] = Wire.read();
    return true;
}

// locate device at 0x6A OR, 0x6B 
bool findIMU() {
    const uint8_t cand[2] = { LSM_ADDR_LOW, LSM_ADDR_HIGH };
    for (uint8_t i = 0; i < 2; i++) {
        Wire.beginTransmission(cand[i]);
        if (Wire.endTransmission() == 0) { imuAddr = cand[i]; return true; }
    }
    // if not found, then false. 
    return false;
}

void setup() {
    Serial.begin(115200);
    delay(1000);
    Serial.println("\n=== LSM6DS3TR-C I2C check  (SDA=38  SCL=39) ===");

    Wire.begin(IMU_SDA, IMU_SCL, I2C_HZ);

    if (!findIMU()) {
        Serial.println("FAIL: nothing answered at 0x6A or 0x6B.");
        while (true) delay(1000); // :-/ kkep an eye here, I am running on infinite loop.
    }
    Serial.printf("ACK at 0x%02X\n", imuAddr);

    uint8_t who = imuRead(REG_WHO_AM_I);
    Serial.printf("WHO_AM_I = 0x%02X  (expected 0x%02X)  ->  %s\n", who, WHO_AM_I_VAL, who == WHO_AM_I_VAL ? "MATCH" : "MISMATCH");
    if (who != WHO_AM_I_VAL)
        Serial.println("  (0x69 = LSM6DS3, 0x6C = LSM6DSO  different part)");

    // CTRL3_C : BDU=1 (bit6) + IF_INC=1 (bit2)  = 0x44
    imuWrite(REG_CTRL3_C, 0x44);
    // CTRL1_XL: 104 Hz, ±2 g     = 0x40
    imuWrite(REG_CTRL1_XL, 0x40);
    // CTRL2_G : 104 Hz, 250 dps  = 0x40
    imuWrite(REG_CTRL2_G, 0x40);

    Serial.println("Configured: accel +-2g @104Hz, gyro 250dps @104Hz");
    Serial.println("Tilt / rotate the board values should respond.\n");
    delay(200);
}

void loop() {
    uint8_t b[6];

    // accelerometer  (g)
    float ax = 0, ay = 0, az = 0;
    if (imuReadBytes(REG_OUTX_L_XL, b, 6)) {
        int16_t x = (int16_t)((b[1] << 8) | b[0]);
        int16_t y = (int16_t)((b[3] << 8) | b[2]);
        int16_t z = (int16_t)((b[5] << 8) | b[4]);
        ax = x * ACC_MG_PER_LSB / 1000.0f;
        ay = y * ACC_MG_PER_LSB / 1000.0f;
        az = z * ACC_MG_PER_LSB / 1000.0f;
    }

    // gyroscope  (dps)
    float gx = 0, gy = 0, gz = 0;
    if (imuReadBytes(REG_OUTX_L_G, b, 6)) {
        int16_t x = (int16_t)((b[1] << 8) | b[0]);
        int16_t y = (int16_t)((b[3] << 8) | b[2]);
        int16_t z = (int16_t)((b[5] << 8) | b[4]);
        gx = x * GYR_MDPS_PER_LSB / 1000.0f;
        gy = y * GYR_MDPS_PER_LSB / 1000.0f;
        gz = z * GYR_MDPS_PER_LSB / 1000.0f;
    }

    // temperature (16 LSB/°C, 0 LSB at 25 °C)
    // both these sensors also has in built sensors, and I found them somewhat okayish. 
    // though, they are not meant for reading the actual room temperature, they are just used to show how much the in-chip temperature is. 
    // I heated all the ICs to see how they behave.
    uint8_t t[2];
    float tempC = 0;
    if (imuReadBytes(REG_OUT_TEMP_L, t, 2)) {
        int16_t traw = (int16_t)((t[1] << 8) | t[0]);
        // tempC = traw / 256.0f + 25.0f; // playing around with the floating points to see how much the temp. changes.
        // 16.0f is now the LSM6DS3's actual datasheet sensitivity: 16 LSB/degree C.
        tempC = traw / 16.0f + 25.0f;    
    }

    Serial.printf("A[g] % .2f % .2f % .2f   G[dps] % 7.1f % 7.1f % 7.1f   T %.1fC\n", ax, ay, az, gx, gy, gz, tempC);
    //delay(200);
}

I have finalised that I will be choosing LSM6DS3 for IMU of Ariwoo.

Ariwoo only needs one number: the tilt angle. And gravity is always sitting right there on that axis as an absolute reference, so a complementary filter corrects the angle against it every few milliseconds. The gyro only has to stay accurate for the blink between corrections. Any bias or drift gets washed out almost immediately. This Sensor, LSM6DS3 is a confident pick.

Thank you! ♥️