2

For this project, I was using an Elegoo Car V3 and I was trying to add a gyroscope onto it. When I run the code for the car, my loop code iterates once and it is always able to read the sensor data. But after that, the program starts hanging. I traced back the problem to the Wire.endTransmission(false) line in my code. For some reason, that line was not completing the second time.

I spent a few hours trying to find a solution online. I triple checked my wiring and still, I could not find a solution to this problem.

Thank you for taking the time to help me!

This is the output of the program

RawX= 82
RawY= 241
RawZ= -1
-----------------------------------------
AngleX= 195.41
AngleY= 216.93
AngleZ= 200.14
-----------------------------------------

And this is the code


#include <Wire.h>

const int MPU_addr = 0x68;
int16_t AcX,AcY,AcZ,Tmp,GyX,GyY,GyZ;

int minVal = 265;
int maxVal = 402;

double x;
double y;
double z;
int c = 0;
 
//www.elegoo.com

//     Right motor truth table
//Here are some handy tables to show the various modes of operation.
//  ENB         IN3             IN4         Description  
//  LOW   Not Applicable   Not Applicable   Motor is off
//  HIGH        LOW             LOW         Motor is stopped (brakes)
//  HIGH        LOW             HIGH        Motor is on and turning forwards
//  HIGH        HIGH            LOW         Motor is on and turning backwards
//  HIGH        HIGH            HIGH        Motor is stopped (brakes)   

// define IO pin
#define ENA 5
#define ENB 6
#define IN1 7
#define IN2 8
#define IN3 9
#define IN4 11

//set car speed
#define CAR_SPEED 100
typedef unsigned char u8;  //Change the name of unsigned char to u8

void forward(u8 car_speed)
{
  analogWrite(ENA, car_speed);
  analogWrite(ENB, car_speed);
  digitalWrite(IN1, HIGH);
  digitalWrite(IN2, LOW);
  digitalWrite(IN3, LOW);
  digitalWrite(IN4, HIGH);
}


void back(u8 car_speed)
{
  analogWrite(ENA, car_speed);
  analogWrite(ENB, car_speed);
  digitalWrite(IN1, LOW);
  digitalWrite(IN2, HIGH);
  digitalWrite(IN3, HIGH);
  digitalWrite(IN4, LOW);
}


void left(u8 car_speed)
{
  analogWrite(ENA, 250);
  analogWrite(ENB, 250);
  digitalWrite(IN1, LOW);
  digitalWrite(IN2, HIGH);

  digitalWrite(IN3, LOW);
  digitalWrite(IN4, HIGH);
}

void right(u8 car_speed)
{
  analogWrite(ENA, 250);
  analogWrite(ENB, 250);
  digitalWrite(IN1, HIGH);
  digitalWrite(IN2, LOW);
  digitalWrite(IN3, HIGH);
  digitalWrite(IN4, LOW);
}

void stop()
{
  digitalWrite(ENA, LOW);
  digitalWrite(ENB, LOW);
}


int getGyroData() {
    Wire.beginTransmission(MPU_addr);
    Wire.write(0x3B);
    Wire.endTransmission(false);


    Wire.requestFrom(MPU_addr,6,true);
    AcX = Wire.read()<<8|Wire.read();
    AcY = Wire.read()<<8|Wire.read();
    AcZ = Wire.read()<<8|Wire.read();


    int xAng = map(AcX, minVal, maxVal,-90, 90);
    int yAng = map(AcY, minVal, maxVal,-90, 90);
    int zAng = map(AcZ, minVal, maxVal,-90, 90);

    x= RAD_TO_DEG * (atan2(-yAng, -zAng)+PI);
    y= RAD_TO_DEG * (atan2(-xAng, -zAng)+PI);
    z= RAD_TO_DEG * (atan2(-yAng, -xAng)+PI);

    Serial.print("AngleX= ");
    Serial.println(x);

    Serial.print("AngleY= ");
    Serial.println(y);

    Serial.print("AngleZ= ");
    Serial.println(z);
    Serial.println("-----------------------------------------");


}


void turn(int degrees) {
    int *originalData;
    originalData = getGyroData();
    int originalTurn = originalData[2];

    bool notDone = true;

    while (notDone) {
        
        int *newVal;
        newVal = getGyroData();
        int newTurn = newVal[2];

        int change = originalTurn - newTurn;
        Serial.println(change);
    }
}

void setup(){
  Wire.begin();
  Wire.beginTransmission(MPU_addr);
  Wire.write(0x6B);
  Wire.write(0);
  Wire.endTransmission(true);
  pinMode(IN1, OUTPUT);//before useing io pin, pin mode must be set first 
  pinMode(IN2, OUTPUT);
  pinMode(IN3, OUTPUT);
  pinMode(IN4, OUTPUT);
  pinMode(ENA, OUTPUT);
  pinMode(ENB, OUTPUT);
  Serial.begin(9600);
  
}


void loop(){
    c++;
    
    Serial.println(c);
    Wire.beginTransmission(MPU_addr);
    Serial.println(c);
    Wire.write(0x43);
    Serial.println(c);
    Wire.endTransmission(false);

    Serial.println(c);
    Wire.requestFrom(MPU_addr,4,true);
    AcX = Wire.read()<<8|Wire.read();
    AcY = Wire.read()<<8|Wire.read();
    AcZ = Wire.read()<<8|Wire.read();
    Serial.println(c);

    Serial.print("RawX= ");
    Serial.println(AcX);

    Serial.print("RawY= ");
    Serial.println(AcY);

    Serial.print("RawZ= ");
    Serial.println(AcZ);
    Serial.println("-----------------------------------------");

    int xAng = map(AcX, minVal, maxVal,-90, 90);
    int yAng = map(AcY, minVal, maxVal,-90, 90);
    int zAng = map(AcZ, minVal, maxVal,-90, 90);

    x= RAD_TO_DEG * (atan2(-yAng, -zAng)+PI);
    y= RAD_TO_DEG * (atan2(-xAng, -zAng)+PI);
    z= RAD_TO_DEG * (atan2(-yAng, -xAng)+PI);

    Serial.print("AngleX= ");
    Serial.println(x);

    Serial.print("AngleY= ");
    Serial.println(y);

    Serial.print("AngleZ= ");
    Serial.println(z);
    Serial.println("-----------------------------------------");
    delay(500);
    
}

This is a schematic of the car I found

This is a schematic of the car I found

3

In the comments below, @chrisl makes something explicit that I hadn't in previous edits. Reading it first may make the below easier to interpret:

Useful fact about I2C on Arduino: Wire.endTransmission() is the function, that actually does the I2C communication. Before that (all the Wire.beginTransmission() and Wire.write() calls) no data will run over the bus, just placed inside the libraries buffer. Thus a hanging Wire.endTransmission() equals a blocked I2C bus.


On the UNO the A4 and A5 are SDA and SCL, the same signals that are available near AREF and pin 13 on the other side of the board.

So, the ultrasonic range finder in the picture is attached the signals that are needed to operate the I2C ("Wire") bus, and may easily be interfering with Wire.endTransmission(false). One of the I2C signals is probably causing the range finger to trigger during I2C traffic. After each trigger, the echo signal from the range finder would then interfere with the connected I2C bus signal.

You could try bit banging I2C using a library instead of the native I2C that is on A4/A5, and use that to operate your gyroscope. According to your diagram, A0 through A3 are unused, and seem to be the only signals unused from the UNO. Despite being "analog" pins they function as digital pins also and should work fine for bit-banging. Getting to them may be a pain though, since the shield doesn't seem to make them available again as pins.

Or you may be able to route the ultrasonic sensor away from A4/A5 either by not plugging it into the header on the shield and instead route the signals from the plug to where an unused set of pins is available (again A0 though A3) and then updating the code accordingly. Another possibility might be leave it plugged into the shield but bend the A4 and A5 pins to the side so they don't enter the UNO below, and use jumpers to route them from the bent pins to some other pair of available pins; you won't be able to bend them back and forth more than once or twice, so I would be careful with trying that.

6
  • 1
    Useful fact about I2C on Arduino: Wire.endTransmission() is the function, that actually does the I2C communication. Before that (all the Wire.beginTransmission() and Wire.write() calls) no data will run over the bus, just placed inside the libraries buffer. Thus a hanging Wire.endTransmission() equals a blocked I2C bus. – chrisl Jan 1 at 13:19
  • Yeah, I probably should have been explicit about that. Will edit it later to incorporate your comment. – timemage Jan 1 at 13:54
  • @timemage This worked like a charm! Removing the ultrasonic sensor allowed the gyro to function. Thank you for answering so quickly! I just wanted to ask you why the A4 and A5 pins are used for the SDA and SCL communications pins. Can I use any other analog pins for the Gyro? – Akash Dubey Jan 1 at 15:45
  • I may try to update the answer to be more explicit that. A pin on the AVR may have have special functions beyond being a plain GPIO pin (digitalRead/digitalWrite capable) or connected to the analog to digital converter (analogRead capable). I2C/TWI "Wire" is a special function found only on the A4 an A5 pins of the UNO. The ultrasonic sensor by comparison uses only generic GPIO functionality that can be had on nearly any pin. So it makes sense to put the gyro on A4/A5 and move the ultrasonic sensor to A0-A3 when that's possible. – timemage Jan 1 at 16:08
  • Using I2C/Wire without the aid of the chip's native support for I2C is what "bit banging" means essentially. – timemage Jan 1 at 16:11

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service, privacy policy and cookie policy

Not the answer you're looking for? Browse other questions tagged or ask your own question.