J.A.C.W.I.B — Autonomous Car

Amod Sahasrabudhe
Towards Data Science
14 min readApr 26, 2020

--

Authors/Developers: Udit Gavasane, Rohan Tergaonkar, Amod Sahasrabudhe

Massive thanks to David Tian whose work on “Deep Pi Car” series inspired us to develop a similar model. You can refer to his article here.

Introduction

How relevant are Autonomous vehicles?

Autonomous vehicles are a thing of the future. Many technology giants such as Tesla, Google and automobile companies such as Uber,GM,BMW are investing in autonomous vehicles. It is believed that self driving cars would be a common sight on the roads in the near future. How about using economic tools and parts to build your very own self driving car that can detect lanes and follow them? Here is a nice and crisp image of our car which we have named J.A.C.W.I.B (Just Another Car With Intelligent Brain)

Hardware Components

  • Remote Controlled Car: We used a remote control car that made use of 3 DC motors(one for steering and two for throttling).
  • Raspberry Pi 3 model B+
  • 32 GB micro SD: used to deploy Raspbian OS and memory for Raspberry Pi.
  • RaspberryPi 5MP camera module: It supports 1080p @ 30 fps, 720p @ 60 fps, and 640x480p 60/90 recording.
  • Motor Driver(LM298N): used to control the directions and speeds of the DC motors. It supports the control of 2 dc motors in 1 board and can withstand 1.5 A.
  • Power Bank: Power Bank (rated at 5V, 2.1A) to power up the Raspberry Pi module.
  • Battery: 9V Li-ion USB rechargeable battery, 500mAh capacity. Used to power up the motor driver .
  • Male to male and female to female jumper wires.
  • Blue tape: This is a very important component of this project, it is used to make the two lane lines in which the car will drive between.
  • Zip ties
  • Screw driver

Raspberry Pi Setup

Raspberry Pi Operating System

The Raspberry Pi needs an operating system to run different types of programs on it. You can refer this excellent guide.

Setup Remote Access

It is advisable to set up remote access to your Raspberry Pi as you cannot connect it to an external display while the car is driving. To set up remote access you can refer this guide. You can also refer to this video guide.

Setup Remote File Access

Since our Raspberry Pi is running using remote access, it is also essential that we can transfer files to/from the Raspberry Pi easily. Refer to this guide.

After the Raspberry Pi setup is complete we can now move on to install the essential libraries.

Installing OpenCV

OpenCV (Open Source Computer Vision Library) is an advanced library that contains functions mainly aimed at real-time computer vision. The use of OpenCV will enable us to perceive what’s in front of us and help us identify lanes. Run the commands (in bold) in your Raspberry Pi terminal.

#Installing dependent librariespi@raspberrypi:~ $  sudo apt-get install libhdf5-dev -y && sudo apt-get install libhdf5-serial-dev -y && sudo apt-get install libatlas-base-dev -y && sudo apt-get install libjasper-dev -y && sudo apt-get install libqtgui4 -y && sudo apt-get install libqt4-test -y# install OpenCV
pi@raspberrypi:~ $ pip3 install opencv-python
Collecting opencv-python
[Omitted....]
Installing collected packages: numpy, opencv-python
Successfully installed numpy-1.16.2 opencv-python-3.4.4.19

Test you OpenCV installation by running the following code.

pi@raspberrypi:~ $ python3 -c "import cv2"

If you do not see any error while running the command, the library should be installed correctly.

Hardware Assembly

Raspberry Pi + Motor Driver assembly schematic

The image above shows the connection between Raspberry Pi, Raspberry Pi camera module and the LM298N motor driver. As we wished to control the throttling speed of the two motors, we connected them to the same port. These connections are done with the help of male-male and female-female jumper wires. The camera module is attached on the front grill of the car.

Raspberry Pi GPIO Pin Configuration

  • ENA — GPIO 25
  • IN1 — GPIO 23
  • IN2 — GPIO 24
  • IN3 — GPIO 17
  • IN4 — GPIO27
  • ENB — GPIO22

Testing the parts

After completing all the connections, we will test them to make sure that all connections are correct.

Testing the camera

Open a new python file on your Raspberry Pi and type in the following.

import cv2video = cv2.VideoCapture(0)while True:
ret,frame = video.read()
cv2.imshow('original',frame)
cv2.imwrite('original.jpg',frame)

key = cv2.waitKey(1) #wait for 1 ms for any keyboard button
if key == 27:
break
video.release()
cv2.destroyAllWindows()

The first line is to import our OpenCV library and to use its functions. The VideoCapture(0) function starts streaming a live video from the source. The parameter supplied is ‘0’ which means that we are using the default camera i.e. Raspberry Pi camera in this case. The video.read() will read each frame comes from the camera and save it in a variable called “frame”. The function imshow() will display our frames headed by the word “original” and the imwrite() function will store the “frame” as “original.jpg” on our storage device. If “esc” button is pressed, a decimal value of 27 is returned and it will break the loop accordingly.

Testing the motors

We need to test the motor to check the speed and to see the direction in which the motors are rotating. Run the following code on your Raspberry Pi to check the motor speed and direction.

import RPi.GPIO as GPIO          
from time import sleep

in1 = 24
in2 = 23
in3 = 17
in4 = 27
en1 = 25
en2 = 22
temp1=1

GPIO.setmode(GPIO.BCM)
GPIO.setup(in1,GPIO.OUT)
GPIO.setup(in2,GPIO.OUT)
GPIO.setup(in3,GPIO.OUT)
GPIO.setup(in4,GPIO.OUT)
GPIO.setup(en1,GPIO.OUT)
GPIO.setup(en2,GPIO.OUT)
GPIO.output(in1,GPIO.LOW)
GPIO.output(in2,GPIO.LOW)
GPIO.output(in3,GPIO.LOW)
GPIO.output(in4,GPIO.LOW)
p=GPIO.PWM(en1,1000)
q=GPIO.PWM(en2,1000)

p.start(75)
q.start(75)
print("\n")
print("The default speed & direction of motor is LOW & Forward.....")
print("r-run x-stop w-forward s-backward a-left d-right m-medium e-exit f-front")
print("\n")

while(1):

x=raw_input()

if x=='r':
print("run")
if(temp1==1):
GPIO.output(in1,GPIO.HIGH)
GPIO.output(in2,GPIO.LOW)
GPIO.output(in3,GPIO.HIGH)
GPIO.output(in4,GPIO.LOW)

print("forward")
x='z'
else
:
GPIO.output(in1,GPIO.LOW)
GPIO.output(in2,GPIO.HIGH)
GPIO.output(in3,GPIO.LOW)
GPIO.output(in4,GPIO.HIGH)

print("backward")
x='z'


elif
x=='x':
print("stop")
GPIO.output(in1,GPIO.LOW)
GPIO.output(in2,GPIO.LOW)
GPIO.output(in3,GPIO.LOW)
GPIO.output(in4,GPIO.LOW)

x='z'

elif
x=='w':
print("forward")
GPIO.output(in1,GPIO.HIGH)
GPIO.output(in2,GPIO.LOW)
temp1=1
x='z'

elif
x=='s':
print("backward")
GPIO.output(in1,GPIO.LOW)
GPIO.output(in2,GPIO.HIGH)
temp1=0
x='z'

elif
x=='d':
print("right")
GPIO.output(in3,GPIO.LOW)
GPIO.output(in4,GPIO.HIGH)
temp1=1
x='z'

elif
x=='a':
print("left")
GPIO.output(in3,GPIO.HIGH)
GPIO.output(in4,GPIO.LOW)
temp1=0
x='z'

elif
x=='f':
print("front")
GPIO.output(in3,GPIO.LOW)
GPIO.output(in4,GPIO.LOW)
temp1=0
x='z'

elif
x==' ':
print("brake")
GPIO.output(in1,GPIO.LOW)
GPIO.output(in2,GPIO.LOW)
x='z'

elif
x=='m':
print("medium")
p.ChangeDutyCycle(50)
q.ChangeDutyCycle(50)
x='z'

elif
x=='e':
GPIO.cleanup()
print("GPIO Clean up")
break

else
:
print("<<< wrong data >>>")
print("please enter the defined data to continue.....")

Enable pins take a Pulse Width Modulation (PWM) input signal from the Raspberry Pi and run the motors accordingly. For example, a 100% PWM signal means we are working on the maximum speed and 0% PWM signal means the motor is not rotating. You can adjust that using ChangeDutyCycle() function. If in case your motors function in the opposite direction, then just reverse the polarity. If the motors do not function at all then test your hardware connection again. Refer this documentation for understanding more about Raspberry Pi GPIO pin configuration.

We are done with the testing. Now it’s time to start the actual programming!

Lane Navigation

The lane detection algorithm developed by David Tian is used and we will explain it here in modules.

Convert to HSV Space

We turn the color space used by the image, which is RGB (Red/Green/Blue) into the HSV (Hue/Saturation/Value) color space. The main advantage of doing so is to differentiate between colors by their level of brightness.

Detect Blue Color and Edges

The reason for using blue colored lanes was that it was not found commonly in the place we built our car. To extract blue color from a HSV frame, a range of hue, saturation and value should be mentioned. To reduce the overall distortion in each frame, edges are detected using Canny Edge Detector. You can refer more on Canny here.

def detect_edges(frame):
# filter for blue lane lines
hsv = cv2.cvtColor(frame, cv2.COLOR_BGR2HSV)
lower_blue = np.array([90, 120, 0], dtype="uint8")
upper_blue = np.array([150, 255, 255], dtype="uint8")
mask = cv2.inRange(hsv, lower_blue, upper_blue)
# detect edges
edges = cv2.Canny(mask, 50, 100)
return edges

Select Region of Interest

We can observe that there will be other blue colors present in our frame as well. We need to isolate only the lanes as that is the part which we wish to focus on.

def region_of_interest(edges):
height, width = edges.shape
mask = np.zeros_like(edges)
# only focus lower half of the screen
polygon = np.array([[
(0, height),
(0, height / 2),
(width, height / 2),
(width, height),
]], np.int32)
cv2.fillPoly(mask, polygon, 255) cropped_edges = cv2.bitwise_and(edges, mask)
cv2.imshow("roi", cropped_edges)
return cropped_edges
Isolating Region of Interest

Detect Line Segments

Hough transform is used to detect any shape in a frame if we represent it in mathematical form. In our case, we need to detect the lines. It can also work on slightly distorted shapes as well. You can refer more about Hough Transform here.

def detect_line_segments(cropped_edges):
rho = 1
theta = np.pi / 180
min_threshold = 10
line_segments = cv2.HoughLinesP(cropped_edges, rho, theta, min_threshold,np.array([]), minLineLength=5, maxLineGap=150) return line_segments

The HoughLinesP() function takes the following parameters :

  • Frame: is the frame we want to detect lines in. In our case, it is cropped_edges
  • rho: is the distance precision in pixel.
  • theta: angular precision in radians ( always = π/180 ~ 1 degree)
  • min_threshold is the number of votes needed to be considered a line segment. If a line has more votes, Hough Transform considers them to be more likely to have detected a line segment.
  • maxLineGap: maximum gap in pixels between 2 lines to be treated as 1 line.

Calculate Steering Angle

We know that the equation of line is y=mx+b, where m is the slope of the line and b is the y-intercept. The average of slopes and intercepts of line segments detected using Hough transform will be calculated. The left lane line has x₁ < x₂ and y₂ < y₁ and the slope, m= (y₂ — y₁) / (x₂ — x₁) which will give a negative slope. The right lane is the complete opposite. The right lane has x > x and y > y which will give a positive slope. In the case of vertical lines (x = x), the slope will be infinity. In this case, we will skip all vertical lines to prevent an error. To accurately detect the lanes, the frame is divided into two regions, right and left through boundary lines.

def average_slope_intercept(frame, line_segments):
lane_lines = []
if line_segments is None:
print("no line segments detected")
return lane_lines
height, width, _ = frame.shape
left_fit = []
right_fit = []
boundary = 1 / 3
left_region_boundary = width * (1 - boundary)
right_region_boundary = width * boundary
for line_segment in line_segments:
for x1, y1, x2, y2 in line_segment:
if x1 == x2:
print("skipping vertical lines")
continue
fit = np.polyfit((x1, x2), (y1, y2), 1)
slope = (y2 - y1) / (x2 - x1)
intercept = y1 - (slope * x1)
if slope < 0:
if x1 < left_region_boundary and x2 < left_region_boundary:
left_fit.append((slope, intercept))
else:
if x1 > right_region_boundary and x2 > right_region_boundary:
right_fit.append((slope, intercept))
left_fit_average = np.average(left_fit, axis=0)
if len(left_fit) > 0:
lane_lines.append(make_points(frame, left_fit_average))
right_fit_average = np.average(right_fit, axis=0)
if len(right_fit) > 0:
lane_lines.append(make_points(frame, right_fit_average))
return lane_lines

make_points() is a helper function for average_slope_intercept() function which will return the bounded coordinates of the lane lines.

def make_points(frame, line):
height, width, _ = frame.shape
slope, intercept = line y1 = height # bottom of the frame
y2 = int(y1 / 2) # make points from middle of the frame down
if slope == 0:
slope = 0.1
x1 = int((y1 - intercept) / slope)
x2 = int((y2 - intercept) / slope)
return [[x1, y1, x2, y2]]

To display the lane lines on the frame, the following function is used

def display_lines(frame, lines, line_color=(0, 255, 0), line_width=6):
line_image = np.zeros_like(frame)
if lines is not None:
for line in lines:
for x1, y1, x2, y2 in line:
cv2.line(line_image, (x1, y1), (x2, y2), line_color, line_width)
line_image = cv2.addWeighted(frame, 0.8, line_image, 1, 1) return line_image

Now, comes in the most important step of calculating the steering angle before applying speed to our motors. We need to make sure that the car stays exactly in the middle of the detected lane lines. We may come across two scenarios :

  • Two detected Lane Lines
  • Single detected Lane Line

Calculating the heading line is the use of trigonometric functions tan and atan( i.e. tan⁻¹).

def get_steering_angle(frame, lane_lines):
height, width, _ = frame.shape
if len(lane_lines) == 2:
_, _, left_x2, _ = lane_lines[0][0]
_, _, right_x2, _ = lane_lines[1][0]
mid = int(width / 2)
x_offset = (left_x2 + right_x2) / 2 - mid
y_offset = int(height / 2)
elif len(lane_lines) == 1:
x1, _, x2, _ = lane_lines[0][0]
x_offset = x2 - x1
y_offset = int(height / 2)
elif len(lane_lines) == 0:
x_offset = 0
y_offset = int(height / 2)
angle_to_mid_radian = math.atan(x_offset / y_offset)
angle_to_mid_deg = int(angle_to_mid_radian * 180.0 / math.pi)
steering_angle = angle_to_mid_deg + 90
#print(steering_angle)
return steering_angle

The heading line is displayed using the following.

def display_heading_line(frame, steering_angle, line_color=(0, 0, 255), line_width=5):
heading_image = np.zeros_like(frame)
height, width, _ = frame.shape
steering_angle_radian = steering_angle / 180.0 * math.pi x1 = int(width / 2)
y1 = height
x2 = int(x1 - height / 2 / math.tan(steering_angle_radian))
y2 = int(height / 2)
cv2.line(heading_image, (x1, y1), (x2, y2), line_color, line_width)
heading_image = cv2.addWeighted(frame, 0.8, heading_image, 1, 1)
return heading_image

Transferring the Steering Angle using Socket

Now that we have calculated the steering angle we need to make use of this angle to steer our car. Technically, you can run the lane detection algorithm on the Raspberry Pi itself. However, the above processing might be too heavy for the Raspberry Pi and may result in a lag. This may produce inaccurate results. To solve this problem, we use our laptop/PC’s processing power and make use of sockets. So, the input camera stream(captured using Raspberry Pi camera module) arrives from a socket to the laptop/PC where it performs the above mentioned lane detection and calculation of the steering angle. The following code displays the socket program usage and also how the lane detection modules are called.

ser_soc = socket.socket()
ser_soc.bind(('192.168.2.11', 5500))
ser_soc.listen(2)
conn, address = ser_soc.accept()
class VideoStreamingTest(object):
def __init__(self, host, port):
self.server_socket = socket.socket()
self.server_socket.bind((host, port))
self.server_socket.listen(1)
self.connection, self.client_address = self.server_socket.accept()
self.connection = self.connection.makefile('rb')
self.host_name = socket.gethostname()
self.host_ip = socket.gethostbyname(self.host_name)
self.streaming()
def streaming(self): try:
print("Host: ", self.host_name + ' ' + self.host_ip)
print("Connection from: ", self.client_address)
print("Streaming...")
print("Press 'q' to exit")
# need bytes here
stream_bytes = b' '
while True
:
stream_bytes += self.connection.read(1024)
first = stream_bytes.find(b'\xff\xd8')
last = stream_bytes.find(b'\xff\xd9')
if first != -1 and last != -1:
jpg = stream_bytes[first:last + 2]
stream_bytes = stream_bytes[last + 2:]
frame = cv2.imdecode(np.frombuffer(jpg, dtype=np.uint8), cv2.IMREAD_COLOR)
edges = detect_edges(frame)
roi = region_of_interest(edges)
line_segments = detect_line_segments(roi)
lane_lines = average_slope_intercept(frame, line_segments)
lane_lines_image = display_lines(frame, lane_lines)
steering_angle = get_steering_angle(frame, lane_lines) #pass value through socket
print(steering_angle)
server_program(steering_angle)
heading_image = display_heading_line(lane_lines_image, steering_angle)
cv2.imshow("heading line", heading_image)
if cv2.waitKey(1) & 0xFF == ord('q'):
break
finally:
self.connection.close()
self.server_socket.close()
if __name__ == '__main__':
# host, port
h, p = "192.168.2.11", 8000
VideoStreamingTest(h, p)

The sending socket program is mentioned as follows :

def server_program(data):
data = str(data)
conn.send(data.encode()) # send data to the Raspberry Pi

You can learn more about socket programming here.

NOTE: Your Raspberry Pi and laptop needs to be connected to the same network for transferring the data.

Driving the Car

We now need to send the video stream captured by the Pi Camera to our host machine. For that, we will write the following code.

import io
import socket
import struct
import time
import picamera

# create socket and bind host
client_socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
client_socket.connect(('192.168.2.11', 8000))
connection = client_socket.makefile('wb')

try:
with picamera.PiCamera() as camera:
camera.resolution = (320, 240) # pi camera resolution
camera.framerate = 15 # 15 frames/sec
time.sleep(2) # give 2 secs for camera to initilize
start = time.time()
stream = io.BytesIO()

# send jpeg format video stream
for foo in camera.capture_continuous(stream, 'jpeg', use_video_port = True):
connection.write(struct.pack('<L', stream.tell()))
connection.flush()
stream.seek(0)
connection.write(stream.read())
if time.time() - start > 600:
break
stream.seek(0)
stream.truncate()

connection.write(struct.pack('<L', 0))




finally:
connection.close()
client_socket.close()

Now, once the steering angle is calculated from our initial program, we need to receive it to perform some action. So, we will write the following code

import socket
import math
import sys
import time
import RPi.GPIO as GPIO


def client_program():

cli_soc = socket.socket() # instantiate
cli_soc.connect(('192.168.2.11', 5500))


while True:

data = cli_soc.recv(1024).decode() # receive response

print('Received from server: ' + data) # show in terminal

steering_angle = int(data)

speed = 20
lastTime = 0
lastError = 0

now = time.time()
dt = now - lastTime

kp = 0.4
kd = kp * 0.65


deviation = steering_angle - 90
error = abs(deviation)

if deviation < 10 and deviation > -10:
deviation = 0
error = 0
GPIO.output(in1,GPIO.LOW)
GPIO.output(in2,GPIO.LOW)
steering.stop()

elif deviation > 10:
GPIO.output(in1,GPIO.LOW)
GPIO.output(in2,GPIO.HIGH)
steering.start(100)


elif deviation < -10:
GPIO.output(in1,GPIO.HIGH)
GPIO.output(in2,GPIO.LOW)
steering.start(100)

derivative = kd * (error - lastError) / dt
proportional = kp * error
PD = int(speed + derivative + proportional)
spd = abs(PD)
print(spd)

if spd > 35:
spd = 35


throttle.start(spd)

lastError = error
lastTime = time.time()


cli_soc.close() # close the connection



if __name__ == '__main__':
GPIO.setwarnings(False)

#throttle
throttlePin = 25 # Physical pin 22
in3 = 24 # physical Pin 16
in4 = 23 # physical Pin 18

#Steering of front wheels
steeringPin = 22 # Physical Pin 15
in1 = 17 # Physical Pin 11
in2 = 27 # Physical Pin 13


GPIO.setmode(GPIO.BCM)
GPIO.setup(in1,GPIO.OUT)
GPIO.setup(in2,GPIO.OUT)
GPIO.setup(in3,GPIO.OUT)
GPIO.setup(in4,GPIO.OUT)

GPIO.setup(throttlePin,GPIO.OUT)
GPIO.setup(steeringPin,GPIO.OUT)

# Steering
# in1 = 1 and in2 = 0 -> Left
GPIO.output(in1,GPIO.LOW)
GPIO.output(in2,GPIO.LOW)
steering = GPIO.PWM(steeringPin,1000)
steering.stop()

# Throttle
# in3 = 1 and in4 = 0 -> Forward
GPIO.output(in3,GPIO.HIGH)
GPIO.output(in4,GPIO.LOW)
throttle = GPIO.PWM(throttlePin,1000)
throttle.stop()

client_program()

GPIO.output(in1,GPIO.LOW)
GPIO.output(in2,GPIO.LOW)
GPIO.output(in3,GPIO.LOW)
GPIO.output(in4,GPIO.LOW)
throttle.stop()
steering.stop()

Here, as we are using a DC motor for turning mechanism we calculated the deviation.

Steps for Execution

Check out our GitHub page to download the project and refer the steps of execution.

How to drive

  1. Connection: Connect Raspberry Pi to Host Computer using Remote Desktop Connection to control the Raspberry Pi via Host Computer.
  2. Testing: Execute the test_drive.py program on Raspberry Pi terminal to check the throttle and direction of the car.
  3. Initialise Server: On the host computer, execute computer_server.py.
  4. Initialise Client: On the Raspberry Pi simultaneously execute 2 client programs i.e. raspi_client_1.py and raspi_client_2.py respectively. At this point, the host computer will start calculating steering angle based on the video stream received by raspi_client_2.py from the Raspberry Pi and will send them back through socket which will be received by raspi_client_1.py client.
  5. Self-Driving in Action: Based on the steering angle, the program raspi_client_1.py will give instructions to the GPIO pins of the Raspberry Pi for running the motors (motors are used to drive the wheels of the car). Thus the car will start driving autonomously in the designated lanes.
  6. Self-Driving in Action: Based on the steering angle, the program raspi_client_1.py will give instructions to the GPIO pins of the Raspberry Pi for running the motors (motors are used to drive the wheels of the car). Thus the car will start driving autonomously in the designated lanes.

Result

Check out our YouTube video to see the self driving car in action!

Future Work

At the time of writing this article, we are under lock-down because of COVID-19 pandemic. Once the lock-down is ceased, our next step is to install an ultrasonic sensor on the car. Here, we can calculate the distance between the car and obstacles. Based on this we can tune our car to function in a certain way when an obstacle is detected.

Thank you so much for reading our article completely! This happens to be the first time we are writing an article on a project that we have developed, so the experience was quite exciting. We hope that you like it and try to build something similar of your own. If you have any queries regarding the same, drop a question and we will try our best to answer your problem.

Again, thanks a lot!

--

--

Interested in Artificial Intelligence, Computer Vision, Machine Learning.