Difference between revisions of "2021SummerTeam6"

From MAE/ECE 148 - Introduction to Autonomous Vehicles
Jump to navigation Jump to search
Line 38: Line 38:
= '''Final Project Overview''' =
= '''Final Project Overview''' =
      
      
= '''Our Python Code!''' =
==YoloV5 Object Detection Code ==
    # -*- coding: utf-8 -*-
<nowiki>
"""
import rospy
Created on Mon Mar 29 14:31:14 2021
import cv2
import numpy as np
from std_msgs.msg import Int32, Int32MultiArray
from sensor_msgs.msg import Image
from decoder import decodeImage
import time
from cv_bridge import CvBridge
from elements.yolo import OBJ_DETECTION


@author: Anwar
# Give names for nodes and topics for ROS
"""
STOPSIGN_NODE_NAME = 'stopsign_node'
## You need to install pyaudio to run this example
STOPSIGN_TOPIC_NAME = 'StopSign'
# pip install pyaudio
CAMERA_TOPIC_NAME = 'camera_rgb'


# When using a microphone, the AudioSource `input` parameter would be
# types of objects that can be detected
# initialised as a queue. The pyaudio stream would be continuosly adding
# recordings to the queue, and the websocket client would be sending the
# recordings to the speech to text service


import pyaudio
Object_classes = ['person', 'bicycle', 'car', 'motorcycle', 'airplane', 'bus', 'train', 'truck', 'boat', 'traffic light',                'fire hydrant', 'stop sign', 'parking meter', 'bench', 'bird', 'cat', 'dog', 'horse', 'sheep', 'cow',                'elephant', 'bear', 'zebra', 'giraffe', 'backpack', 'umbrella', 'handbag', 'tie', 'suitcase', 'frisbee',                'skis', 'snowboard', 'sports ball', 'kite', 'baseball bat', 'baseball glove', 'skateboard', 'surfboard',                'tennis racket', 'bottle', 'wine glass', 'cup', 'fork', 'knife', 'spoon', 'bowl', 'banana', 'apple',                'sandwich', 'orange', 'broccoli', 'carrot', 'hot dog', 'pizza', 'donut', 'cake', 'chair', 'couch',                'potted plant', 'bed', 'dining table', 'toilet', 'tv', 'laptop', 'mouse', 'remote', 'keyboard', 'cell phone',                'microwave', 'oven', 'toaster', 'sink', 'refrigerator', 'book', 'clock', 'vase', 'scissors', 'teddy bear',                'hair drier', 'toothbrush' ]
from ibm_watson import SpeechToTextV1
from ibm_watson.websocket import RecognizeCallback, AudioSource
from threading import Thread
from ibm_cloud_sdk_core.authenticators import IAMAuthenticator


try:
    from Queue import Queue, Full
except ImportError:
    from queue import Queue, Full


###############################################
Object_colors = list(np.random.rand(80,3)*255)
#### Initalize queue to store the recordings ##
Object_detector = OBJ_DETECTION('weights/yolov5s.pt', Object_classes)
###############################################
CHUNK = 1024
# Note: It will discard if the websocket client can't consumme fast enough
# So, increase the max size as per your choice
BUF_MAX_SIZE = CHUNK * 10
# Buffer to store audio
q = Queue(maxsize=int(round(BUF_MAX_SIZE / CHUNK)))


# Create an instance of AudioSource
audio_source = AudioSource(q, True, True)


###############################################
class StopSignDetection:
#### Prepare Speech to Text Service ########
        def __init__(self):
###############################################
            self.init_node = rospy.init_node(STOPSIGN_NODE_NAME, anonymous=False)                # initialize the node
            self.StopSign_publisher = rospy.Publisher(STOPSIGN_TOPIC_NAME,Int32, queue_size=1)    # make this node a publisher
            self.camera_subscriber = rospy.Subscriber(CAMERA_TOPIC_NAME,Image,self.detect_stop)  # subscribe to the camera feed
            self.bridge =CvBridge()
            self.stopsign = Int32()


# initialize speech to text service
        def detect_stop(self,data):
authenticator = IAMAuthenticator('your API key')
                frame = self.bridge.imgmsg_to_cv2(data)         # get frame from camera feed data
speech_to_text = SpeechToTextV1(authenticator=authenticator)


# define callback for the speech to text service
                        # detection process
class MyRecognizeCallback(RecognizeCallback):
                objs = Object_detector.detect(frame)             # detect the object
    def __init__(self):
        RecognizeCallback.__init__(self)


    def on_transcription(self, transcript):
                        # plotting
        print(transcript)
                for obj in objs:
                                # print(obj)
                                label = obj['label']
                                score = obj['score']
                                [(xmin,ymin),(xmax,ymax)] = obj['bbox']
                                color = Object_colors[Object_classes.index(label)]
                                frame = cv2.rectangle(frame, (xmin,ymin), (xmax,ymax), color, 2)
                                frame = cv2.putText(frame, f'{label} ({str(score)})', (xmin,ymin),
                cv2.FONT_HERSHEY_SIMPLEX , 0.75, color, 1, cv2.LINE_AA)
                                cv2.imshow('stopsign',frame)                    # create window to show objects detected
                                cv2.waitKey(1)
                          # if a stop sign is detected send out a 1 else send out 0


     def on_connected(self):
                                if label == 'stop sign' and  score > 0.1:
        print('Connection was successful')
                                          self.stopsign.data = 1
                                          self.StopSign_publisher.publish(self.stopsign)
                                else:
                                          self.stopsign.data = 0
                                          self.StopSign_publisher.publish(self.stopsign)
def main():
    StopSign_detector = StopSignDetection()
    rate = rospy.Rate(15)
     while not rospy.is_shutdown():
      rospy.spin()
      rate.sleep()


    def on_error(self, error):
if __name__=='__main__':
        print('Error received: {}'.format(error))
    main()


    def on_inactivity_timeout(self, error):
</nowiki>
        print('Inactivity timeout: {}'.format(error))
 
    def on_listening(self):
        print('Service is listening')
 
    def on_hypothesis(self, hypothesis):
        print(hypothesis)
 
    def on_data(self, data):
        print(data)
 
    def on_close(self):
        print("Connection closed")
 
# this function will initiate the recognize service and pass in the AudioSource
def recognize_using_weboscket(*args):
    mycallback = MyRecognizeCallback()
    speech_to_text.recognize_using_websocket(audio=audio_source,
                                            content_type='audio/l16; rate=44100',
                                            recognize_callback=mycallback,
                                            interim_results=True)
 
###############################################
#### Prepare the for recording using Pyaudio ##
###############################################
 
# Variables for recording the speech
FORMAT = pyaudio.paInt16
CHANNELS = 1
RATE = 44100
 
# define callback for pyaudio to store the recording in queue
def pyaudio_callback(in_data, frame_count, time_info, status):
    try:
        q.put(in_data)
    except Full:
        pass # discard
    return (None, pyaudio.paContinue)
 
# instantiate pyaudio
audio = pyaudio.PyAudio()
 
# open stream using callback
stream = audio.open(
    format=FORMAT,
    channels=CHANNELS,
    rate=RATE,
    input=True,
    frames_per_buffer=CHUNK,
    stream_callback=pyaudio_callback,
    start=False
)
 
#########################################################################
#### Start the recording and start service to recognize the stream ######
#########################################################################
 
print("Enter CTRL+C to end recording...")
stream.start_stream()
 
try:
    recognize_thread = Thread(target=recognize_using_weboscket, args=())
    recognize_thread.start()
 
    while True:
        pass
except KeyboardInterrupt:
    # stop recording
    stream.stop_stream()
    stream.close()
    audio.terminate()
    audio_source.completed_recording()

Revision as of 00:49, 6 September 2021

Team 6 Members

P1.jpg


From Left to Right

Kevin Bishara (MAE) | William Lynch (ECE) | Anwar Hsu (ECE)

Robot & 3D Modeling Designs

Our Robot

P2.png

Electronics Plate

Cad1.png

Camera Mount

Jetson Nano Case

Cad2.png Cad3.png

Autonomous Laps

    DonkeyCar Laps

Our autonomous laps for DonkeyCar can be found here.

    OpenCV/ROS Laps

Our OpenCV/ROS autonomous laps can be found here.

Final Project Overview

YoloV5 Object Detection Code

import rospy
import cv2
import numpy as np
from std_msgs.msg import Int32, Int32MultiArray
from sensor_msgs.msg import Image
from decoder import decodeImage
import time
from cv_bridge import CvBridge
from elements.yolo import OBJ_DETECTION

# Give names for nodes and topics for ROS
STOPSIGN_NODE_NAME = 'stopsign_node'
STOPSIGN_TOPIC_NAME = 'StopSign'
CAMERA_TOPIC_NAME = 'camera_rgb'

# types of objects that can be detected

Object_classes = ['person', 'bicycle', 'car', 'motorcycle', 'airplane', 'bus', 'train', 'truck', 'boat', 'traffic light',                'fire hydrant', 'stop sign', 'parking meter', 'bench', 'bird', 'cat', 'dog', 'horse', 'sheep', 'cow',                'elephant', 'bear', 'zebra', 'giraffe', 'backpack', 'umbrella', 'handbag', 'tie', 'suitcase', 'frisbee',                'skis', 'snowboard', 'sports ball', 'kite', 'baseball bat', 'baseball glove', 'skateboard', 'surfboard',                'tennis racket', 'bottle', 'wine glass', 'cup', 'fork', 'knife', 'spoon', 'bowl', 'banana', 'apple',                'sandwich', 'orange', 'broccoli', 'carrot', 'hot dog', 'pizza', 'donut', 'cake', 'chair', 'couch',                'potted plant', 'bed', 'dining table', 'toilet', 'tv', 'laptop', 'mouse', 'remote', 'keyboard', 'cell phone',                'microwave', 'oven', 'toaster', 'sink', 'refrigerator', 'book', 'clock', 'vase', 'scissors', 'teddy bear',                'hair drier', 'toothbrush' ] 


Object_colors = list(np.random.rand(80,3)*255)
Object_detector = OBJ_DETECTION('weights/yolov5s.pt', Object_classes)


class StopSignDetection:
        def __init__(self):
            self.init_node = rospy.init_node(STOPSIGN_NODE_NAME, anonymous=False)                 # initialize the node
            self.StopSign_publisher = rospy.Publisher(STOPSIGN_TOPIC_NAME,Int32, queue_size=1)    # make this node a publisher
            self.camera_subscriber = rospy.Subscriber(CAMERA_TOPIC_NAME,Image,self.detect_stop)   # subscribe to the camera feed
            self.bridge =CvBridge()
            self.stopsign = Int32()

        def detect_stop(self,data):
                frame = self.bridge.imgmsg_to_cv2(data)          # get frame from camera feed data

                        # detection process
                objs = Object_detector.detect(frame)             # detect the object 

                        # plotting
                for obj in objs:
                                # print(obj)
                                label = obj['label']
                                score = obj['score']
                                [(xmin,ymin),(xmax,ymax)] = obj['bbox']
                                color = Object_colors[Object_classes.index(label)]
                                frame = cv2.rectangle(frame, (xmin,ymin), (xmax,ymax), color, 2)
                                frame = cv2.putText(frame, f'{label} ({str(score)})', (xmin,ymin),
                 cv2.FONT_HERSHEY_SIMPLEX , 0.75, color, 1, cv2.LINE_AA)
                                cv2.imshow('stopsign',frame)                    # create window to show objects detected
                                cv2.waitKey(1)
				
                           # if a stop sign is detected send out a 1 else send out 0

                                if label == 'stop sign' and  score > 0.1:
                                           self.stopsign.data = 1
                                           self.StopSign_publisher.publish(self.stopsign)
                                else:
                                           self.stopsign.data = 0
                                           self.StopSign_publisher.publish(self.stopsign)
def main():
    StopSign_detector = StopSignDetection()
    rate = rospy.Rate(15)
    while not rospy.is_shutdown():
       rospy.spin()
       rate.sleep()

if __name__=='__main__':
    main()