fixed object detection code to work in the devcontainer
Browse files
object_detection/__pycache__/buoy_detection_node.cpython-310.pyc
CHANGED
|
Binary files a/object_detection/__pycache__/buoy_detection_node.cpython-310.pyc and b/object_detection/__pycache__/buoy_detection_node.cpython-310.pyc differ
|
|
|
object_detection/buoy_detection_node.py
CHANGED
|
@@ -11,22 +11,27 @@ from std_msgs.msg import Int32
|
|
| 11 |
from autoboat_msgs.msg import ObjectDetectionResultsList
|
| 12 |
|
| 13 |
from cv_bridge import CvBridge
|
| 14 |
-
|
| 15 |
from ultralytics import YOLO
|
| 16 |
import cv2
|
| 17 |
import numpy as np
|
| 18 |
from math import sqrt
|
| 19 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 20 |
TRAINED_IMAGE_SIZE = (640, 640) # pixel width and height of the images that the model was trained on
|
| 21 |
IMAGE_CONFIDENCE = 0.3
|
| 22 |
|
| 23 |
-
SHOULD_SAVE_IMAGES =
|
| 24 |
|
| 25 |
|
| 26 |
class BuoyDetectionNode(Node):
|
| 27 |
def __init__(self):
|
| 28 |
super().__init__("buoy_detection")
|
| 29 |
-
self.model = YOLO("/
|
| 30 |
self.cv_bridge = CvBridge()
|
| 31 |
|
| 32 |
self.current_image_rgb = None
|
|
@@ -38,12 +43,12 @@ class BuoyDetectionNode(Node):
|
|
| 38 |
self.buoy_angle_pub = self.create_publisher(Float32, "/buoy_angle", 10)
|
| 39 |
self.buoy_depth_pixel_pub = self.create_publisher(Float32, "/buoy_depth_pixel", 10)
|
| 40 |
|
| 41 |
-
self.depth_image_listener = self.create_subscription(
|
| 42 |
-
|
| 43 |
-
|
| 44 |
-
|
| 45 |
-
|
| 46 |
-
)
|
| 47 |
# self.depth_image_listener = self.create_subscription(msg_type=Image, topic="/camera/depth/image_rect_raw", callback=self.depth_image_callback, qos_profile=sensor_qos_profile)
|
| 48 |
self.rgb_image_listener = self.create_subscription(
|
| 49 |
msg_type=Image, topic="/camera/camera/color/image_raw", callback=self.rgb_image_callback, qos_profile=sensor_qos_profile
|
|
@@ -215,17 +220,18 @@ class BuoyDetectionNode(Node):
|
|
| 215 |
if max_value <= 20:
|
| 216 |
self.current_image_rgb[y_value, x_value] = [160, 32, 240]
|
| 217 |
|
| 218 |
-
cv2.imwrite("rgb_image.jpg", self.current_image_rgb)
|
|
|
|
| 219 |
|
| 220 |
# For Depth Image
|
| 221 |
-
for x_value in range(self.depth_image.shape[1]):
|
| 222 |
-
|
| 223 |
-
|
| 224 |
-
|
| 225 |
-
|
| 226 |
-
|
| 227 |
-
|
| 228 |
-
cv2.imwrite("depth_image.jpg", self.depth_image)
|
| 229 |
|
| 230 |
if SHOULD_SAVE_IMAGES:
|
| 231 |
print("GOT HERE")
|
|
|
|
| 11 |
from autoboat_msgs.msg import ObjectDetectionResultsList
|
| 12 |
|
| 13 |
from cv_bridge import CvBridge
|
| 14 |
+
|
| 15 |
from ultralytics import YOLO
|
| 16 |
import cv2
|
| 17 |
import numpy as np
|
| 18 |
from math import sqrt
|
| 19 |
|
| 20 |
+
|
| 21 |
+
import os
|
| 22 |
+
|
| 23 |
+
current_directory_path = os.path.dirname(os.path.realpath(__file__))
|
| 24 |
+
|
| 25 |
TRAINED_IMAGE_SIZE = (640, 640) # pixel width and height of the images that the model was trained on
|
| 26 |
IMAGE_CONFIDENCE = 0.3
|
| 27 |
|
| 28 |
+
SHOULD_SAVE_IMAGES = False
|
| 29 |
|
| 30 |
|
| 31 |
class BuoyDetectionNode(Node):
|
| 32 |
def __init__(self):
|
| 33 |
super().__init__("buoy_detection")
|
| 34 |
+
self.model = YOLO(f"{current_directory_path}/weights/pretty_good_11l_train32.pt")
|
| 35 |
self.cv_bridge = CvBridge()
|
| 36 |
|
| 37 |
self.current_image_rgb = None
|
|
|
|
| 43 |
self.buoy_angle_pub = self.create_publisher(Float32, "/buoy_angle", 10)
|
| 44 |
self.buoy_depth_pixel_pub = self.create_publisher(Float32, "/buoy_depth_pixel", 10)
|
| 45 |
|
| 46 |
+
# self.depth_image_listener = self.create_subscription(
|
| 47 |
+
# msg_type=Image,
|
| 48 |
+
# topic="/camera/camera/aligned_depth_to_color/image_raw",
|
| 49 |
+
# callback=self.depth_image_callback,
|
| 50 |
+
# qos_profile=sensor_qos_profile,
|
| 51 |
+
# )
|
| 52 |
# self.depth_image_listener = self.create_subscription(msg_type=Image, topic="/camera/depth/image_rect_raw", callback=self.depth_image_callback, qos_profile=sensor_qos_profile)
|
| 53 |
self.rgb_image_listener = self.create_subscription(
|
| 54 |
msg_type=Image, topic="/camera/camera/color/image_raw", callback=self.rgb_image_callback, qos_profile=sensor_qos_profile
|
|
|
|
| 220 |
if max_value <= 20:
|
| 221 |
self.current_image_rgb[y_value, x_value] = [160, 32, 240]
|
| 222 |
|
| 223 |
+
# cv2.imwrite("rgb_image.jpg", self.current_image_rgb)
|
| 224 |
+
result.save("rgb_image.png")
|
| 225 |
|
| 226 |
# For Depth Image
|
| 227 |
+
# for x_value in range(self.depth_image.shape[1]):
|
| 228 |
+
# for y_value in range(self.depth_image.shape[0]):
|
| 229 |
+
# difference_vector = [abs(y_value - int(box_y_center + 50)), abs(x_value - int(box_x_center + 30))]
|
| 230 |
+
# max_value = max(difference_vector[0], difference_vector[1])
|
| 231 |
+
# if max_value <= 20:
|
| 232 |
+
# self.depth_image[y_value, x_value] = 0
|
| 233 |
+
|
| 234 |
+
# cv2.imwrite("depth_image.jpg", self.depth_image)
|
| 235 |
|
| 236 |
if SHOULD_SAVE_IMAGES:
|
| 237 |
print("GOT HERE")
|
requirements.txt
CHANGED
|
@@ -1,3 +1,3 @@
|
|
| 1 |
version https://git-lfs.github.com/spec/v1
|
| 2 |
-
oid sha256:
|
| 3 |
-
size
|
|
|
|
| 1 |
version https://git-lfs.github.com/spec/v1
|
| 2 |
+
oid sha256:84043c7caa3615309a0bbb48fcf899ea15d1e49ea6c461204b49dd6c710d8591
|
| 3 |
+
size 40
|