Varun SanthoshRyan ChuangMichael DuganSyed Saqib Habeeb
Published © GPL3+

GSA Owls

An autonomous RC car that uses a Raspberry Pi 5, computer vision, and encoder-based feedback to perform smooth lane keeping.

AdvancedShowcase (no instructions)165
GSA Owls

Things used in this project

Hardware components

Raspberry Pi 5
Raspberry Pi 5
×1
Webcam, Logitech® HD Pro
Webcam, Logitech® HD Pro
×1
52Pi Ultra Thin ICE Tower Cooler for Raspberry Pi 5
×1
RC car
×1
speed encoder
×1
RGB Backlight LCD - 16x2
Adafruit RGB Backlight LCD - 16x2
×1

Story

Read more

Code

Python code

Python
Our primary control logic is implemented in lt25.py and includes:

Lane detection

Stop sign handling

PD steering control

Encoder-based speed feedback
import cv2
import numpy as np
import RPi.GPIO as GPIO
import time
import os
import csv
from collections import deque

# === GPIO SETUP ===
SPEED_PIN = 18
STEERING_PIN = 19
GPIO.setmode(GPIO.BCM)
GPIO.setup(SPEED_PIN, GPIO.OUT)
GPIO.setup(STEERING_PIN, GPIO.OUT)
speed_pwm = GPIO.PWM(SPEED_PIN, 50)
steering_pwm = GPIO.PWM(STEERING_PIN, 50)
speed_pwm.start(7.5)
steering_pwm.start(7.5)

# === CONTROL PARAMETERS ===
Kp = 0.020
Kd = 0.010
last_error = 0
base_pwm = 7.5
MIN_DRIVE_PWM = 8.02
MAX_DRIVE_PWM = 8.08

# === ENCODER CONFIG ===
PPR = 20
WHEEL_RADIUS_CM = 1.19
ENCODER_PATH = "/sys/bus/platform/devices/encoder@0/speed"

def read_speed_ns():
    try:
        with open(ENCODER_PATH, "r") as f:
            val = f.read().strip()
            return int(val) if val.isdigit() else 0
    except Exception as e:
        print("Encoder read error:", e)
        return 0

def calculate_cm_per_sec(interval_ns, ppr=PPR, radius_cm=WHEEL_RADIUS_CM):
    if interval_ns <= 0:
        return 0.0
    cm_per_rev = 2 * 3.1416 * radius_cm
    pulses_per_sec = 1e9 / interval_ns
    revs_per_sec = pulses_per_sec / ppr
    return revs_per_sec * cm_per_rev

# === CAMERA SETUP ===
cap = cv2.VideoCapture(0, cv2.CAP_V4L2)
cap.set(cv2.CAP_PROP_FRAME_WIDTH, 640)
cap.set(cv2.CAP_PROP_FRAME_HEIGHT, 480)

if not cap.isOpened():
    print("Camera could not be opened.")
    exit()

print("Centering steering...")
steering_pwm.ChangeDutyCycle(7.5)
time.sleep(1.0)

print("Camera preview active. Press SPACE to start, or Q to quit.")
while True:
    ret, frame = cap.read()
    if not ret:
        print("Camera error.")
        break

    cv2.imshow("Camera Preview", frame)
    key = cv2.waitKey(1)
    if key != -1 and key & 0xFF == ord(' '):
        print("Starting lane tracking...")
        break
    elif key != -1 and key & 0xFF == ord('q'):
        print("Quitting before start.")
        cap.release()
        cv2.destroyAllWindows()
        GPIO.cleanup()
        exit()

# === Stop Sign Detection State ===
stop_counter = 0
stop_detected = False
stop_frames_between = 3
frame_count = 0
last_stop_time = 0
stop_cooldown = 15.0

# === Speed Control Timing ===
speed_control_interval = 10  # apply control every N frames
speed_history = deque(maxlen=5)

# === CSV Logging ===
log_file = open("run_log.csv", mode="w", newline="")
csv_writer = csv.writer(log_file)
csv_writer.writerow(["Frame", "Lane Error", "Speed Error", "Encoder Speed", "Steering PWM", "Speed PWM", "P Value", "D Value"])


def is_in_stop_cooldown():
    return (time.time() - last_stop_time) < stop_cooldown

# === MAIN LOOP ===
try:
    while True:
        ret, frame = cap.read()
        if not ret:
            print("Camera read failed.")
            break

        height, width = frame.shape[:2]
        roi = frame[int(height * 0.5):, :]  # Bottom half
        hsv = cv2.cvtColor(roi, cv2.COLOR_BGR2HSV)

        # === BLUE MASK FOR LANE ===
        lower_blue = np.array([100, 50, 50])
        upper_blue = np.array([130, 255, 255])
        blue_mask = cv2.inRange(hsv, lower_blue, upper_blue)
        M = cv2.moments(blue_mask)

        # === RED MASK FOR STOP SIGN ===
        lower_red1 = np.array([0, 100, 100])
        upper_red1 = np.array([10, 255, 255])
        lower_red2 = np.array([160, 100, 100])
        upper_red2 = np.array([180, 255, 255])
        red_mask1 = cv2.inRange(hsv, lower_red1, upper_red1)
        red_mask2 = cv2.inRange(hsv, lower_red2, upper_red2)
        red_mask = cv2.bitwise_or(red_mask1, red_mask2)

        current_time = time.time()
        if (
            frame_count % stop_frames_between == 0 and
            not stop_detected and
            not is_in_stop_cooldown()
        ):
            red_area = cv2.countNonZero(red_mask)
            if red_area > 500:
                stop_counter += 1
                stop_detected = True
                last_stop_time = current_time
                print(f"STOP SIGN #{stop_counter} DETECTED!")
                speed_pwm.ChangeDutyCycle(7.5)  # Stop
                time.sleep(3 if stop_counter == 1 else 9999)
                if stop_counter == 1:
                    print("Resuming after stop...")
                    speed_pwm.ChangeDutyCycle(MIN_DRIVE_PWM)
                else:
                    print("Final stop reached. Exiting.")
                    break
        else:
            stop_detected = False

        # === LANE CENTERING ===
        lane_error = 0
        steer_pwm = 7.5
        p_term = 0
        d_term = 0
        if M["m00"] > 0:
            cx = int(M["m10"] / M["m00"])
            lane_error = cx - (width // 2)
            d_error = lane_error - last_error
            p_term = Kp * lane_error
            d_term = Kd * d_error
            steer_pwm = base_pwm + p_term + d_term
            steer_pwm = max(6.4, min(8.6, steer_pwm))
            steering_pwm.ChangeDutyCycle(steer_pwm)
            last_error = lane_error

        # === SPEED MONITORING ===
        interval_ns = read_speed_ns()
        current_speed = calculate_cm_per_sec(interval_ns)
        speed_history.append(current_speed)
        avg_speed = sum(speed_history) / len(speed_history) if speed_history else 0.0

        # === SPEED CONTROL ===
        speed_error = 0.0
        drive_pwm = MIN_DRIVE_PWM
        if frame_count % speed_control_interval == 0:
            target_speed = 7.0
            speed_error = target_speed - current_speed
            drive_pwm = MIN_DRIVE_PWM + 0.03 * speed_error
            drive_pwm = max(MIN_DRIVE_PWM, min(MAX_DRIVE_PWM, drive_pwm))
            speed_pwm.ChangeDutyCycle(drive_pwm)

        print(f"Lane error: {lane_error:.2f} | Steer PWM: {steer_pwm:.2f} | Speed: {current_speed:.2f} cm/s")
        csv_writer.writerow([frame_count, lane_error, speed_error, current_speed, steer_pwm, drive_pwm, p_term, d_term])

        frame_count += 1

        cv2.imshow("Lane Tracking", frame)
        key = cv2.waitKey(1)
        if key != -1 and key & 0xFF == ord('q'):
            print("User stopped.")
            break

finally:
    print("Cleanup...")
    try:
        speed_pwm.ChangeDutyCycle(7.5)
        steering_pwm.ChangeDutyCycle(7.5)
        time.sleep(1)
        speed_pwm.stop()
        steering_pwm.stop()
        log_file.close()
    except Exception as e:
        print("PWM stop error:", e)
    finally:
        GPIO.cleanup()
        cap.release()
        cv2.destroyAllWindows()

speed controller

C/C++
#include <linux/kernel.h>         
#include <linux/init.h>        
#include <linux/platform_device.h> 
#include <linux/of.h>            
#include <linux/of_device.h>     
#include <linux/gpio/consumer.h>  
#include <linux/interrupt.h>      
#include <linux/ktime.h>         
#include <linux/fs.h>           
#include <linux/device.h>         

MODULE_LICENSE("GPL");
MODULE_AUTHOR("Student");
MODULE_DESCRIPTION("Optical Encoder Driver using GPIOD for speed measurement");

#define DEVICE_NAME "proj3,encoder-driver" // Device tree compatible string

static struct gpio_desc *encoder_gpio; // Descriptor for encoder GPIO pin
static unsigned int encoder_irq;       // IRQ number assigned to encoder GPIO

static ktime_t last_activation_time;   // Last timestamp when encoder edge occurred
static u64 last_interval_ns = 0;       // Time interval between encoder edges in nanoseconds

// Show function for sysfs file: returns last time interval in nanoseconds
static ssize_t speed_show(struct device *dev,
                          struct device_attribute *attr, char *buf)
{
    return sprintf(buf, "%llu\n", last_interval_ns);
}
static DEVICE_ATTR_RO(speed); // Read-only sysfs attribute named 'speed'

// Interrupt Service Routine for encoder edge detection
static irqreturn_t encoder_isr(int irq, void *dev_id)
{
    ktime_t now = ktime_get(); // Get current time

    // Skip first activation if not yet initialized
    if (ktime_to_ns(last_activation_time) != 0) {
        ktime_t diff = ktime_sub(now, last_activation_time); // Time since last edge
        u64 diff_ns = ktime_to_ns(diff);

        if (diff_ns > 1000000) // Debounce: ignore pulses faster than 1ms
            last_interval_ns = diff_ns; // Store interval for sysfs access
    }

    last_activation_time = now; // Update timestamp for next edge
    return IRQ_HANDLED;
}

// Probe function: runs when device is found
static int encoder_probe(struct platform_device *pdev)
{
    int ret;

    // Request GPIO descriptor from device tree
    encoder_gpio = devm_gpiod_get(&pdev->dev, NULL, GPIOD_IN);
    if (IS_ERR(encoder_gpio)) {
        dev_err(&pdev->dev, "Failed to get encoder GPIO\n");
        return PTR_ERR(encoder_gpio);
    }

    // Convert GPIO to IRQ number
    encoder_irq = gpiod_to_irq(encoder_gpio);
    if (encoder_irq < 0) {
        dev_err(&pdev->dev, "Failed to map GPIO to IRQ\n");
        return encoder_irq;
    }

    // Register ISR for both rising and falling edges
    ret = request_irq(encoder_irq, encoder_isr,
                      IRQF_TRIGGER_RISING | IRQF_TRIGGER_FALLING,
                      "encoder_irq", NULL);
    if (ret) {
        dev_err(&pdev->dev, "Failed to request IRQ\n");
        return ret;
    }

    // Create sysfs entry to expose speed value to user space
    ret = device_create_file(&pdev->dev, &dev_attr_speed);
    if (ret < 0) {
        dev_err(&pdev->dev, "Failed to create sysfs entry\n");
        return ret;
    }

    dev_info(&pdev->dev, "Encoder driver initialized\n");
    return 0;
}

// Remove function: called when device is removed
static void encoder_remove(struct platform_device *pdev)
{
    free_irq(encoder_irq, NULL); // Free the IRQ
    device_remove_file(&pdev->dev, &dev_attr_speed); // Remove sysfs file
    dev_info(&pdev->dev, "Encoder driver removed\n");
}

// Device tree match table
static const struct of_device_id encoder_of_match[] = {
    { .compatible = DEVICE_NAME },
    { }
};
MODULE_DEVICE_TABLE(of, encoder_of_match);

// Register the platform driver
static struct platform_driver encoder_driver = {
    .probe = encoder_probe,
    .remove = encoder_remove,
    .driver = {
        .name = "encoder_driver",
        .of_match_table = encoder_of_match,
    },
};

// Macro to register the platform driver at load time
module_platform_driver(encoder_driver);

Objection Recognition

C/C++
import torch
import time
import cv2

# Load YOLOv5 model
model = torch.hub.load(
    repo_or_dir = '/home/pi/laneTracking/yolov5',
    model = 'yolov5s',
    source ='local',
    force_reload =True
)
model.conf = 0.5  # Confidence threshold
model.iou = 0.45  # IOU threshold
model.classes = None  # Detect all classes
model.to('cpu')  # Ensure CPU only

# Open USB webcam
cap = cv2.VideoCapture(0)
cap.set(cv2.CAP_PROP_FRAME_WIDTH, 320)
cap.set(cv2.CAP_PROP_FRAME_HEIGHT, 320)


print("Starting camera... Press 'q' to quit.")

frame_count = 0
start_time = time.time()

while cap.isOpened():
    ret, frame = cap.read()
    if not ret:
        break

    # Run detection
    results = model(frame, size=320)
    annotated_frame = results.render()[0]

    # Show frame
    cv2.imshow("YOLOv5 Webcam", annotated_frame)
    frame_count += 1

    # Break on key
    if cv2.waitKey(1) & 0xFF == ord('q'):
        break

# Compute FPS
end_time = time.time()
fps = frame_count / (end_time - start_time)
print(f"Average FPS: {fps:.2f}")

cap.release()
cv2.destroyAllWindows()

device tree source file

C/C++
/dts-v1/;
/plugin/;

/ {
    compatible = "brcm,bcm2711"; // Target platform: Raspberry Pi 4 SoC (BCM2711)

    // First fragment configures GPIO16 as an input with no pull resistor
    fragment@0 {
        target = <&gpio>; // Target the main GPIO controller node
        __overlay__ {
            encoder_pins: encoder_pins {
                brcm,pins = <16>;       // Use GPIO pin 16
                brcm,function = <0>;    // Set as input
                brcm,pull = <0>;        // No pull-up or pull-down resistor
            };
        };
    };

    // Second fragment defines a new device node for the encoder driver
    fragment@1 {
        target-path = "/"; // Apply overlay at the root of the device tree
        __overlay__ {
            encoder: encoder@0 {
                compatible = "proj3,encoder-driver"; // Matches driver "DEVICE_NAME"
                gpios = <&gpio 16 0>;                // Use GPIO16, active-low
            };
        };
    };
};

Makefile

C/C++
# Modified from:
# Dr. Derek Molloy, School of Electronic Engineering, Dublin City University,
# Ireland. URL: http://derekmolloy.ie/writing-a-linux-kernel-module-part-1-introduction/
PWD=$(shell pwd)
KERNEL_BUILD=/lib/modules/$(shell uname -r)/build

obj-m+=encoder_driver.o

all:
	make -C /lib/modules/$(shell uname -r)/build/ M=$(PWD) modules
clean:
	make -C /lib/modules/$(shell uname -r)/build/ M=$(PWD) clean

Credits

Varun Santhosh
1 project • 0 followers
Ryan Chuang
1 project • 0 followers
Michael Dugan
1 project • 0 followers
Syed Saqib Habeeb
1 project • 0 followers

Comments