diff --git a/physical_bringup/launch/modules/driving_cnn1.launch b/physical_bringup/launch/modules/driving_cnn1.launch index b81fce09..744f0291 100644 --- a/physical_bringup/launch/modules/driving_cnn1.launch +++ b/physical_bringup/launch/modules/driving_cnn1.launch @@ -4,7 +4,7 @@ - + diff --git a/physical_bringup/launch/modules/driving_cnn2a.launch b/physical_bringup/launch/modules/driving_cnn2a.launch index 0d68273e..1c18fdbb 100644 --- a/physical_bringup/launch/modules/driving_cnn2a.launch +++ b/physical_bringup/launch/modules/driving_cnn2a.launch @@ -4,7 +4,7 @@ - + diff --git a/physical_bringup/launch/modules/signal_panel_recognition.launch b/physical_bringup/launch/modules/signal_panel_recognition.launch index e7195813..0221c937 100644 --- a/physical_bringup/launch/modules/signal_panel_recognition.launch +++ b/physical_bringup/launch/modules/signal_panel_recognition.launch @@ -1,16 +1,10 @@ - - - - - - \ No newline at end of file diff --git a/physical_bringup/launch/signal_usbcam.launch b/physical_bringup/launch/signal_usbcam.launch new file mode 100644 index 00000000..05f2829e --- /dev/null +++ b/physical_bringup/launch/signal_usbcam.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/physical_bringup/launch/traxxas_drive1.launch b/physical_bringup/launch/traxxas_drive1.launch index c3ed09b0..178c7662 100644 --- a/physical_bringup/launch/traxxas_drive1.launch +++ b/physical_bringup/launch/traxxas_drive1.launch @@ -1,14 +1,11 @@ - - - @@ -18,7 +15,6 @@ - diff --git a/physical_bringup/launch/traxxas_drive2a.launch b/physical_bringup/launch/traxxas_drive2a.launch index 5a0e2f35..8fd4622e 100644 --- a/physical_bringup/launch/traxxas_drive2a.launch +++ b/physical_bringup/launch/traxxas_drive2a.launch @@ -1,9 +1,6 @@ - - - @@ -19,8 +16,6 @@ - - diff --git a/physical_bringup/launch/traxxas_drive2a_kinect.launch b/physical_bringup/launch/traxxas_drive2a_kinect.launch index 89a29976..2d75fe55 100644 --- a/physical_bringup/launch/traxxas_drive2a_kinect.launch +++ b/physical_bringup/launch/traxxas_drive2a_kinect.launch @@ -1,9 +1,6 @@ - - - @@ -18,8 +15,6 @@ - - diff --git a/physical_bringup/launch/traxxas_drive_signal1.launch b/physical_bringup/launch/traxxas_drive_signal1.launch index 4970713b..71ec8310 100644 --- a/physical_bringup/launch/traxxas_drive_signal1.launch +++ b/physical_bringup/launch/traxxas_drive_signal1.launch @@ -33,7 +33,6 @@ - diff --git a/physical_bringup/launch/traxxas_drive_signal2a.launch b/physical_bringup/launch/traxxas_drive_signal2a.launch index b66e6e72..4755d451 100644 --- a/physical_bringup/launch/traxxas_drive_signal2a.launch +++ b/physical_bringup/launch/traxxas_drive_signal2a.launch @@ -33,7 +33,6 @@ - diff --git a/signal_recognition/launch/signal_panel_recognition.launch b/signal_recognition/launch/signal_panel_recognition.launch index 7fd4c9e8..58a78af7 100644 --- a/signal_recognition/launch/signal_panel_recognition.launch +++ b/signal_recognition/launch/signal_panel_recognition.launch @@ -1,16 +1,10 @@ - - - - - - \ No newline at end of file diff --git a/signal_recognition/scripts/signal_panel_recognition.py b/signal_recognition/scripts/signal_panel_recognition.py index cfd2340e..19e871ec 100755 --- a/signal_recognition/scripts/signal_panel_recognition.py +++ b/signal_recognition/scripts/signal_panel_recognition.py @@ -1,35 +1,24 @@ #!/usr/bin/env python3 # Imports -#import argparse import cv2 -from csv import writer -#import copy import numpy as np import rospy from std_msgs.msg import Bool -from geometry_msgs.msg._Twist import Twist from sensor_msgs.msg._Image import Image from cv_bridge.core import CvBridge -from datetime import datetime -#from tensorflow.keras.models import load_model import pathlib -#import os -#import string +from datetime import datetime +import pandas as pd +import signal +import sys +import os + global img_rbg global bridge global begin_img -# not used by now -def preProcess(img): - img = cv2.cvtColor(img, cv2.COLOR_RGB2YUV) - img = cv2.GaussianBlur(img, (3, 3), 0) - img = cv2.resize(img, (200, 66)) - img = img/255 - - return img - def message_RGB_ReceivedCallback(message): global img_rbg @@ -41,14 +30,25 @@ def message_RGB_ReceivedCallback(message): begin_img = True -def main(): +def signal_handler(sig, frame): + global signal_log + global log_path + + rospy.loginfo('You pressed Ctrl+C!') + curr_time = datetime.now() + time_str = str(curr_time.year) + '_' + str(curr_time.month) + '_' + str(curr_time.day) + '__' + str( + curr_time.hour) + '_' + str(curr_time.minute) + signal_log.to_csv(log_path + '/signal_log_' + time_str + '.csv', mode='a', index=False, header=False) + sys.exit(0) +def main(): + global signal_log + global log_path # PARAMETERS__________________________________________________________________ # Import Parameters scale_import = 0.1 # The scale of the first image, related to the imported one. N_red = 2 # Number of piramidizations to apply to each image. - factor_red = 0.8 # Font Parameters subtitle_offset = -10 @@ -62,13 +62,9 @@ def main(): line_thickness = 3 # Detection Parameters - scale_cap = 0.4 detection_threshold = 0.85 - # Initial velocity - vel = 0 - # ______________________________________________________________________________ # Images to import and Images Info @@ -90,25 +86,36 @@ def main(): global begin_img begin_img = False velbool = False + count_stop = 0 + count_start = 0 + count_max = 5 - #twist = Twist() # Init Node rospy.init_node('ml_driving', anonymous=False) # Get parameters - image_raw_topic = rospy.get_param('~image_raw_topic', '/ackermann_vehicle/camera2/rgb/image_raw') - twist_cmd_topic = rospy.get_param('~twist_cmd_topic', '/cmd_vel') + image_raw_topic = rospy.get_param('~image_raw_topic', '/ackermann_vehicle/camera2/rgb/image_raw') signal_cmd_topic = rospy.get_param('~signal_cmd_topic', '/signal_vel') - twist_linear_x = rospy.get_param('~twist_linear_x', 0.5) # Create publishers - #if twist_cmd_topic!= "": - #pubtwist = rospy.Publisher(twist_cmd_topic, Twist, queue_size=10) - - #if vel_cmd_topic!= "": pubbool = rospy.Publisher(signal_cmd_topic, Bool, queue_size=10) + # Define path for .csv + s = str(pathlib.Path(__file__).parent.absolute()) + log_path = s + '/log/' + rospy.loginfo(log_path) + + # If the path does not exist, create it + if not os.path.exists(log_path): + os.makedirs(log_path) + + # Create pandas dataframe + signal_log = pd.DataFrame(columns=['Time', 'Signal', 'Resolution']) + + # set handler on termination + signal.signal(signal.SIGINT, signal_handler) + # ______________________________________________________________________________ path = str(pathlib.Path(__file__).parent.absolute()) @@ -205,7 +212,6 @@ def main(): for name in dict_images.keys(): for key in dict_images[name]['images']: dict_images[name]['images'][key] = cv2.GaussianBlur(dict_images[name]['images'][key], (3, 3), 0) - #cv2.imshow(name + ' ' + key, dict_images[name]['images'][key]) # ______________________________________________________________________________ @@ -218,18 +224,15 @@ def main(): Image, message_RGB_ReceivedCallback) - rate = rospy.Rate(10) + rate = rospy.Rate(30) while not rospy.is_shutdown(): if begin_img == False: continue - #resized_ = preProcess(img_rbg) - width_frame = img_rbg.shape[1] height_frame = img_rbg.shape[0] - #default_dim = (width_frame, height_frame) reduced_dim = (int(width_frame * scale_cap), int(height_frame * scale_cap)) frame = cv2.resize(img_rbg, reduced_dim) @@ -244,11 +247,6 @@ def main(): max_key = '' - ##cv2.imshow('Robot View Processed', resized_) - #cv2.imshow('Robot View', img_rbg) - #cv2.imshow('Robot View used', frame) - #cv2.waitKey(1) - # For each image: for name in dict_images.keys(): for key in dict_images[name]['images']: @@ -264,13 +262,22 @@ def main(): max_name = name max_key = key - #print (max_res, max_key) + # Write log files + curr_time = datetime.now() + time_str = str(curr_time.year) + '_' + str(curr_time.month) + '_' + str(curr_time.day) + '__' + str( + curr_time.hour) + '_' + str(curr_time.minute) + '_' + str(curr_time.second) + '__' + str( + curr_time.microsecond) + # add image, angle and velocity to the signal_log pandas + max_res_round = round(max_res, 3) + print(max_res_round) + row = pd.DataFrame([[time_str, max_name, max_res_round]], columns=['Time', 'Signal', 'Resolution']) + signal_log = signal_log.append(row, ignore_index=True) + if max_res > detection_threshold: max_width = int(dict_images[max_name]['images'][max_key].shape[1] / scale_cap) max_height = int(dict_images[max_name]['images'][max_key].shape[0] / scale_cap) - max_dim = (max_width, max_height) for pt in zip(*max_loc[::-1]): pt = tuple(int(pti / scale_cap) for pti in pt) @@ -278,8 +285,6 @@ def main(): dict_colors.get(dict_images[max_name]['color']), line_thickness) text = 'Detected: ' + max_name + ' ' + max_key + ' > ' + dict_images[max_name]['type'] + ': ' + \ dict_images[max_name]['title'] - - #print(text) origin = (pt[0], pt[1] + subtitle_offset) origin_2 = (0, height_frame + subtitle_2_offset) @@ -292,21 +297,19 @@ def main(): # Defining and publishing the velocity of the car in regards to the signal seen if max_name == "pForward": velbool = True + count_start = count_start + 1 + count_stop = 0 elif max_name == "pStop": velbool = False + count_stop = count_stop + 1 + count_start = 0 + + if count_stop >= count_max or count_start >= count_max: + pubbool.publish(velbool) - # Send twist or bool - #if twist_cmd_topic != "": - # twist.linear.x = vel - # twist.linear.y = 0 - # twist.linear.z = 0 - # twist.angular.x = 0 - # twist.angular.y = 0 - # twist.angular.z = 0 - # pubtwist.publish(twist) - - #if vel_cmd_topic != "": - pubbool.publish(velbool) + else: + count_stop = 0 + count_start = 0 # Show image cv2.imshow("Frame", img_rbg)