diff --git a/butia_image2world/scripts/butia_image2world/image2world/image2world.py b/butia_image2world/scripts/butia_image2world/image2world/image2world.py index 6ef94e16..56420230 100755 --- a/butia_image2world/scripts/butia_image2world/image2world/image2world.py +++ b/butia_image2world/scripts/butia_image2world/image2world/image2world.py @@ -307,18 +307,47 @@ def __instanceSegmentationDescriptionProcessing(self, source_data, description2d def __poseDescriptionProcessing(self, data, description2d : Description2D, header): description3d : Description3D = self.__detectionDescriptionProcessing(data, description2d ,header) - kpt : KeyPoint2D - for kpt in description2d.pose: - kpt3D = KeyPoint3D() - kpt3D.id = kpt.id - kpt3D.score = kpt.score - kpt3D.x = kpt.x - kpt3D.y = kpt.y - kpt3D.z = 0 - description3d.pose.append(kpt3D) + if 'image_depth' in data and 'camera_info' in data: + image_depth = data['image_depth'] + camera_info = data['camera_info'] - return description3d + self.__mountLutTable(camera_info) + + h, w = image_depth.shape + + kpt : KeyPoint2D + for kpt in description2d.pose: + kpt3D = KeyPoint3D() + kpt3D.id = kpt.id + + u = int(kpt.x) + v = int(kpt.y) + if u >= w or u < 0 or v >= h or v < 0: + kpt3D.score = 0 + + else: + depth = image_depth[v, u] + + if depth <= 0: + kpt3D.score = 0 + + else: + kpt3D.score = kpt.score + + depth /= 1000. + + vertex_3d = np.zeros(3) + vertex_3d[:2] = self.lut_table[v, u, :]*depth + vertex_3d[2] = depth + + kpt3D.x = vertex_3d[0] + kpt3D.y = vertex_3d[1] + kpt3D.z = vertex_3d[2] + + description3d.pose.append(kpt3D) + + return description3d def __createDescription3D(self, source_data, description2d : Description2D, header): if description2d.type in self.DESCRIPTION_PROCESSING_ALGORITHMS: @@ -419,6 +448,29 @@ def publishMarkers(self, descriptions3d): marker.text = '{} ({:.2f})'.format(name, det.score) marker.lifetime = rospy.Time.from_sec(2) markers.markers.append(marker) + + for idx, kpt3D in enumerate(det.pose): + if kpt3D.score > 0: + marker = Marker() + marker.header = det.poses_header + marker.type = Marker.SPHERE + marker.id = idx + marker.color.r = color[1] + marker.color.g = color[2] + marker.color.b = color[0] + marker.color.a = 1 + marker.scale.x = 0.05 + marker.scale.y = 0.05 + marker.scale.z = 0.05 + marker.pose.position.x = kpt3D.x + marker.pose.position.y = kpt3D.y + marker.pose.position.z = kpt3D.z + marker.pose.orientation.x = 0.0 + marker.pose.orientation.y = 0.0 + marker.pose.orientation.z = 0.0 + marker.pose.orientation.w = 1.0 + marker.lifetime = rospy.Time.from_sec(2) + markers.markers.append(marker) self.marker_publisher.publish(markers) diff --git a/butia_people_tracking/config/ros.yaml b/butia_people_tracking/config/ros.yaml index 13ec292e..8e1d52e2 100644 --- a/butia_people_tracking/config/ros.yaml +++ b/butia_people_tracking/config/ros.yaml @@ -4,7 +4,6 @@ services: stop_tracking: "/butia_vision/pt/stop" topics: - butia_recognition: - people_detection: "/butia_vision/br/people_detection" people_tracking: + people_detection: "/butia_vision/br/recognitions2D" people_tracking: "/butia_vision/pt/people_tracking" \ No newline at end of file diff --git a/butia_people_tracking/scripts/people_tracking_node.py b/butia_people_tracking/scripts/people_tracking_node.py index 0c5aec9a..94b4bfab 100755 --- a/butia_people_tracking/scripts/people_tracking_node.py +++ b/butia_people_tracking/scripts/people_tracking_node.py @@ -115,11 +115,11 @@ def stopTracking(req): queue_size = rospy.get_param("/people_tracking/queue/size", 1) - param_start_service = rospy.get_param("/services/people_tracking/start_tracking", "/butia_vision/pt/start") - param_stop_service = rospy.get_param("/services/people_tracking/stop_tracking", "/butia_vision/pt/stop") + param_start_service = rospy.get_param("people_tracking/services/people_tracking/start_tracking", "/butia_vision/pt/start") + param_stop_service = rospy.get_param("people_tracking/services/people_tracking/stop_tracking", "/butia_vision/pt/stop") - param_people_detection_topic = rospy.get_param("/topics/butia_recognition/people_detection", "/butia_vision/br/people_detection") - param_people_tracking_topic = rospy.get_param("/topics/people_tracking/people_tracking", "/butia_vision/pt/people_tracking") + param_people_detection_topic = rospy.get_param("people_tracking/topics/people_tracking/people_detection", "/butia_vision/br/recognitions2D") + param_people_tracking_topic = rospy.get_param("people_tracking/topics/people_tracking/people_tracking", "/butia_vision/pt/people_tracking") tracker_publisher = rospy.Publisher(param_people_tracking_topic, Recognitions2D, queue_size = queue_size) view_publisher = rospy.Publisher('/butia_vision/pt/people_tracking_view', Image, queue_size = queue_size) diff --git a/butia_recognition/config/yolo_tracker_bag_recognition.yaml b/butia_recognition/config/yolo_tracker_bag_recognition.yaml new file mode 100644 index 00000000..04ed0daa --- /dev/null +++ b/butia_recognition/config/yolo_tracker_bag_recognition.yaml @@ -0,0 +1,53 @@ +debug_kpt_threshold: 0.5 + +model_file: yolov8s-pose.pt + +subscribers: + + queue_size: 1 + exact_time: true + slop: 0.1 + + image_rgb: /butia_vision/bvb/image_rgb + + image_depth: /butia_vision/bvb/image_depth + + camera_info: /butia_vision/bvb/camera_info + + +publishers: + + recognition: + topic: /butia_vision/br/recognitions2D + queue_size: 1 + + debug: + topic: /butia_vision/br/debug2 + queue_size: 1 + + tracking: + topic: /butia_vision/pt/tracking2D + queue_size: 1 + +servers: + start: + service: /butia_vision/br/yolo_tracking/start + + stop: + service: /butia_vision/br/yolo_tracking/stop + +services: + tracking: + start: /butia_vision/yolo_pt/start + stop: /butia_vision/yolo_pt/stop + +tracking: + start_on_init: false + use_boxmot: false + model_file: osnet_x0_25_msmt17.pt + thresholds: + reid_threshold: 0.3 + det_threshold: 0.5 + iou_threshold: 0.15 + max_age: 10 + max_time: 10 diff --git a/butia_recognition/config/yolov5_people_detection.yaml b/butia_recognition/config/yolov5_people_detection.yaml index f8bd53a4..2a961896 100644 --- a/butia_recognition/config/yolov5_people_detection.yaml +++ b/butia_recognition/config/yolov5_people_detection.yaml @@ -24,7 +24,7 @@ subscribers: publishers: people_detection: - topic: /butia_vision/br/face_recognition + topic: /butia_vision/br/recognition2D queue_size: 1 servers: diff --git a/butia_recognition/config/yolov8_bag_recognition.yaml b/butia_recognition/config/yolov8_bag_recognition.yaml new file mode 100644 index 00000000..1d487c6f --- /dev/null +++ b/butia_recognition/config/yolov8_bag_recognition.yaml @@ -0,0 +1,42 @@ +threshold: 0.5 +classes_by_category: + bag: ['bag'] +all_classes: + - bag + +max_sizes: + - [0.5, 2.5, 0.5] + +model_file: yolov8_bag.pt + +subscribers: + + queue_size: 1 + exact_time: false + slop: 0.2 + + image_rgb: /butia_vision/bvb/image_rgb + camera_info: /butia_vision/bvb/camera_info + image_depth: /butia_vision/bvb/image_depth + # points: /butia_vision/bvb/points + + # image_rgb: /camera/color/image_raw + # camera_info: /camera/color/camera_info + # image_depth: /camera/aligned_depth_to_color/image_raw + +publishers: + + object_recognition: + topic: /butia_vision/br/object_recognition + queue_size: 1 + +servers: + + list_classes: + service: /butia_vision/br/object_recognition/list_classes + + start: + service: /butia_vision/br/object_recognition/start + + stop: + service: /butia_vision/br/object_recognition/stop diff --git a/butia_recognition/config/yolov8_object_recognition.yaml b/butia_recognition/config/yolov8_object_recognition.yaml new file mode 100644 index 00000000..c22625c4 --- /dev/null +++ b/butia_recognition/config/yolov8_object_recognition.yaml @@ -0,0 +1,47 @@ +threshold: 0.5 +classes_by_category: + fruits: ['Apple', 'Banana', 'Grape', 'Orange', 'Pineapple', 'Watermelon'] +all_classes: + - Apple + - Banana + - Grape + - Orange + - Pineapple + - Watermelon + +max_sizes: + - [0.5, 2.5, 0.5] + +model_file: yolov8_lab_objects.pt + +subscribers: + + queue_size: 1 + exact_time: false + slop: 0.2 + + # image_rgb: /butia_vision/bvb/image_rgb + # camera_info: /butia_vision/bvb/camera_info + # image_depth: /butia_vision/bvb/image_depth + #points: /butia_vision/bvb/points + + image_rgb: /camera/color/image_raw + camera_info: /camera/color/camera_info + image_depth: /camera/aligned_depth_to_color/image_raw + +publishers: + + object_recognition: + topic: /butia_vision/br/object_recognition + queue_size: 1 + +servers: + + list_classes: + service: /butia_vision/br/object_recognition/list_classes + + start: + service: /butia_vision/br/object_recognition/start + + stop: + service: /butia_vision/br/object_recognition/stop diff --git a/butia_recognition/config/yolov8_object_recognition_backup.yaml b/butia_recognition/config/yolov8_object_recognition_backup.yaml new file mode 100644 index 00000000..381ee636 --- /dev/null +++ b/butia_recognition/config/yolov8_object_recognition_backup.yaml @@ -0,0 +1,97 @@ +threshold: 0.5 +classes_by_category: + drink: ['guarana', 'Guarana', 'IceTea', 'tonic', Tonic', 'Coke', 'Beer can', 'CoconutWater', 'Water', Soda can'] + snack: ['corn flakes', 'CornFlakes', 'pringles', 'Pringles', 'Popcorn', 'Cookies', 'Cracker', 'Chocolate Milk', 'TunaCan'] + fruits: ['apple', 'Apple', 'kiwi', 'Kiwi', 'orange', 'Banana', 'Orange'] + cutlelary: ['bowl', 'Bowl', 'fork', 'knife', 'plate', 'Plate', 'Cleaner', 'Napkin', 'Cloth', 'EnglishSauce', 'TomatoSauce'] + misc: ['sponge', 'Sponge', 'Bag', 'Alcohol Bottle', 'Soap', 'Mug', 'Carrot', 'Yeast', 'Coconut Milk', 'Chocolate Powder', 'Ketchup', 'Mayonnaise', 'Mustard', 'Toothpaste', 'Gelatine'] +all_classes: + - Alcohol Bottle + - Apple + - Bag + - Banana + - Beer can + - Bowl + - Carrot + - Chocolate Milk + - Chocolate Powder + - Cleaner + - Cloth + - Coconut Milk + - CoconutWater + - Coke + - Cookies + - CornFlakes + - Cracker + - EnglishSauce + - Gelatine + - Guarana + - IceTea + - Ketchup + - Kiwi + - Mayonnaise + - Mug + - Mustard + - Napkin + - Orange + - Plate + - Popcorn + - Pringles + - Soap + - Soda can + - Sponge + - TomatoSauce + - Tonic + - Toothpaste + - TunaCan + - Water + - Yeast + - apple + - bowl + - corn flakes + - fork + - guarana + - kiwi + - knife + - orange + - plate + - pringles + - sponge + - tonic + +max_sizes: + - [0.5, 2.5, 0.5] + +model_file: yolov8_lab_objects.pt + +subscribers: + + queue_size: 1 + exact_time: false + slop: 0.2 + + # image_rgb: /butia_vision/bvb/image_rgb + # camera_info: /butia_vision/bvb/camera_info + # image_depth: /butia_vision/bvb/image_depth + #points: /butia_vision/bvb/points + + image_rgb: /camera/color/image_raw + camera_info: /camera/color/camera_info + image_depth: /camera/aligned_depth_to_color/image_raw + +publishers: + + object_recognition: + topic: /butia_vision/br/object_recognition + queue_size: 1 + +servers: + + list_classes: + service: /butia_vision/br/object_recognition/list_classes + + start: + service: /butia_vision/br/object_recognition/start + + stop: + service: /butia_vision/br/object_recognition/stop diff --git a/butia_recognition/include/yolov5 b/butia_recognition/include/yolov5 index d3ea0df8..956be8e6 160000 --- a/butia_recognition/include/yolov5 +++ b/butia_recognition/include/yolov5 @@ -1 +1 @@ -Subproject commit d3ea0df8b9f923685ce5f2555c303b8eddbf83fd +Subproject commit 956be8e642b5c10af4a1533e09084ca32ff4f21f diff --git a/butia_recognition/launch/yolov8_bag_recognition.launch b/butia_recognition/launch/yolov8_bag_recognition.launch new file mode 100644 index 00000000..836da2fc --- /dev/null +++ b/butia_recognition/launch/yolov8_bag_recognition.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + [255,0,0] + + + diff --git a/butia_recognition/launch/yolov8_object_recognition.launch b/butia_recognition/launch/yolov8_object_recognition.launch new file mode 100644 index 00000000..45ddd500 --- /dev/null +++ b/butia_recognition/launch/yolov8_object_recognition.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + [255,0,0] + + + diff --git a/butia_recognition/scripts/butia_recognition/__init__.py b/butia_recognition/scripts/butia_recognition/__init__.py index 6208e7fb..3b212d1e 100644 --- a/butia_recognition/scripts/butia_recognition/__init__.py +++ b/butia_recognition/scripts/butia_recognition/__init__.py @@ -1,2 +1,3 @@ from .base_recognition import * -from .yolov5_recognition import * \ No newline at end of file +from .yolov5_recognition import * +from .yolov8_recognition import * \ No newline at end of file diff --git a/butia_recognition/scripts/butia_recognition/yolo_tracker_recognition/yolo_tracker_recognition.py b/butia_recognition/scripts/butia_recognition/yolo_tracker_recognition/yolo_tracker_recognition.py index b13a261f..77816c93 100755 --- a/butia_recognition/scripts/butia_recognition/yolo_tracker_recognition/yolo_tracker_recognition.py +++ b/butia_recognition/scripts/butia_recognition/yolo_tracker_recognition/yolo_tracker_recognition.py @@ -19,6 +19,9 @@ from butia_vision_msgs.msg import Recognitions2D, Description2D, KeyPoint2D, Recognitions3D from copy import deepcopy +import gc +import torch + DeepOCSORT = None class YoloTrackerRecognition(BaseRecognition): @@ -33,6 +36,8 @@ def __init__(self,state = True): DeepOCSORT = boxmot.DeepOCSORT if self.tracking_on_init: self.startTracking(None) + + self.lastTrack = perf_counter() rospy.loginfo("Yolo Tracker Recognition Node started") @@ -48,17 +53,17 @@ def initRosComm(self): def serverStart(self, req): self.loadModel() - return super().serverStart(req) def serverStop(self, req): self.unLoadModel() + self.stopTracking(None) return super().serverStop(req) def startTracking(self, req): self.loadTrackerModel() self.trackID = -1 - self.lastTrack = 0 + self.lastTrack = perf_counter() self.tracking = True rospy.loginfo("Tracking started!!!") return EmptyResponse() @@ -88,12 +93,15 @@ def loadTrackerModel(self): def unLoadTrackerModel(self): if self.use_boxmot: del self.tracker + torch.cuda.empty_cache() + self.tracker = None return def unLoadModel(self): del self.model - self.unLoadTrackingModel + torch.cuda.empty_cache() + self.model = None return @ifState @@ -121,24 +129,28 @@ def callback(self, *args): bboxs = None if tracking and self.use_boxmot: - results = self.model(img,verbose=False) + results = list(self.model.predict(img, verbose=False, stream=True)) bboxs = self.tracker.update(results[0].boxes.data.cpu().numpy(),img) elif tracking: - results = self.model.track(img, persist=True, + results = list(self.model.track(img, persist=True, conf=self.det_threshold, iou=self.iou_threshold, device="cuda:0", tracker=self.tracker_cfg_file, - verbose=True) + verbose=True, stream=True)) bboxs = results[0].boxes.data.cpu().numpy() else: - results = self.model(img,verbose=False) + results = list(self.model.predict(img, verbose=False, stream=True)) bboxs = results[0].boxes.data.cpu().numpy() people_ids = [] tracked_box = None now = perf_counter() + is_aged = (now - self.lastTrack >= self.max_time) + is_id_found = False + previus_size = float("-inf") + new_id = -1 # descriptions = [] for i, box in enumerate(bboxs): description = Description2D() @@ -160,7 +172,6 @@ def callback(self, *args): description.id = i box_label = "" - previus_size = float("-inf") if tracking: description.global_id = ID if description.label == "person": @@ -168,29 +179,33 @@ def callback(self, *args): box_label = f"ID:{ID} " size = description.bbox.size_x * description.bbox.size_y - if ID == self.trackID or \ - self.trackID == -1 or \ - (perf_counter() - self.lastTrack >= self.max_time and \ - (tracked_box == None or\ - size > previus_size)): - - self.trackID = ID - previus_size = size + + if ID == self.trackID: + is_id_found = True tracked_box = description + + if (not is_id_found) and (is_aged or self.trackID == -1): + if tracked_box is None or size > previus_size: + previus_size = size + tracked_box = description + new_id = ID + recognition.descriptions.append(description) - + cv.rectangle(debug_img,(int(X1),int(Y1)), (int(X2),int(Y2)),(0,0,255),thickness=2) cv.putText(debug_img,f"{box_label}{self.model.names[clss]}:{score:.2f}", (int(X1), int(Y1)), cv.FONT_HERSHEY_SIMPLEX,0.75,(0,0,255),thickness=2) track_recognition = Recognitions2D() track_recognition.header = HEADER tracked_description : Description2D = deepcopy(tracked_box) - if tracked_box != None: + if tracked_box is not None: track_recognition.header = recognition.header track_recognition.image_rgb = recognition.image_rgb track_recognition.image_depth = recognition.image_depth track_recognition.camera_info = recognition.camera_info tracked_description.type = Description2D.DETECTION + if not is_id_found: + self.trackID = new_id # recognition.descriptions.append(tracked_box) self.lastTrack = now cv.rectangle(debug_img,(int(tracked_box.bbox.center.x-tracked_box.bbox.size_x/2),\ diff --git a/butia_recognition/scripts/butia_recognition/yolov8_recognition/__init__.py b/butia_recognition/scripts/butia_recognition/yolov8_recognition/__init__.py new file mode 100644 index 00000000..421055ec --- /dev/null +++ b/butia_recognition/scripts/butia_recognition/yolov8_recognition/__init__.py @@ -0,0 +1 @@ +from .yolov8_recognition import * \ No newline at end of file diff --git a/butia_recognition/scripts/butia_recognition/yolov8_recognition/backup_do_arquivo_padrao.py b/butia_recognition/scripts/butia_recognition/yolov8_recognition/backup_do_arquivo_padrao.py new file mode 100644 index 00000000..e96facc3 --- /dev/null +++ b/butia_recognition/scripts/butia_recognition/yolov8_recognition/backup_do_arquivo_padrao.py @@ -0,0 +1,169 @@ +#!/usr/bin/env python3 +# -*- coding: utf-8 -*- +import rospy + +import rospkg + +from sensor_msgs.msg import Image +from std_srvs.srv import Empty, EmptyResponse + +from butia_vision_msgs.srv import ListClasses, ListClassesResponse + +from butia_vision_bridge import VisionSynchronizer + +def ifState(func): + def wrapper_func(*args, **kwargs): + if args[0].state: + func(*args, **kwargs) + return wrapper_func + + +class BaseRecognition: + def __init__(self, state=True): + self.readParameters() + + self.rospack = rospkg.RosPack().get_path('butia_generic_recognition') + + self.state = state + + def initRosComm(self): + self.recognized_objects_pub = rospy.Publisher(self.object_recognition_topic, Recognitions2D, queue_size=self.object_recognition_qs) + + self.list_objects_server = rospy.Service(self.list_objects_service, ListClasses, self.getObjectList) + + self.start_server = rospy.Service(self.start_service, Empty, self.start) + + self.stop_server = rospy.Service(self.stop_service, Empty, self.stop) + + def start(self, req): + self.state = True + return EmptyResponse() + + def stop(self, req): + self.state = False + return EmptyResponse() + + def getObjectList(self, req): + objects_list = [] + for key, value in self.classes_by_category.items(): + for elem in value: + objects_list.append(key + '/' + elem) + return ListClassesResponse(objects_list) + + def yoloRecognitionCallback(self, img): + + if self.state == True: + + with torch.no_grad(): + + rospy.loginfo('Image ID: ' + str(img.header.seq)) + + cv_img = np.frombuffer(img.data, dtype=np.uint8).reshape(img.height, img.width, -1) + + #cv_img = self.bridge.imgmsg_to_cv2(img, desired_encoding='rgb8').copy() + + #results = self.model(torch.tensor(cv_img.reshape((1, 3, 640, 480)).astype(np.float32)).to(self.model.device)) + results = self.model(cv_img) + + bbs_l = results.pandas().xyxy[0] + + objects = [] + people = [] + + for i in range(len(bbs_l)): + + if int(bbs_l['class'][i]) >= len(self.all_classes): + continue + bbs_l['name'][i] = self.all_classes[int(bbs_l['class'][i])] + reference_model = bbs_l['name'][i] + print(bbs_l['name'][i]) + #cv_img = cv2.cvtColor(cv_img, cv2.COLOR_RGB2BGR) + cv_img = cv2.rectangle(cv_img, (int(bbs_l['xmin'][i]), int(bbs_l['ymin'][i])), (int(bbs_l['xmax'][i]), int(bbs_l['ymax'][i])), self.colors[bbs_l['name'][i]]) + cv_img = cv2.putText(cv_img, bbs_l['name'][i], (int(bbs_l['xmin'][i]), int(bbs_l['ymin'][i])), cv2.FONT_HERSHEY_SIMPLEX, 1.0, color=self.colors[bbs_l['name'][i]]) + if ('people' in self.all_classes and bbs_l['name'][i] in self.classes_by_category['people'] or 'people' in self.all_classes and bbs_l['name'][i] == 'people') and bbs_l['confidence'][i] >= self.threshold: + + person = Description() + person.label_class = 'people' + '/' + bbs_l['name'][i] + person.reference_model = reference_model + person.probability = bbs_l['confidence'][i] + person.bounding_box.minX = int(bbs_l['xmin'][i]) + person.bounding_box.minY = int(bbs_l['ymin'][i]) + person.bounding_box.width = int(bbs_l['xmax'][i] - bbs_l['xmin'][i]) + person.bounding_box.height = int(bbs_l['ymax'][i] - bbs_l['ymin'][i]) + people.append(person) + + elif (bbs_l['name'][i] in [val for sublist in self.all_classes for val in sublist] or bbs_l['name'][i] in self.all_classes) and bbs_l['confidence'][i] >= self.threshold: + + object_d = Description() + index = None + j = 0 + for value in self.classes_by_category.values(): + if bbs_l['name'][i] in value: + index = j + j += 1 + object_d.reference_model = reference_model + object_d.label_class = self.all_classes[index] + '/' + bbs_l['name'][i] if index is not None else bbs_l['name'][i] + + object_d.probability = bbs_l['confidence'][i] + object_d.bounding_box.minX = int(bbs_l['xmin'][i]) + object_d.bounding_box.minY = int(bbs_l['ymin'][i]) + object_d.bounding_box.width = int(bbs_l['xmax'][i] - bbs_l['xmin'][i]) + object_d.bounding_box.height = int(bbs_l['ymax'][i]- bbs_l['ymin'][i]) + objects.append(object_d) + + #cv2.imshow('YoloV5', cv_img) + #cv2.waitKey(1) + + debug_msg = Image() + debug_msg.data = cv_img[:,:,::-1].flatten().tolist() + debug_msg.encoding = "rgb8" + debug_msg.width = cv_img.shape[1] + debug_msg.height = cv_img.shape[0] + debug_msg.step = debug_msg.width*3 + self.debug_image_pub.publish(debug_msg) + + objects_msg = Recognitions() + people_msg = Recognitions() + + if len(objects) > 0: + #objects_msg.header = bbs.header + objects_msg.image_header = img.header + objects_msg.descriptions = objects + self.recognized_objects_pub.publish(objects_msg) + + if len(people) > 0: + #people_msg.header = bbs.header + people_msg.image_header = img.header + people_msg.descriptions = people + self.recognized_people_pub.publish(people_msg) + + def readParameters(self): + self.bounding_boxes_topic = rospy.get_param("/object_recognition/subscribers/bounding_boxes/topic", "/darknet_ros/bounding_boxes") + self.bounding_boxes_qs = rospy.get_param("/object_recognition/subscribers/bounding_boxes/queue_size", 1) + + self.image_topic = rospy.get_param("/object_recognition/subscribers/image/topic", "/butia_vision/bvb/image_rgb_raw") + self.image_qs = rospy.get_param("/object_recognition/subscribers/image/queue_size", 1) + + self.debug_image_topic = rospy.get_param("/object_recognition/publishers/debug_image/topic", "/butia_vision/or/debug") + self.debug_image_qs = rospy.get_param("/object_recognition/publishers/debug_image/queue_size", 1) + + self.object_recognition_topic = rospy.get_param("/object_recognition/publishers/object_recognition/topic", "/butia_vision/or/object_recognition") + self.object_recognition_qs = rospy.get_param("/object_recognition/publishers/object_recognition/queue_size", 1) + + self.people_detection_topic = rospy.get_param("/object_recognition/publishers/people_detection/topic", "/butia_vision/or/people_detection") + self.people_detection_qs = rospy.get_param("/object_recognition/publishers/people_detection/queue_size", 1) + + self.object_list_updated_topic = rospy.get_param("/object_recognition/publishers/object_list_updated/topic", "/butia_vision/or/object_list_updated") + self.object_list_updated_qs = rospy.get_param("/object_recognition/publishers/object_list_updated/queue_size", 1) + + self.list_objects_service = rospy.get_param("/object_recognition/servers/list_objects/service", "/butia_vision/or/list_objects") + self.start_service = rospy.get_param("/object_recognition/servers/start/service", "/butia_vision/or/start") + self.stop_service = rospy.get_param("/object_recognition/servers/stop/service", "/butia_vision/or/stop") + + self.threshold = rospy.get_param("/object_recognition/threshold", 0.5) + + self.all_classes = list(rospy.get_param("/object_recognition/all_classes")) + + self.classes_by_category = dict(rospy.get_param("/object_recognition/classes_by_category")) + + self.model_file = rospy.get_param("/object_recognition/model_file", "larc2021_go_and_get_it.pt") \ No newline at end of file diff --git a/butia_recognition/scripts/butia_recognition/yolov8_recognition/yolov8_recognition.py b/butia_recognition/scripts/butia_recognition/yolov8_recognition/yolov8_recognition.py old mode 100644 new mode 100755 index 6593d7a5..fc9497e7 --- a/butia_recognition/scripts/butia_recognition/yolov8_recognition/yolov8_recognition.py +++ b/butia_recognition/scripts/butia_recognition/yolov8_recognition/yolov8_recognition.py @@ -1,20 +1,18 @@ #!/usr/bin/env python3 # -*- coding: utf-8 -*- import rospy - import ros_numpy - from butia_recognition import BaseRecognition, ifState - import numpy as np import os from copy import copy import cv2 from ultralytics import YOLO - from std_msgs.msg import Header from sensor_msgs.msg import Image +from geometry_msgs.msg import Vector3 from butia_vision_msgs.msg import Description2D, Recognitions2D +import torch class YoloV8Recognition(BaseRecognition): @@ -43,101 +41,93 @@ def serverStop(self, req): return super().serverStop(req) def loadModel(self): - self.model = YOLO("/home/butiabots/Workspace/butia_ws/src/butia_vision/butia_recognition/config/yolov8_network_config/yolov8_lab_objects.pt") + self.model = YOLO("/home/jetson/sd/butia_ws/src/butia_vision/butia_recognition/config/yolov8_network_config/yolov8_bag.pt") self.model.conf = self.threshold print('Done loading model!') def unLoadModel(self): del self.model + torch.cuda.empty_cache() + self.model = None @ifState def callback(self, *args): - img = None - #points = None - if len(args): - img = args[0] - print(img) - - #points = args[1] - - rospy.loginfo('Image ID: ' + str(img.header.seq)) - - cv_img = ros_numpy.numpify(img) - print(cv_img[0]) - results = self.model.predict(cv_img) # MUDEI AQUI - bbs_l = None - debug_img = copy(cv_img) - print("-----------------------------------------------------------------------------") - for elemento in results: - bbs_l = elemento.boxes - debug_img = elemento.plot() - print(len(bbs_l.xyxy)) - print(bbs_l) - print("-----------------------------------------------------------------------------") - print(type(results)) - - bbs_l = bbs_l.xyxy - #bbs_l = results.boxes + source_data = self.sourceDataFromArgs(args) + if 'image_rgb' not in source_data: + rospy.logwarn('Souce data has no image_rgb.') + return None + + img_rgb = source_data['image_rgb'] + cv_img = ros_numpy.numpify(img_rgb) + rospy.loginfo('Image ID: ' + str(img_rgb.header.seq)) + objects_recognition = Recognitions2D() h = Header() - h.seq = self.seq - self.seq += 1 + h.seq = self.seq #id mensagem + self.seq += 1 #prox id h.stamp = rospy.Time.now() - objects_recognition.header = h - objects_recognition.image_rgb = copy(img) - #objects_recognition.points = copy(points) + objects_recognition.header = h + objects_recognition = BaseRecognition.addSourceData2Recognitions2D(source_data, objects_recognition) people_recognition = copy(objects_recognition) + description_header = img_rgb.header + description_header.seq = 0 - # description_header = img.header - # description_header.seq = 0 - # for i in range(len(bbs_l)): - # if int(bbs_l['class'][i]) >= len(self.classes): - # continue - - # label_class = self.classes[int(bbs_l['class'][i])] - - # description = Description2D() - # description.header = copy(description_header) - # description.type = Description2D.DETECTION - # description.id = description.header.seq - # description.score = bbs_l['confidence'][i] - # size = int(bbs_l['xmax'][i] - bbs_l['xmin'][i]), int(bbs_l['ymax'][i] - bbs_l['ymin'][i]) - # description.bbox.center.x = int(bbs_l['xmin'][i]) + int(size[0]/2) - # description.bbox.center.y = int(bbs_l['ymin'][i]) + int(size[1]/2) - # description.bbox.size_x = size[0] - # description.bbox.size_y = size[1] - # print(f"-----------------------------------------------------------------------------{size}") - - # if ('people' in self.classes and label_class in self.classes_by_category['people'] or 'people' in self.classes and label_class == 'people') and bbs_l['confidence'][i] >= self.threshold: - - # description.label = 'people' + '/' + label_class - # people_recognition.descriptions.append(description) - - # elif (label_class in [val for sublist in self.classes for val in sublist] or label_class in self.classes) and bbs_l['confidence'][i] >= self.threshold: - # print(f"-----------------------------------------------------------------------------{label_class}aaaaaaaaaaaaaaaa") - # index = None - # j = 0 - # for value in self.classes_by_category.values(): - # if label_class in value: - # index = j - # j += 1 - # description.label = self.classes[index] + '/' + label_class if index is not None else label_class - - # objects_recognition.descriptions.append(description) - - # debug_img = cv2.rectangle(debug_img, (int(bbs_l['xmin'][i]), int(bbs_l['ymin'][i])), (int(bbs_l['xmax'][i]), int(bbs_l['ymax'][i])), self.colors[label_class]) - # debug_img = cv2.putText(debug_img, label_class, (int(bbs_l['xmin'][i]), int(bbs_l['ymin'][i])), cv2.FONT_HERSHEY_SIMPLEX, 1.0, color=self.colors[label_class]) - # description_header.seq += 1 - - self.debug_publisher.publish(ros_numpy.msgify(Image, np.flip(debug_img, 2), 'rgb8')) + results = list(self.model.predict(cv_img, verbose=False, stream=True)) + boxes_ = results[0].boxes.cpu().numpy() + + if len(results[0].boxes): + for i in range(len(results[0].boxes)): + box = results[0].boxes[i] + xyxy_box = list(boxes_[i].xyxy.astype(int)[0]) + + if int(box.cls) >= len(self.all_classes): + continue - if len(objects_recognition.descriptions) > 0: - self.object_recognition_publisher.publish(objects_recognition) + label_class = self.all_classes[int(box.cls)] - if len(people_recognition.descriptions) > 0: - self.people_detection_publisher.publish(people_recognition) + + description = Description2D() + description.header = copy(description_header) + description.type = Description2D.DETECTION + description.id = description.header.seq + description.score = float(box.conf) + description.max_size = Vector3(*[0.5, 0.5, 0.5]) + size = int(xyxy_box[2] - xyxy_box[0]), int(xyxy_box[3] - xyxy_box[1]) + description.bbox.center.x = int(xyxy_box[0]) + int(size[0]/2) + description.bbox.center.y = int(xyxy_box[1]) + int(size[1]/2) + description.bbox.size_x = size[0] + description.bbox.size_y = size[1] + + if ('people' in self.all_classes and label_class in self.classes_by_category['people'] or 'people' in self.all_classes and label_class == 'people') and box.conf >= self.threshold: + + description.label = 'people' + '/' + label_class + people_recognition.descriptions.append(description) + + elif (label_class in [val for sublist in self.all_classes for val in sublist] or label_class in self.all_classes) and box.conf >= self.threshold: + index = None + + for value in self.classes_by_category.items(): + if label_class in value[1]: + index = value[0] + + description.label = index + '/' + label_class if index is not None else label_class + objects_recognition.descriptions.append(description) + + debug_img = results[0].plot() + description_header.seq += 1 + + self.debug_publisher.publish(ros_numpy.msgify(Image, debug_img, 'rgb8')) + + if len(objects_recognition.descriptions) > 0: + self.object_recognition_publisher.publish(objects_recognition) + + if len(people_recognition.descriptions) > 0: + self.people_detection_publisher.publish(people_recognition) + else: + debug_img = results[0].plot() + self.debug_publisher.publish(ros_numpy.msgify(Image, debug_img, 'rgb8')) def readParameters(self): self.debug_topic = rospy.get_param("~publishers/debug/topic", "/butia_vision/br/debug") @@ -151,7 +141,8 @@ def readParameters(self): self.threshold = rospy.get_param("~threshold", 0.5) - self.all_classes = list(rospy.get_param("/object_recognition/all_classes")) + + self.all_classes = list(rospy.get_param("~all_classes", [])) self.classes_by_category = dict(rospy.get_param("~classes_by_category", {})) self.model_file = rospy.get_param("~model_file", "yolov8_lab_objects.pt") @@ -162,4 +153,4 @@ def readParameters(self): yolo = YoloV8Recognition() - rospy.spin() + rospy.spin() \ No newline at end of file diff --git a/butia_recognition/scripts/butia_recognition_pytorch_node_v8.py b/butia_recognition/scripts/butia_recognition_pytorch_node_v8.py new file mode 100644 index 00000000..0924a3c8 --- /dev/null +++ b/butia_recognition/scripts/butia_recognition_pytorch_node_v8.py @@ -0,0 +1,12 @@ +#!/usr/bin/env python + +import rospy + +from butia_recognition import YoloV8Recognition + +if __name__ == '__main__': + rospy.init_node('butia_recognition_pytorch_node', anonymous = True) + + yolo = YoloV8Recognition() + + rospy.spin() diff --git a/butia_vision_launchfiles/yolo_tracker_bag_recognition.launch b/butia_vision_launchfiles/yolo_tracker_bag_recognition.launch new file mode 100644 index 00000000..adcc26b2 --- /dev/null +++ b/butia_vision_launchfiles/yolo_tracker_bag_recognition.launch @@ -0,0 +1,47 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [0,255,0] + 30 + + + + + + \ No newline at end of file