Building a Line Following Robot with TCS34725 RGB Sensor

Ready to take your line-following robot to the next level? In this advanced Arduino tutorial, you will build a TCS34725 line-following robot that uses an RGB color sensor and a PID controller to navigate tracks with precision and stability. If you completed the beginner line-following robot with KY-033 IR sensors, this project is the natural next step. Specifically, you will replace the simple infrared sensor with the TCS34725 RGB light sensor, add a full PID control loop, and achieve noticeably smoother and more accurate line tracking, even on complex curved tracks.

As a result, this tutorial covers the complete build process from 3D-printed chassis design to wiring, calibration, Arduino programming, and PID tuning. Therefore, whether you are building your first Arduino PID line follower or upgrading from a simpler design, this guide gives you everything you need to build, program, and tune an advanced line-following robot powered by the TCS34725 sensor and the Arduino Motor Shield Rev3.

What You Will Learn

  • How the TCS34725 RGB sensor detects the contrast between the track line and the background surface
  • How PID control improves line-following stability compared to simple on/off steering
  • How the Arduino Uno and Motor Shield Rev3 work together to drive the robot
  • How the robot calibrates itself automatically by sampling black and white areas
  • How to wire, assemble, program, and test the complete robot
  • How to tune PID parameters (Kp, Ki, Kd) for better performance on different tracks

How the Robot Works

Before diving into the build, it helps to understand the overall system. This TCS34725 Arduino robot uses a closed-loop feedback system where sensor input directly controls motor output through a PID algorithm. Here is how each component contributes:

First, the Arduino Uno serves as the brain of the robot. It reads sensor data, runs the PID calculations, and sends speed commands to both motors. Meanwhile, the Arduino Motor Shield Rev3 sits on top of the Uno and handles power distribution and direction control for the two DC motors. Consequently, it allows the Arduino to independently control the speed and direction of each wheel, which is essential for steering.

Sensor and Calibration

The TCS34725 RGB light sensor is mounted on the underside of the robot, facing down toward the track surface. Unlike a simple IR reflectance sensor that only detects light or dark, the TCS34725 measures light intensity across red, green, blue, and clear channels. In this project, however, the clear channel (C) is used because it provides a reliable overall brightness reading that clearly distinguishes a dark line from a light background.

Furthermore, during startup, the robot performs an automatic calibration routine. It rotates slightly to position the sensor over a dark area, records the light intensity as the black value, then rotates in the opposite direction to sample the white background. The average of these two readings becomes the threshold (middleValue). Subsequently, during operation, the sensor continuously reads the clear channel, and the difference between the current reading and the threshold becomes the error signal that feeds into the PID controller.

Finally, the PID controller takes this error and calculates a correction value. In particular, a positive correction means the robot needs to steer one way; a negative correction means the opposite. This correction is added to the left motor speed and subtracted from the right motor speed (or vice versa), creating a smooth differential steering response. As a result, the robot follows the line with minimal oscillation and adapts smoothly to curves, a significant improvement over the simpler bang-bang control used in the KY-033 line-following robot tutorial.

Components Needed (Bill of Materials)

The following table lists every component required to build this RGB sensor line-following robot. Moreover, if you already built the KY-033 line-following robot, you can reuse the chassis, motors, wheels, Arduino, and motor shield. The only new component is the TCS34725 sensor module.

3D-Printed Parts

These parts are custom-designed for this project and can be downloaded as STL files from Cults3D or get the complete project package from our OmArTronics Shop.

ComponentRequired / OptionalPurposeNotes
ChassisRequiredHouses the motors, sensor, and Arduino board3D-printed, PLA or ABS recommended
Sensor HolderRequiredAligns the TCS34725 sensor for consistent line detectionKeeps sensor at correct height above the track
Arduino HolderRequiredMounts the Arduino Uno securely to the chassisProvides easy access for programming and wiring

Motors, Wheels, and Electronics

ComponentQtyRequired / OptionalPurposeNotes
DC Motor with Gearbox2RequiredDrives the robot wheelsStandard yellow TT motors work well
Wheels2RequiredProvide mobilityMust fit the motor shafts
Support Wheel (Caster)1RequiredBalances the robot at the rearBall caster or swivel caster
Arduino Uno1RequiredMicrocontroller for programming and controlRuns PID calculations and reads sensor data
Arduino Motor Shield Rev31RequiredDrives both motors and distributes powerStacks directly on the Arduino Uno
TCS34725 RGB Light Sensor1RequiredMeasures light intensity to detect line contrastUses the clear (C) channel for this project
Jumper WiresSeveralRequiredConnects componentsMale-to-female and male-to-male
Screws and Threaded InsertsAs neededRequiredSecurely mounts all parts to the chassisM3 screws recommended
Battery (7.4V LiPo or 9V)1RequiredPowers the robotLiPo recommended for consistent voltage
Power Switch1OptionalEasy on/off controlSaves battery life between tests

Step 1: Designing the Robot in Autodesk Inventor

The robot was designed in Autodesk Inventor to ensure all components fit securely while keeping the structure lightweight and compact. In particular, the design focuses on three custom parts:

  • Chassis: A sturdy base for mounting the motors, the TCS34725 sensor, and the Arduino with its motor shield.
  • Sensor Holder: Positions the TCS34725 sensor at the correct height above the ground for reliable readings. Proper sensor height is critical for accurate calibration and consistent line detection.
  • Arduino Holder: Provides easy access to the Arduino Uno for programming, wiring, and debugging.

You can download the STL files for all 3D-printed parts from Cults3D or get them from our OmArTronics Shop.

Step 2: 3D Printing the Components

Once the design is finalized, print the components using a standard FDM 3D printer. A Creality Ender 3 or similar printer works well. PLA is the easiest material to print, while ABS offers more durability if you plan to use the robot extensively. Afterward, clean the parts after printing: remove any support material, sand rough edges, and verify that all screw holes and component slots are the correct size before assembly.

Step 3: Assembling the Line-Following Robot

Assembled TCS34725 line-following robot with orange 3D-printed chassis, two DC motor wheels, a rear caster, and the OmArTronics logo.

Mounting the Motors and Wheels

  1. First, secure both DC motors to the chassis using M3 screws and threaded inserts. Make sure the motor shafts face outward.
  2. Next, press the wheels onto the motor shafts and verify that both wheels spin freely without rubbing against the chassis.
  3. Finally, mount the support caster wheel at the rear of the chassis to provide stable three-point balance.

Installing the Electronics

  1. First, mount the Arduino Uno into the Arduino holder and attach the holder to the chassis.
  2. Then, stack the Arduino Motor Shield Rev3 on top of the Arduino Uno, ensuring all header pins are properly aligned.
  3. After that, attach the TCS34725 sensor module to the sensor holder and mount the holder to the front-bottom of the chassis, facing downward toward the track surface. The sensor should be approximately 10 to 15 mm above the ground for best results.
  4. Lastly, connect the battery and secure all components so nothing is loose during movement.

Step 4: Wiring the Components

Importantly, this project uses a single TCS34725 RGB sensor (not multiple sensors). Specifically, the sensor connects to the Arduino via I2C, while the motors are controlled through the Motor Shield. The wiring diagram below shows the complete circuit.

Complete wiring diagram for the TCS34725 line-following robot showing connections between Arduino Uno, Motor Shield Rev3, TCS34725 sensor, two DC motors, and battery.

Motor Connections

The DC motors connect to the motor terminals on the Arduino Motor Shield Rev3. The shield handles direction and PWM speed control through these pins:

MotorShield TerminalDirection PinPWM (Speed) Pin
Left Motor (Motor A)Motor A terminalDigital Pin 12 (DIR_A)Digital Pin 3 (PWM_A)
Right Motor (Motor B)Motor B terminalDigital Pin 13 (DIR_B)Digital Pin 11 (PWM_B)

TCS34725 Sensor Connections (I2C)

The TCS34725 communicates with the Arduino over the I2C bus. Connect it as follows:

TCS34725 PinArduino PinNotes
VIN5VPower supply for the sensor
GNDGNDCommon ground
SDAA4 (SDA)I2C data line
SCLA5 (SCL)I2C clock line

Power Connections

ComponentConnectionNotes
Battery (7.4V LiPo or 9V)Motor Shield external power inputPowers both motors and Arduino through the shield
Power Switch (optional)In series with battery positive leadAllows easy on/off without disconnecting the battery

Important: This project uses one single TCS34725 sensor, not an array of multiple sensors. The sensor reads the clear channel (C) to detect overall brightness. All references to “sensor” throughout this tutorial refer to this single TCS34725 module.

Step 5: Understanding PID Control for This Robot

The TCS34725 RGB sensor is highly effective for distinguishing a black line from a white background due to its ability to measure light intensity. This project combines that sensor with a PID (Proportional-Integral-Derivative) controller to ensure smooth and accurate path following. For instance, if you previously built the KY-033 line-following robot, you will notice a major difference: the KY-033 version used simple on/off digital signals (line detected or not), resulting in jerky zig-zag behavior. This PID-based approach uses continuous analog values from the TCS34725 clear channel to calculate proportional corrections, producing much smoother and more predictable motion.

PID feedback control loop diagram showing how the setpoint, error, controller output, and plant feedback work together in the TCS34725 line-following robot.

What Error, Setpoint, and Correction Mean in This Robot

To clarify, in this specific robot, the PID terms map to concrete values:

  • Setpoint: The middleValue, which is the average of the black and white calibration readings. This represents the boundary between line and background.
  • Process variable: The current clear-channel reading from the TCS34725 sensor.
  • Error: The difference between the middleValue and the current sensor reading. A positive error means the sensor is over the dark line; a negative error means it is over the bright background.
  • Correction (y): The PID output value added to one motor speed and subtracted from the other, creating differential steering.

The Three PID Components

Proportional (P) — Reacts to the current error. The proportional term multiplies the current error by the gain Kp. For example, in this robot, if the sensor drifts off the line edge, the P term immediately produces a correction proportional to how far off the sensor is. Larger Kp values produce faster reactions but can cause overshooting and oscillation if set too high. The equation is: P = Kp × error.

Integral (I) — Compensates for accumulated error over time. The integral term sums the error over time and multiplies it by Ki. In particular, this is useful when the robot consistently drifts slightly to one side due to motor differences or track asymmetry. The integral corrects this steady-state bias. In the code, the integral sum is constrained to a small range (±4) to prevent windup, and it resets when the error is small. The equation is: I = Ki × Σerror.

Derivative (D) — Predicts future error from the rate of change. The derivative term looks at how fast the error is changing and multiplies the change rate by Kd. Essentially, this acts as a damper: if the robot is swinging toward the line quickly, the D term slows down the correction to prevent overshoot. However, for this project, the derivative component is optional and secondary. The P and I terms do most of the work; Kd can be increased slightly if you observe persistent oscillation. The equation is: D = Kd × (error − previousError).

The Combined PID Equation

The full PID correction combines all three terms: correction = Kp × error + Ki × Σerror + Kd × (error − previousError). Subsequently, this correction value is then applied to the motor speeds:

  • speedLeft = baseSpeed + correction
  • speedRight = baseSpeed − correction

For instance, when the error is zero (sensor is right on the threshold), both motors run at the base speed and the robot drives straight. When the error is positive or negative, the correction makes one motor faster and the other slower, causing the robot to steer back toward the line.

Advantages of PID for Line Following

  • Precision: Keeps the robot accurately tracking the line edge, even through curves.
  • Smooth motion: Eliminates the jerky zig-zag behavior common in simple threshold-based line followers.
  • Disturbance rejection: Handles changes in surface reflectivity, motor inconsistencies, and battery voltage drops.
  • Adaptability: Can be tuned for different track layouts, line widths, and robot speeds by adjusting Kp, Ki, and Kd.

Step 6: Programming the Line-Following Robot (Arduino Code)

Below is the complete Arduino sketch for the TCS34725 line-following robot with PID control. Upload this code to your Arduino Uno using the Arduino IDE. Before uploading, make sure you have the Adafruit TCS34725 library and the AFMotor library installed before compiling. You can find both in the Arduino Library Manager. The full code is also available on the GitHub repository linked in the Resources section.

Complete Arduino Sketch

/**
 * Author: Omar Draidrya
 * Date: 2024/12/06
 * Line-Following Robot with TCS34725.
 */
#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);
}
    

Code Walkthrough

Here is a detailed breakdown of each section of the code so you understand how the TCS34725 sensor-based line-following robot operates:

Sensor Initialization

Adafruit_TCS34725 tcs = Adafruit_TCS34725(TCS34725_INTEGRATIONTIME_2_4MS, TCS34725_GAIN_4X);
    

The TCS34725 sensor is initialized with a very short integration time (2.4 ms) and moderate gain (4×). As a result, the short integration time means the sensor takes readings extremely quickly, which is critical for a moving robot that needs to respond to line changes in real time. The 4× gain amplifies the signal enough to distinguish black from white without saturating the sensor on bright surfaces. Therefore, if your readings seem too low or too high, you can experiment with different gain settings (1×, 4×, 16×, or 60×).

Motor Pin Definitions

#define DIR_A 12
#define DIR_B 13
#define PWM_A 3
#define PWM_B 11
    

In summary, these pin definitions match the Arduino Motor Shield Rev3 layout. DIR_A and DIR_B control the rotation direction of each motor (HIGH for forward, LOW for reverse). PWM_A and PWM_B control the speed of each motor using pulse-width modulation (PWM), where a value of 0 means stopped and 255 means full speed. Consequently, the PID correction adjusts these PWM values independently for each motor to create steering.

Calibration Routine

void calibrateSensor() {
  // Measures the light intensity for black and white areas.
  // Calculates the middle value (threshold) as the average of the two.
}
    

The calibration function is one of the most important parts of the code. Specifically, when the robot powers on, it performs these steps automatically:

  1. Measure the black (dark) value: The robot rotates slightly to the left for 350 ms, positioning the sensor over the dark surface area. It then stops and takes a clear-channel reading, which becomes the blackValue.
  2. Measure the white (bright) value: The robot rotates to the right for 500 ms (slightly longer to also cover the white tape). It stops and takes another reading, which becomes the whiteValue.
  3. Calculate the threshold: As a result, the middleValue is set to the average of the black and white readings. This threshold is the dividing line between “on the dark line” and “on the bright background” for all subsequent PID calculations.

Important placement note: Before powering on the robot, place it so the sensor starts at the left edge of the white tape on the dark surface. The calibration assumes the robot will first read a dark area (left turn) and then a bright area (right turn). If the robot is placed in the wrong position, calibration will give incorrect values and the robot will not follow the line correctly.

Main Loop and Error Calculation

void loop() {
  uint16_t r, g, b, c;
  tcs.getRawData(&r, &g, &b, &c);
  // Reads the light intensity from the sensor.
  // Calculates error and adjusts motor speeds using PID control.
}
    

In every loop iteration, the sensor reads the red, green, blue, and clear channels. However, only the clear channel c is used because it provides a reliable overall brightness measurement. The error is calculated as middleValue - c: when the sensor is over the dark line, c is low and the error is positive; when it is over the bright background, c is high and the error is negative. Consequently, this signed error drives the PID correction to steer the robot in the correct direction.

PID Correction Calculation

float correction = Kp * error + Ki * sumError + Kd * differential;
    

Essentially, this single line is the core of the PID controller. It combines proportional, integral, and derivative terms into one correction value. The integral sum (sumError) is constrained between -4 and 4 to prevent integral windup, which could cause the robot to overshoot badly after a long turn. Additionally, when the error is very small (less than 2.0), the integral sum resets to zero, preventing unnecessary accumulated correction when the robot is already tracking well.

Speed Limiting

Once the PID correction is applied to the base speed, both motor speeds are constrained to a range of 20 to 255 using the constrain() function. In other words, the minimum of 20 ensures the motors always have enough power to turn (very low PWM values may not produce any motion due to motor friction). The maximum of 255 is the Arduino PWM limit.

Motor Control Function

void controlMotors(int speedLeft, int speedRight) {
  // Adjusts motor direction and speed based on the calculated correction.
}
    

The controlMotors() function accepts signed speed values for each motor. Specifically, positive values drive the motor forward; negative values drive it in reverse (used during calibration turns). Therefore, the function sets the direction pin (HIGH or LOW) and then applies the absolute speed value via PWM. As a result, this allows the same function to handle forward driving, turning, and the calibration rotation maneuvers.

Step 7: Calibration — How the Robot Learns the Track

Importantly, calibration is essential for this robot because the absolute sensor readings vary depending on lighting conditions, sensor height, surface color, and tape material. Instead of hardcoding a fixed threshold, the robot measures the actual environment at startup and calculates the threshold dynamically.

Before Calibration: Correct Placement

Place the robot so the TCS34725 sensor is positioned at the left edge of the white tape, with the dark surface to the left and the white tape to the right. This ensures that when the robot rotates left during calibration, the sensor reads the dark background, and when it rotates right, it reads the white tape.

What the Calibration Routine Does

  1. Rotates the robot left for 350 ms and records the clear-channel reading as blackValue.
  2. Rotates the robot right for 500 ms and records the clear-channel reading as whiteValue.
  3. Calculates middleValue = (blackValue + whiteValue) / 2.
  4. Prints all three values to the Serial Monitor so you can verify correct calibration.

What to Do If Calibration Gives Poor Values

  • For example, if the black and white values are very close together, the sensor cannot distinguish the line from the background. Check the sensor height (should be 10–15 mm above the surface), ensure the line has strong contrast, and verify the sensor is working by checking raw values in the Serial Monitor.
  • Similarly, if the values seem reversed (black value higher than white value), the robot may have been placed in the wrong starting position or the rotation times need adjustment.
  • In addition, if the sensor always returns very low or zero values, check the I2C wiring (SDA to A4, SCL to A5) and confirm the sensor is detected at startup.

Step 8: How to Test and Tune the Robot

TCS34725 line-following robot being tested on a curved white tape track on a dark surface, demonstrating PID-controlled line tracking.

In essence, testing and tuning are where your line-following robot goes from “working” to “working well.” Follow this process to get the best performance from your DIY line follower robot with PID.

Setting Up the Test Track

  • Use a 50 mm wide white adhesive tape on a dark, non-reflective surface. This provides strong contrast for the TCS34725 sensor.
  • Therefore, start with a simple oval or gentle curve layout. Avoid sharp 90-degree turns until the PID is tuned.
  • Furthermore, make sure the track surface is evenly lit. Shadows or bright spotlights can confuse the sensor readings.

Tuning the PID Parameters

PID tuning is an iterative process. The default values in the code (Kp = 24.0, Ki = 1.0, Kd = 1.0) are a good starting point, but you may need to adjust them for your specific setup.

  1. Start with Kp only. Set Ki = 0 and Kd = 0. Then, gradually increase Kp from a low value (e.g., 5) until the robot begins to follow the line. If it overshoots and oscillates, reduce Kp slightly.
  2. Add Ki carefully. For instance, if the robot consistently drifts to one side or misses gentle curves, increase Ki in small increments (e.g., 0.5). Too much Ki causes slow oscillation and instability.
  3. Add Kd only if needed. In contrast, if the robot oscillates even after tuning Kp, a small Kd value (e.g., 0.5 to 2.0) can dampen the oscillation. Avoid setting Kd too high, as it can make the robot sluggish or jittery.
  4. Reduce base speed during early tests. Essentially, a lower baseSpeed (e.g., 40–60) gives the PID controller more time to react. Once tuned, you can gradually increase the speed.
  5. Watch for oscillation vs. sluggishness. Specifically, if the robot zig-zags rapidly around the line, Kp is too high or Kd is too low. If the robot reacts too slowly and misses curves, Kp is too low.

Open the Serial Monitor at 9600 baud while testing. The calibration values and error readings will help you understand what the robot is seeing and how to adjust the PID gains.

Troubleshooting Common Issues

If your robot is not performing as expected, the following tables summarize the most common problems and their solutions:

ProblemPossible CauseSolution
Robot does not follow the line at allSensor not detected, wrong wiring, or failed calibrationCheck I2C wiring (SDA→A4, SCL→A5). Open Serial Monitor to verify sensor detection and calibration values. Reposition the robot and recalibrate.
Robot oscillates heavily around the lineKp is too high or Kd is too lowReduce Kp by 20–30%. Add a small Kd value (0.5–2.0) to dampen oscillation.
Robot reacts too slowly and misses curvesKp is too low or base speed is too highIncrease Kp gradually. Reduce baseSpeed to give the PID more reaction time.
Sensor readings seem unstable or noisySensor too far from surface, ambient light interference, or loose wiringLower the sensor to 10–15 mm above the track. Shield the sensor from overhead lights. Check all wire connections.
Robot calibrates incorrectlyWrong starting position or insufficient contrastPlace the robot at the left edge of the white tape on the dark surface. Ensure the tape is truly white and the background is truly dark.

Motor, Power, and Track Issues

ProblemPossible CauseSolution
Motors are too weak or do not moveLow battery, PWM value too low, or motor wiring reversedCharge or replace the battery. Check that minimum speed (20) is enough for your motors. Swap motor wires if direction is wrong.
One motor runs faster than the otherMotor hardware differences or wiring issueThis is normal for cheap motors. The integral (Ki) term in the PID helps correct this drift. You can also adjust the base speed offset in code.
Robot drives in circles during calibrationOne motor is wired in reverseSwap the positive and negative wires for the motor that turns in the wrong direction.
Line contrast is insufficientTape color too similar to background, or glossy surface causes reflectionsUse matte white tape on a matte dark surface. Avoid glossy floors or metallic tape.
Power issues cause inconsistent behaviorBattery voltage dropping during motor useUse a fully charged LiPo battery. A 9V block battery may not provide enough current for both motors. Consider a battery voltage monitor.

Frequently Asked Questions

What is the TCS34725 sensor and why use it for a line-following robot?

The TCS34725 is an RGB color and clear light sensor that communicates over I2C. In contrast to basic IR reflectance sensors, it provides analog light intensity values across multiple channels, allowing for more precise threshold-based line detection. This makes it ideal for building an advanced Arduino line-following robot with PID control.

What is PID control and why does a line-following robot need it?

PID stands for Proportional-Integral-Derivative. It is a feedback control algorithm that calculates a correction based on the current error, accumulated past errors, and the rate of error change. As a result, a line-following robot with PID control follows the line smoothly instead of zig-zagging, because the motor speed adjustments are proportional to how far off the line the sensor is.

Can I use a different Arduino board instead of the Arduino Uno?

Yes, in fact, you can use other Arduino-compatible boards such as the Arduino Mega or Arduino Nano, as long as they support I2C and have compatible pins for the Motor Shield. The Motor Shield Rev3 is designed for the Uno form factor, so it stacks directly on the Uno or Mega. If you use a Nano, you will need to wire the motor driver connections manually.

How is this project different from the KY-033 line-following robot?

The KY-033 line-following robot tutorial used simple digital IR sensors that output only HIGH or LOW signals. Consequently, the robot steered using basic threshold logic, which caused jerky motion. This TCS34725 version uses analog light intensity readings combined with a PID controller, resulting in much smoother tracking and the ability to handle complex curved tracks.

What channel of the TCS34725 does this robot use?

This project uses the clear (C) channel of the TCS34725. The clear channel measures overall light intensity without any color filter, which provides the best contrast between dark and bright surfaces for line detection.

How does the automatic calibration work?

At startup, the robot rotates left to read the dark surface and right to read the white tape. It then calculates the average of these two readings as the threshold (middleValue). As a result, this calibration adapts to different lighting conditions and surface colors, so you do not need to hardcode sensor thresholds.

What battery should I use for this robot?

A 7.4V LiPo battery pack is recommended because it provides consistent voltage and enough current to drive both motors reliably. However, a 9V block battery can work for initial testing but may drain quickly under motor load, causing inconsistent behavior.

How far should the TCS34725 sensor be from the ground?

The sensor should be approximately 10 to 15 mm above the track surface. In other words, too close and it may not distinguish colors well; too far and the readings become weak and noisy. The sensor holder included in the 3D-printed design is sized for this optimal range.

Can I use multiple TCS34725 sensors on this robot?

The TCS34725 has a fixed I2C address, so you cannot connect two sensors directly to the same bus without an I2C multiplexer (such as the TCA9548A). Accordingly, this project is designed for a single sensor, which is sufficient for PID-based line following on standard tracks.

What line width and color work best?

A 50 mm wide white adhesive tape on a dark matte surface works well. Above all, the key is strong contrast between the line and the background. Avoid glossy or reflective surfaces, as they can produce inconsistent sensor readings depending on the angle of ambient light.

How do I know if my PID values are correct?

If the robot follows the line smoothly without excessive oscillation or losing the line on curves, your PID values are well tuned. Additionally, use the Serial Monitor to observe the error values. If the error fluctuates rapidly and the robot zig-zags, reduce Kp. If it drifts off on curves, increase Kp. Add Ki only if there is consistent drift, and Kd only if oscillation persists after P tuning.

Can I modify this project to follow a colored line instead of a black/white track?

Yes. Since the TCS34725 provides red, green, blue, and clear channel data, you can modify the code to use specific color channels instead of the clear channel. For example, to follow a red line, you could use the red channel reading relative to the green and blue channels. However, this is an advanced modification that requires changes to the error calculation logic.

Resources and Downloads

  • GitHub Repository: Full Arduino code for this project is available on GitHub.
  • STL Files: Download the 3D-printable chassis, sensor holder, and Arduino holder from Cults3D or from our OmArTronics Shop.
  • Adafruit TCS34725 Library: Install via Arduino IDE Library Manager (search for “Adafruit TCS34725”).
  • AFMotor Library: Install via Arduino IDE Library Manager (search for “Adafruit Motor Shield”).

Related OmArTronics Tutorials

If you enjoyed this project, furthermore, explore these related tutorials to continue building your robotics skills:

Conclusion

In conclusion, you have now built a complete TCS34725 line-following robot with Arduino and PID control. Throughout this tutorial, you went through 3D design, printing, assembly, wiring, sensor calibration, PID theory, Arduino programming, testing, and tuning. Compared to a basic IR-based line follower, consequently, this robot demonstrates significantly smoother and more accurate line tracking thanks to the continuous analog readings from the TCS34725 sensor and the proportional corrections from the PID controller.

Moving forward, you can experiment with faster base speeds, tighter track curves, colored line detection using the RGB channels, or adding multiple sensors with an I2C multiplexer. You can also explore other OmArTronics robotics projects to continue expanding your skills in Arduino programming, mechatronics, and mobile robot design.

Download the 3D Print Files (STL)

All 3D-printable STL files for this project are available for download. You can get them from our shop or browse them on Cults3D:

1 thought on “Building a Line Following Robot with TCS34725 RGB Sensor”

Leave a Comment