diff --git a/modules/docker-compose.perception.yaml b/modules/docker-compose.perception.yaml index 3614af7d..1651d739 100644 --- a/modules/docker-compose.perception.yaml +++ b/modules/docker-compose.perception.yaml @@ -30,7 +30,7 @@ services: capabilities: [ gpu ] command: /bin/bash -c "ros2 launch camera_object_detection eve_launch.py" volumes: - - /mnt/wato-drive2/perception_models/yolov8s.pt:/perception_models/yolov8s.pt + - /mnt/wato-drive2/perception_models/yolov8m.pt:/perception_models/yolov8m.pt lidar_object_detection: build: diff --git a/src/perception/camera_object_detection/camera_object_detection/yolov8_detection.py b/src/perception/camera_object_detection/camera_object_detection/yolov8_detection.py index b5ad2ea8..f5822173 100755 --- a/src/perception/camera_object_detection/camera_object_detection/yolov8_detection.py +++ b/src/perception/camera_object_detection/camera_object_detection/yolov8_detection.py @@ -34,8 +34,8 @@ def __init__(self): self.declare_parameter("camera_topic", "/camera/right/image_color") self.declare_parameter("publish_vis_topic", "/annotated_img") self.declare_parameter("publish_detection_topic", "/detections") - self.declare_parameter("model_path", "/perception_models/yolov8s.pt") - self.declare_parameter("image_size", 480) + self.declare_parameter("model_path", "/perception_models/yolov8m.pt") + self.declare_parameter("image_size", 1024) self.declare_parameter("compressed", False) self.camera_topic = self.get_parameter("camera_topic").value diff --git a/src/perception/camera_object_detection/config/deepracer_config.yaml b/src/perception/camera_object_detection/config/deepracer_config.yaml index 542efa7a..88a2e959 100755 --- a/src/perception/camera_object_detection/config/deepracer_config.yaml +++ b/src/perception/camera_object_detection/config/deepracer_config.yaml @@ -3,5 +3,5 @@ camera_object_detection_node: camera_topic: /camera_pkg/display_mjpeg publish_vis_topic: /annotated_img publish_obstacle_topic: /obstacles - model_path: /perception_models/yolov8s.pt - image_size: 480 + model_path: /perception_models/yolov8m.pt + image_size: 1024 diff --git a/src/perception/camera_object_detection/config/eve_config.yaml b/src/perception/camera_object_detection/config/eve_config.yaml index 11687c55..efac49fa 100755 --- a/src/perception/camera_object_detection/config/eve_config.yaml +++ b/src/perception/camera_object_detection/config/eve_config.yaml @@ -3,21 +3,21 @@ left_camera_object_detection_node: camera_topic: /camera/left/image_color publish_vis_topic: /camera/left/annotated_img publish_detection_topic: /camera/left/detections - model_path: /perception_models/yolov8s.pt - image_size: 480 + model_path: /perception_models/yolov8m.pt + image_size: 1024 center_camera_object_detection_node: ros__parameters: camera_topic: /camera/center/image_color publish_vis_topic: /camera/center/annotated_img publish_detection_topic: /camera/center/detections - model_path: /perception_models/yolov8s.pt - image_size: 480 + model_path: /perception_models/yolov8m.pt + image_size: 1024 right_camera_object_detection_node: ros__parameters: camera_topic: /camera/right/image_color publish_vis_topic: /camera/right/annotated_img publish_detection_topic: /camera/right/detections - model_path: /perception_models/yolov8s.pt - image_size: 480 + model_path: /perception_models/yolov8m.pt + image_size: 1024 diff --git a/src/perception/camera_object_detection/config/nuscenes_config.yaml b/src/perception/camera_object_detection/config/nuscenes_config.yaml index 6dff0554..6251c4b0 100755 --- a/src/perception/camera_object_detection/config/nuscenes_config.yaml +++ b/src/perception/camera_object_detection/config/nuscenes_config.yaml @@ -3,6 +3,6 @@ camera_object_detection_node: camera_topic: /CAM_FRONT/image_rect_compressed publish_vis_topic: /annotated_img publish_obstacle_topic: /obstacles - model_path: /perception_models/yolov8s.pt + model_path: /perception_models/yolov8m.pt image_size: 640 compressed: true