Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
24 changes: 14 additions & 10 deletions yolov5_ros/launch/yolov5s_simple.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,22 +7,26 @@
def generate_launch_description():
yolox_ros_share_dir = get_package_share_directory('yolov5_ros')

webcam = launch_ros.actions.Node(
package="v4l2_camera", executable="v4l2_camera_node",
parameters=[
{"image_size": [640,480]},
],
)
#webcam = launch_ros.actions.Node(
# package="v4l2_camera", executable="v4l2_camera_node",
# parameters=[
# {"image_size": [640,480]},
# ],
#)

yolov5_ros = launch_ros.actions.Node(
package="yolov5_ros", executable="yolov5_ros",
parameters=[
{"view_img":False},
{"camera_topic":"camera/mat2image_image2mat"}
],
)

rqt_graph = launch_ros.actions.Node(
package="rqt_graph", executable="rqt_graph",
)
#rqt_graph = launch_ros.actions.Node(
# package="rqt_graph", executable="rqt_graph",
#)

return launch.LaunchDescription([
webcam,
#webcam,
yolov5_ros,
])
3 changes: 1 addition & 2 deletions yolov5_ros/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,7 @@
version='0.2.0',
packages=[package_name],
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/ament_index/resource_index/packages', ['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
(os.path.join('share', package_name), glob('./launch/*.launch.py')),
# (os.path.join('share', package_name), glob('../weights/*.pth'))
Expand Down
48 changes: 27 additions & 21 deletions yolov5_ros/yolov5_ros/main.py
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,6 @@ def __init__(self, weights,
self.line_thickness = line_thickness
self.half = half
self.dnn = dnn

self.s = str()

self.load_model()
Expand Down Expand Up @@ -156,27 +155,27 @@ def image_callback(self, image_raw):
xywh = (xyxy2xywh(torch.tensor(xyxy).view(1, 4)) / gn).view(-1).tolist() # normalized xywh
save_conf = False
line = (cls, *xywh, conf) if save_conf else (cls, *xywh) # label format
if self.view_img: # Add bbox to image
c = int(cls) # integer class
label = f'{self.names[c]} {conf:.2f}'
annotator.box_label(xyxy, label, color=colors(c, True))

# print(xyxy, label)
class_list.append(self.names[c])
confidence_list.append(conf)
# tensor to float
x_min_list.append(xyxy[0].item())
y_min_list.append(xyxy[1].item())
x_max_list.append(xyxy[2].item())
y_max_list.append(xyxy[3].item())
#if self.view_img: # Add bbox to image
c = int(cls) # integer class
label = f'{self.names[c]} {conf:.2f}'
annotator.box_label(xyxy, label, color=colors(c, True))

# print(xyxy, label)
class_list.append(self.names[c])
confidence_list.append(conf)
# tensor to float
x_min_list.append(xyxy[0].item())
y_min_list.append(xyxy[1].item())
x_max_list.append(xyxy[2].item())
y_max_list.append(xyxy[3].item())

# Stream results
im0 = annotator.result()
if self.view_img:
cv2.imshow("yolov5", im0)
cv2.waitKey(1) # 1 millisecond

return class_list, confidence_list, x_min_list, y_min_list, x_max_list, y_max_list
return class_list, confidence_list, x_min_list, y_min_list, x_max_list, y_max_list, im0

class yolov5_ros(Node):
def __init__(self):
Expand All @@ -187,8 +186,7 @@ def __init__(self):
self.pub_bbox = self.create_publisher(BoundingBoxes, 'yolov5/bounding_boxes', 10)
self.pub_image = self.create_publisher(Image, 'yolov5/image_raw', 10)

self.sub_image = self.create_subscription(Image, 'image_raw', self.image_callback,10)


# parameter
FILE = Path(__file__).resolve()
ROOT = FILE.parents[0]
Expand All @@ -210,6 +208,8 @@ def __init__(self):
self.declare_parameter('line_thickness', 2)
self.declare_parameter('half', False)
self.declare_parameter('dnn', False)
self.declare_parameter('camera_topic', 'image_raw')
self.declare_parameter('img_flipped', False)

self.weights = self.get_parameter('weights').value
self.data = self.get_parameter('data').value
Expand All @@ -225,6 +225,9 @@ def __init__(self):
self.line_thickness = self.get_parameter('line_thickness').value
self.half = self.get_parameter('half').value
self.dnn = self.get_parameter('dnn').value
self.camera_topic = self.get_parameter('camera_topic').value

self.sub_image = self.create_subscription(Image, self.camera_topic, self.image_callback,10)

self.yolov5 = yolov5_demo(self.weights,
self.data,
Expand All @@ -239,7 +242,8 @@ def __init__(self):
self.agnostic_nms,
self.line_thickness,
self.half,
self.dnn)
self.dnn
)


def yolovFive2bboxes_msgs(self, bboxes:list, scores:list, cls:list, img_header:Header):
Expand All @@ -265,13 +269,15 @@ def yolovFive2bboxes_msgs(self, bboxes:list, scores:list, cls:list, img_header:H
def image_callback(self, image:Image):
image_raw = self.bridge.imgmsg_to_cv2(image, "bgr8")
# return (class_list, confidence_list, x_min_list, y_min_list, x_max_list, y_max_list)
class_list, confidence_list, x_min_list, y_min_list, x_max_list, y_max_list = self.yolov5.image_callback(image_raw)
class_list, confidence_list, x_min_list, y_min_list, x_max_list, y_max_list, im0 = self.yolov5.image_callback(image_raw)

msg = self.yolovFive2bboxes_msgs(bboxes=[x_min_list, y_min_list, x_max_list, y_max_list], scores=confidence_list, cls=class_list, img_header=image.header)
self.pub_bbox.publish(msg)

self.pub_image.publish(image)

output_img = self.bridge.cv2_to_imgmsg(im0, "bgr8")
self.pub_image.publish(output_img)
#self.pub_image.publish(image)

print("start ==================")
print(class_list, confidence_list, x_min_list, y_min_list, x_max_list, y_max_list)
print("end ====================")
Expand Down
8 changes: 4 additions & 4 deletions yolov5_ros/yolov5_ros/utils/general.py
Original file line number Diff line number Diff line change
Expand Up @@ -373,10 +373,10 @@ def check_imshow():
try:
assert not is_docker(), 'cv2.imshow() is disabled in Docker environments'
assert not is_colab(), 'cv2.imshow() is disabled in Google Colab environments'
cv2.imshow('test', np.zeros((1, 1, 3)))
cv2.waitKey(1)
cv2.destroyAllWindows()
cv2.waitKey(1)
#cv2.imshow('test', np.zeros((1, 1, 3)))
#cv2.waitKey(1)
#cv2.destroyAllWindows()
#cv2.waitKey(1)
return True
except Exception as e:
LOGGER.warning(f'WARNING: Environment does not support cv2.imshow() or PIL Image.show() image displays\n{e}')
Expand Down
14 changes: 8 additions & 6 deletions yolov5_ros/yolov5_ros/utils/plots.py
Original file line number Diff line number Diff line change
Expand Up @@ -105,13 +105,15 @@ def box_label(self, box, label='', color=(128, 128, 128), txt_color=(255, 255, 2
outside = p1[1] - h - 3 >= 0 # label fits outside box
p2 = p1[0] + w, p1[1] - h - 3 if outside else p1[1] + h + 3
cv2.rectangle(self.im, p1, p2, color, -1, cv2.LINE_AA) # filled
text_location = (p1[0], p1[1] - 2 if outside else p1[1] + h + 2)
cv2.putText(self.im,
label, (p1[0], p1[1] - 2 if outside else p1[1] + h + 2),
0,
self.lw / 3,
txt_color,
thickness=tf,
lineType=cv2.LINE_AA)
label, text_location,
0,
self.lw / 3,
txt_color,
thickness=tf,
lineType=cv2.LINE_AA)


def rectangle(self, xy, fill=None, outline=None, width=1):
# Add rectangle to image (PIL-only)
Expand Down