Building a Line Following Robot

In this tutorial, we’ll upgrade the KY-033 line-following robot from the previous tutorial by replacing the KY-033 IR sensor with a TCS34725 RGB sensor. This new approach, combined with PID control, improves accuracy and stability, making it ideal for navigating complex tracks with smoother adjustments. Building on the previous project, you’ll gain a deeper insight into robotics and sensor integration while exploring advanced techniques for line-following robots.

 

 

Components Needed:

 

3D-Printed Parts

Chassis: Houses the motors, sensors, and Arduino board. - BUY NOW

Sensor Holder: Aligns the sensors for precise line detection. - BUY NOW

Arduino Holder: Mounts the Arduino securely to the chassis. - BUY NOW 

Motors and Wheels

 

2 DC Motors with Gearboxes: Drive the robot.- BUY NOW

2 Wheels: Provide mobility.- BUY NOW

1 Support Wheel: Balances the robot for smooth movement.- BUY NOW 

 

Electronics

Arduino Uno: Microcontroller for programming and control.- BUY NOW

Arduino Motor Shield Rev3: Drives the motors and distributes power.

TCS34725 RGB Light Sensor: Measures light intensity to differentiate between colors.

 

Accessories

Jumper Wires: For connecting components.- BUY NOW

Screws and Inserts: To securely mount parts.

Battery (e.g., 7.4V LiPo): Powers the robot.

Power Switch: Optional, for easy on/off control. - BUY NOW 

 

Step 1: Designing the Robot in Autodesk Inventor

We started by designing the robot in Autodesk Inventor. The design ensures all components fit securely while maintaining a lightweight and compact structure. Key features include:

Chassis: A sturdy base for mounting the motors, sensors, and Arduino.

Sensor Holder: Holds the TCS34725 sensor for precise line detection.

Arduino Holder: Provides easy access to the Arduino for programming and wiring.

You can download the STL files for these 3D-printed parts from Cults3D.

 

Step 2: 3D Printing the Components

After finalizing the design, we used a Creality Ender 3 printer to 3D print the components. Materials like PLA or ABS are recommended for durability. Ensure the parts are cleaned and prepared before assembly.

 

Step 3: Assembling the Line-Following Robot With TCS34725 RGB Sensor

1. Mounting the Motors and Wheels

Secure the motors to the chassis using screws and inserts. Attach the wheels to the motor shafts and ensure smooth rotation. Mount the support wheel at the rear for balance.

2. Installing the Electronics

Mount the Arduino Uno and Motor Shield to the chassis. Attach the sensors to the sensor holder. Connect the Battery and secure all components.

3. Wiring the Components

Wire the motors to the Motor Shield. Connect the sensors to the Arduino pins. Ensure the battery is safely connected and add a switch for convenience.

 

 

Step 4: Understanding PID Control

The TCS34725 RGB sensor is highly effective for distinguishing the black line from the white background due to its ability to measure light intensity across various wavelengths. This approach includes a calibration phase and uses a PID controller to ensure smooth and accurate path following.

 

Understanding PID Control Fully in the Context of Line Following

The PID (Proportional-Integral-Derivative) controller is a fundamental concept in control systems, designed to adjust outputs based on feedback from a process variable. In the context of the line-following robot, PID ensures dynamic control of motor speeds, enabling precise and smooth path following.


Components of the PID Controller

Proportional (P) Component

Purpose: Reacts immediately to the error. 

Equation:
y(t) = Kp * e(t) 

How it works:
The proportional term multiplies the current error (e) by a proportional gain (Kp). This provides a correction that is directly proportional to the deviation from the desired position, such as the center of the line. 

 

Effect:Quick responsiveness to errors.Larger Kp values result in faster reactions but can cause overshooting or instability. 

 

Example in Line Following:
If the robot veers off the line, the proportional component immediately adjusts motor speeds to steer it back. 

 

Integral (I) Component

Purpose: Compensates for accumulated errors over time. 

Equation:
y(t) = Ki * ∫e(t) dt 

 

How it works:
The integral term sums the error over time and multiplies it by the integral gain (Ki). This helps to correct long-term drift caused by persistent small errors. 

 

Effect:Eliminates steady-state error.Slower to react compared to the proportional component. 

 

Example in Line Following:
If the robot consistently drifts to one side, the integral component adjusts the motors to correct the bias over time. 

 

Derivative (D) Component (optional for this project)

Purpose: Reacts to the rate of change of the error.

Equation:
y(t) = Kd * (de(t)/dt) 

 

How it works:
The derivative term predicts future errors based on the rate at which the error changes and multiplies this rate by the derivative gain (Kd). 

 

Effect:Reduces oscillations and improves stability.Particularly useful for systems experiencing rapid changes. 

 

Example in Line Following:
If the robot oscillates around the line, the derivative component stabilizes it by reducing abrupt motor speed changes.

 

Combining P, I, and D in a PID Controller

A PID controller combines these three components to provide precise and stable control. The combined equation is:

y(t) = Kp * e(t) + Ki * ∫e(t) dt + Kd * (de(t)/dt)

 

How it applies to Line Following:

The proportional term reacts immediately to how far the robot is from the line.The integral term addresses consistent drift over time.The derivative term dampens oscillations and stabilizes movement.

 

Dynamic Error Correction with PID

Error Calculation:

The error (e) is the difference between the sensor reading and the threshold (middle value).This error drives the PID calculations.

Correction Value (y):

The PID controller calculates y to determine how much to adjust motor speeds:speedLeft = baseSpeed + yspeedRight = baseSpeed - y 

Motor Speed Adjustment:

Motor speeds are adjusted dynamically based on the correction value to maintain the robot on the line. 

 

Advantages of Using PID in Line Following

Precision: Keeps the robot accurately centered on the line, even in curves.

Smooth Movements: Avoids jerky or abrupt adjustments by balancing the contributions of P, I, and D.Disturbance Rejection: Handles changes in surface reflectivity or motor inconsistencies.Adaptability: Can be tuned for different track layouts or robot configurations.

 

 

Practical Tuning of PID

Start with Proportional Gain (Kp):

Gradually increase Kp until the robot begins to follow the line effectively. Monitor for overshooting or oscillations. 

Add Integral Gain (Ki):

Introduce Ki to address steady-state errors (e.g., consistent drift).Avoid excessive Ki to prevent instability or oscillations. 

Adjust Derivative Gain (Kd):

If necessary, use Kd to stabilize movements and reduce oscillations. Avoid setting Kd too high, as it can make the robot sluggish. 

Complete Code for TCS34725 Sensor with PID:

 

Step 5: Programming the Line-Following Robot With TCS34725 RGB Sensor

 

 

 

 

Step 6: Testing the Line-Following Robot With TCS34725 RGB Sensor

 

To test the functionality of the robot, a 50mm wide white adhesive tape was placed on a dark surface, forming a curvy line. This setup simulates a typical track for a line-following robot. The testing process was conducted using two different sensor configurations:

The Line-Following Robot With TCS34725 RGB Sensor was placed at the left edge of the white tape, with the TCS34725 sensor positioned near the line.The robot performed an automatic calibration by measuring light intensity in two key areas:

Dark Area: The robot slightly rotated to measure the dark background.

Bright Area: The robot slightly rotated in the opposite direction to measure the white tape.

 

After calculating the middle value as the threshold, the robot began following the line. The PID controller was used to ensure smooth and precise adjustments while navigating curves.

CODE
#include <Wire.h>
#include <AFMotor.h>
#include <Adafruit_TCS34725.h>
 
// Initialize TCS34725 sensor
Adafruit_TCS34725 tcs = Adafruit_TCS34725(TCS34725_INTEGRATIONTIME_2_4MS, TCS34725_GAIN_4X);
 
// Motor control pins
#define DIR_A 12
#define DIR_B 13
#define PWM_A 3
#define PWM_B 11
 
// PID parameters
float Kp = 24.0;  // Proportional gain
float Ki = 1.0;   // Integral gain
float Kd = 1.0;   // Derivative gain
int baseSpeed = 60;  // Base speed
 
// Middle value for black/white
int middleValue = 3; // Adjusted based on measured values
 
// Global variables for PID
float error = 0, previousError = 0, sumError = 0;
 
void setup() {
  Serial.begin(9600);
 
  // Initialize TCS34725 sensor
  if (!tcs.begin()) {
    Serial.println("Error: TCS34725 not detected. Check wiring!");
    while (1);
  }
  Serial.println("TCS34725 sensor detected!");
 
  // Configure motor control pins
  pinMode(DIR_A, OUTPUT);
  pinMode(DIR_B, OUTPUT);
  pinMode(PWM_A, OUTPUT);
  pinMode(PWM_B, OUTPUT);
 
  // Perform sensor calibration
  calibrateSensor();
}
 
void loop() {
  uint16_t r, g, b, c;
  tcs.getRawData(&r, &g, &b, &c);
 
  // Calculate error
  error = middleValue - (float)c ;
 
  // PID calculation
  sumError += error;
  sumError = constrain(sumError, -4, 4); // Limit integral component
 
  if (abs(error) < 2.0) {
    sumError = 0; // Reset for small errors
  }
 
  float differential = error - previousError;
  float correction = Kp * error + Ki * sumError + Kd * differential;
  previousError = error;
 
  // Adjust motor speeds
  int speedLeft = baseSpeed + (int)correction;
  int speedRight = baseSpeed - (int)correction;
 
  speedLeft = constrain(speedLeft, 20, 255);
  speedRight = constrain(speedRight, 20, 255);
 
  controlMotors(speedLeft, speedRight);
}
 
void calibrateSensor() {
  uint16_t r, g, b, c;
 
  // Measure black value
  Serial.println("Calibrating: Measuring black value...");
  controlMotors(-85, 85); // Slightly turn left
  delay(350);
   // Stop motors after calibration
  controlMotors(0, 0);
  delay(50);
 
  tcs.getRawData(&r, &g, &b, &c);
  int blackValue = c;
  Serial.print("Black Value: ");
  Serial.println(blackValue);
 
  // Measure white value
  Serial.println("Calibrating: Measuring white value...");
  controlMotors(85, -85); // Slightly turn right
  delay(500);
    // Stop motors after calibration
  controlMotors(0, 0);
  delay(50);
 
  tcs.getRawData(&r, &g, &b, &c);
  int whiteValue = c;
  Serial.print("White Value: ");
  Serial.println(whiteValue);
 
  // Calculate middle value
  middleValue = (blackValue + whiteValue) / 2;
  Serial.print("Middle Value: ");
  Serial.println(middleValue);
 
  // Stop motors after calibration
  controlMotors(0, 0);
}
 
void controlMotors(int speedLeft, int speedRight) {
  if (speedLeft >= 0) {
    digitalWrite(DIR_A, HIGH);
  } else {
    digitalWrite(DIR_A, LOW);
    speedLeft = abs(speedLeft);
  }
 
  if (speedRight >= 0) {
    digitalWrite(DIR_B, HIGH);
  } else {
    digitalWrite(DIR_B, LOW);
    speedRight = abs(speedRight);
  }
 
  analogWrite(PWM_A, speedLeft);
  analogWrite(PWM_B, speedRight);
}
License
All Rights
Reserved
licensBg
0