Bỏ qua nội dung

Hướng dẫn bắt đầu nhanh ROS (Hệ điều hành Robot)

Giới thiệu về ROS (có chú thích) từ Open Robotics trên Vimeo .

ROS là gì?

Hệ điều hành Robot (ROS) là một khuôn khổ mã nguồn mở được sử dụng rộng rãi trong nghiên cứu và công nghiệp robot. ROS cung cấp một bộ sưu tập các thư viện và công cụ để giúp các nhà phát triển tạo ra các ứng dụng robot. ROS được thiết kế để hoạt động với nhiều nền tảng robot khác nhau, khiến nó trở thành một công cụ linh hoạt và mạnh mẽ cho các nhà nghiên cứu robot.

Các tính năng chính của ROS

  1. Kiến trúc mô-đun : ROS có kiến trúc mô-đun, cho phép các nhà phát triển xây dựng các hệ thống phức tạp bằng cách kết hợp các thành phần nhỏ hơn, có thể tái sử dụng được gọi là các nút . Mỗi nút thường thực hiện một chức năng cụ thể và các nút giao tiếp với nhau bằng cách sử dụng các thông báo qua các chủ đề hoặc dịch vụ .

  2. Phần mềm trung gian truyền thông : ROS cung cấp cơ sở hạ tầng truyền thông mạnh mẽ hỗ trợ truyền thông giữa các quy trình và tính toán phân tán. Điều này đạt được thông qua mô hình đăng ký-xuất bản cho các luồng dữ liệu (chủ đề) và mô hình yêu cầu-trả lời cho các cuộc gọi dịch vụ.

  3. Trừu tượng phần cứng : ROS cung cấp một lớp trừu tượng trên phần cứng, cho phép các nhà phát triển viết mã không phụ thuộc vào thiết bị. Điều này cho phép sử dụng cùng một mã với các thiết lập phần cứng khác nhau, tạo điều kiện tích hợp và thử nghiệm dễ dàng hơn.

  4. Công cụ và tiện ích : ROS đi kèm với một bộ công cụ và tiện ích phong phú để trực quan hóa, gỡ lỗi và mô phỏng. Ví dụ, RViz được sử dụng để trực quan hóa dữ liệu cảm biến và thông tin trạng thái robot, trong khi Gazebo cung cấp một môi trường mô phỏng mạnh mẽ để thử nghiệm các thuật toán và thiết kế robot.

  5. Hệ sinh thái mở rộng : Hệ sinh thái ROS rất rộng lớn và liên tục phát triển, với nhiều gói có sẵn cho các ứng dụng robot khác nhau, bao gồm điều hướng, thao tác, nhận thức, v.v. Cộng đồng tích cực đóng góp vào việc phát triển và duy trì các gói này.

Sự tiến hóa của các phiên bản ROS

Kể từ khi phát triển vào năm 2007, ROS đã phát triển qua nhiều phiên bản , mỗi phiên bản đều giới thiệu các tính năng và cải tiến mới để đáp ứng nhu cầu ngày càng tăng của cộng đồng robot. Quá trình phát triển ROS có thể được phân loại thành hai loạt chính: ROS 1 và ROS 2. Hướng dẫn này tập trung vào phiên bản Hỗ trợ dài hạn (LTS) của ROS 1, được gọi là ROS Noetic Ninjemys, mã cũng sẽ hoạt động với các phiên bản trước đó.

ROS 1 so với ROS 2

Trong khi ROS 1 cung cấp nền tảng vững chắc cho sự phát triển của robot, ROS 2 khắc phục những điểm yếu của nó bằng cách cung cấp:

  • Hiệu suất thời gian thực : Cải thiện hỗ trợ cho các hệ thống thời gian thực và hành vi xác định.
  • Bảo mật : Các tính năng bảo mật nâng cao cho hoạt động an toàn và đáng tin cậy trong nhiều môi trường khác nhau.
  • Khả năng mở rộng : Hỗ trợ tốt hơn cho các hệ thống nhiều robot và triển khai quy mô lớn.
  • Hỗ trợ đa nền tảng : Mở rộng khả năng tương thích với nhiều hệ điều hành khác ngoài Linux, bao gồm Windows và macOS.
  • Giao tiếp linh hoạt : Sử dụng DDS để giao tiếp giữa các quy trình linh hoạt và hiệu quả hơn.

Tin nhắn và chủ đề ROS

Trong ROS, giao tiếp giữa các nút được tạo điều kiện thông qua các thông báochủ đề . Thông báo là một cấu trúc dữ liệu xác định thông tin được trao đổi giữa các nút, trong khi chủ đề là một kênh được đặt tên mà qua đó các thông báo được gửi và nhận. Các nút có thể xuất bản thông báo đến một chủ đề hoặc đăng ký nhận thông báo từ một chủ đề, cho phép chúng giao tiếp với nhau. Mô hình xuất bản-đăng ký này cho phép giao tiếp không đồng bộ và tách rời giữa các nút. Mỗi cảm biến hoặc bộ truyền động trong hệ thống rô bốt thường xuất bản dữ liệu đến một chủ đề, sau đó có thể được các nút khác sử dụng để xử lý hoặc điều khiển. Đối với mục đích của hướng dẫn này, chúng tôi sẽ tập trung vào các thông báo Hình ảnh, Độ sâu và Đám mây điểm và các chủ đề camera.

Thiết lập Ultralytics YOLO với ROS

Hướng dẫn này đã được thử nghiệm bằng cách sử dụng môi trường ROS này , là một nhánh của kho lưu trữ ROSbot ROS . Môi trường này bao gồm Ultralytics YOLO gói, một container Docker để thiết lập dễ dàng, các gói ROS toàn diện và thế giới Gazebo để thử nghiệm nhanh. Nó được thiết kế để hoạt động với Husarion ROSbot 2 PRO . Các ví dụ mã được cung cấp sẽ hoạt động trong bất kỳ môi trường ROS Noetic/Melodic nào, bao gồm cả mô phỏng và thế giới thực.

Husarion ROSbot 2 PRO

Cài đặt phụ thuộc

Ngoài môi trường ROS, bạn sẽ cần phải cài đặt các phụ thuộc sau:

  • Gói ROS Numpy : Gói này cần thiết để chuyển đổi nhanh giữa các thông điệp ROS Image và mảng numpy.

    pip install ros_numpy
    
  • Gói Ultralytics :

    pip install ultralytics
    

Sử dụng Ultralytics với ROS sensor_msgs/Image

Các sensor_msgs/Image loại tin nhắn thường được sử dụng trong ROS để biểu diễn dữ liệu hình ảnh. Nó chứa các trường để mã hóa, chiều cao, chiều rộng và dữ liệu pixel, làm cho nó phù hợp để truyền hình ảnh được chụp bởi máy ảnh hoặc các cảm biến khác. Tin nhắn hình ảnh được sử dụng rộng rãi trong các ứng dụng robot cho các nhiệm vụ như nhận thức thị giác, phát hiện đối tượngvà điều hướng.

Phát hiện và phân đoạn trong ROS Gazebo

Hình ảnh từng bước sử dụng

Đoạn mã sau đây minh họa cách sử dụng Ultralytics YOLO gói với ROS. Trong ví dụ này, chúng tôi đăng ký một chủ đề máy ảnh, xử lý hình ảnh đến bằng cách sử dụng YOLO và công bố các đối tượng được phát hiện tới các chủ đề mới để phát hiệnphân đoạn .

Đầu tiên, nhập các thư viện cần thiết và khởi tạo hai mô hình: một cho phân đoạn và một cho phát hiện. Khởi tạo một nút ROS (có tên ultralytics) để cho phép giao tiếp với ROS master. Để đảm bảo kết nối ổn định, chúng tôi bao gồm một khoảng dừng ngắn, cho nút đủ thời gian để thiết lập kết nối trước khi tiếp tục.

import time

import rospy

from ultralytics import YOLO

detection_model = YOLO("yolov8m.pt")
segmentation_model = YOLO("yolov8m-seg.pt")
rospy.init_node("ultralytics")
time.sleep(1)

Khởi tạo hai chủ đề ROS: một cho phát hiện và một cho phân đoạn. Các chủ đề này sẽ được sử dụng để xuất bản các hình ảnh được chú thích, giúp chúng có thể truy cập được để xử lý thêm. Việc giao tiếp giữa các nút được tạo điều kiện thuận lợi bằng cách sử dụng sensor_msgs/Image tin nhắn.

from sensor_msgs.msg import Image

det_image_pub = rospy.Publisher("/ultralytics/detection/image", Image, queue_size=5)
seg_image_pub = rospy.Publisher("/ultralytics/segmentation/image", Image, queue_size=5)

Cuối cùng, tạo một thuê bao lắng nghe tin nhắn trên /camera/color/image_raw chủ đề và gọi một hàm gọi lại cho mỗi tin nhắn mới. Hàm gọi lại này nhận các tin nhắn có kiểu sensor_msgs/Image, chuyển đổi chúng thành một mảng numpy bằng cách sử dụng ros_numpy, xử lý các hình ảnh với các hình ảnh đã được khởi tạo trước đó YOLO mô hình, chú thích hình ảnh và sau đó xuất bản chúng trở lại các chủ đề tương ứng: /ultralytics/detection/image để phát hiện và /ultralytics/segmentation/image để phân đoạn.

import ros_numpy


def callback(data):
    """Callback function to process image and publish annotated images."""
    array = ros_numpy.numpify(data)
    if det_image_pub.get_num_connections():
        det_result = detection_model(array)
        det_annotated = det_result[0].plot(show=False)
        det_image_pub.publish(ros_numpy.msgify(Image, det_annotated, encoding="rgb8"))

    if seg_image_pub.get_num_connections():
        seg_result = segmentation_model(array)
        seg_annotated = seg_result[0].plot(show=False)
        seg_image_pub.publish(ros_numpy.msgify(Image, seg_annotated, encoding="rgb8"))


rospy.Subscriber("/camera/color/image_raw", Image, callback)

while True:
    rospy.spin()
Mã hoàn chỉnh
import time

import ros_numpy
import rospy
from sensor_msgs.msg import Image

from ultralytics import YOLO

detection_model = YOLO("yolov8m.pt")
segmentation_model = YOLO("yolov8m-seg.pt")
rospy.init_node("ultralytics")
time.sleep(1)

det_image_pub = rospy.Publisher("/ultralytics/detection/image", Image, queue_size=5)
seg_image_pub = rospy.Publisher("/ultralytics/segmentation/image", Image, queue_size=5)


def callback(data):
    """Callback function to process image and publish annotated images."""
    array = ros_numpy.numpify(data)
    if det_image_pub.get_num_connections():
        det_result = detection_model(array)
        det_annotated = det_result[0].plot(show=False)
        det_image_pub.publish(ros_numpy.msgify(Image, det_annotated, encoding="rgb8"))

    if seg_image_pub.get_num_connections():
        seg_result = segmentation_model(array)
        seg_annotated = seg_result[0].plot(show=False)
        seg_image_pub.publish(ros_numpy.msgify(Image, seg_annotated, encoding="rgb8"))


rospy.Subscriber("/camera/color/image_raw", Image, callback)

while True:
    rospy.spin()
Gỡ lỗi

Gỡ lỗi các nút ROS (Hệ điều hành Robot) có thể là một thách thức do bản chất phân tán của hệ thống. Một số công cụ có thể hỗ trợ quá trình này:

  1. rostopic echo <TOPIC-NAME> :Lệnh này cho phép bạn xem các tin nhắn được đăng về một chủ đề cụ thể, giúp bạn kiểm tra luồng dữ liệu.
  2. rostopic list:Sử dụng lệnh này để liệt kê tất cả các chủ đề có sẵn trong hệ thống ROS, cung cấp cho bạn cái nhìn tổng quan về các luồng dữ liệu đang hoạt động.
  3. rqt_graph:Công cụ trực quan hóa này hiển thị biểu đồ giao tiếp giữa các nút, cung cấp thông tin chi tiết về cách các nút được kết nối với nhau và cách chúng tương tác.
  4. Đối với các hình ảnh phức tạp hơn, chẳng hạn như biểu diễn 3D, bạn có thể sử dụng RViz. RViz (ROS Visualization) là một công cụ trực quan hóa 3D mạnh mẽ dành cho ROS. Nó cho phép bạn trực quan hóa trạng thái của robot và môi trường của nó theo thời gian thực. Với RViz, bạn có thể xem dữ liệu cảm biến (ví dụ: sensors_msgs/Image), trạng thái mô hình robot và nhiều loại thông tin khác, giúp bạn dễ dàng gỡ lỗi và hiểu được hành vi của hệ thống robot.

Xuất bản các lớp được phát hiện với std_msgs/String

Các thông báo ROS chuẩn cũng bao gồm std_msgs/String tin nhắn. Trong nhiều ứng dụng, không cần phải xuất bản lại toàn bộ hình ảnh được chú thích; thay vào đó, chỉ cần các lớp có trong chế độ xem của rô-bốt. Ví dụ sau đây minh họa cách sử dụng std_msgs/String tin nhắn để tái bản các lớp đã phát hiện trên /ultralytics/detection/classes chủ đề. Những tin nhắn này nhẹ hơn và cung cấp thông tin cần thiết, khiến chúng có giá trị cho nhiều ứng dụng khác nhau.

Ví dụ sử dụng

Hãy xem xét một robot nhà kho được trang bị camera và vật thể mô hình phát hiện. Thay vì gửi những hình ảnh có chú thích lớn qua mạng, robot có thể công bố danh sách các lớp được phát hiện dưới dạng std_msgs/String tin nhắn. Ví dụ, khi robot phát hiện các đối tượng như "hộp", "pallet" và "xe nâng", nó sẽ xuất bản các lớp này cho /ultralytics/detection/classes chủ đề. Thông tin này sau đó có thể được hệ thống giám sát trung tâm sử dụng để theo dõi hàng tồn kho theo thời gian thực, tối ưu hóa kế hoạch đường đi của robot để tránh chướng ngại vật hoặc kích hoạt các hành động cụ thể như nhặt hộp đã phát hiện. Phương pháp này làm giảm băng thông cần thiết cho giao tiếp và tập trung vào việc truyền dữ liệu quan trọng.

Sử dụng từng bước của String

Ví dụ này minh họa cách sử dụng Ultralytics YOLO gói với ROS. Trong ví dụ này, chúng tôi đăng ký một chủ đề máy ảnh, xử lý hình ảnh đến bằng cách sử dụng YOLO và công bố các đối tượng được phát hiện vào chủ đề mới /ultralytics/detection/classes sử dụng std_msgs/String tin nhắn. Các ros_numpy gói được sử dụng để chuyển đổi tin nhắn ROS Image thành một mảng numpy để xử lý với YOLO .

import time

import ros_numpy
import rospy
from sensor_msgs.msg import Image
from std_msgs.msg import String

from ultralytics import YOLO

detection_model = YOLO("yolov8m.pt")
rospy.init_node("ultralytics")
time.sleep(1)
classes_pub = rospy.Publisher("/ultralytics/detection/classes", String, queue_size=5)


def callback(data):
    """Callback function to process image and publish detected classes."""
    array = ros_numpy.numpify(data)
    if classes_pub.get_num_connections():
        det_result = detection_model(array)
        classes = det_result[0].boxes.cls.cpu().numpy().astype(int)
        names = [det_result[0].names[i] for i in classes]
        classes_pub.publish(String(data=str(names)))


rospy.Subscriber("/camera/color/image_raw", Image, callback)
while True:
    rospy.spin()

Sử dụng Ultralytics với Hình ảnh độ sâu ROS

Ngoài hình ảnh RGB, ROS còn hỗ trợ hình ảnh độ sâu , cung cấp thông tin về khoảng cách của vật thể từ camera. Hình ảnh độ sâu rất quan trọng đối với các ứng dụng robot như tránh chướng ngại vật, lập bản đồ 3D và định vị.

Ảnh độ sâu là ảnh mà mỗi pixel biểu diễn khoảng cách từ máy ảnh đến vật thể. Không giống như ảnh RGB chụp màu, ảnh độ sâu chụp thông tin không gian, cho phép robot nhận biết cấu trúc 3D của môi trường xung quanh.

Lấy hình ảnh độ sâu

Có thể thu được hình ảnh độ sâu bằng nhiều cảm biến khác nhau:

  1. Camera âm thanh nổi : Sử dụng hai camera để tính toán độ sâu dựa trên sự chênh lệch hình ảnh.
  2. Camera thời gian bay (ToF) : Đo thời gian ánh sáng phản xạ trở về từ một vật thể.
  3. Cảm biến ánh sáng có cấu trúc : Chiếu một mẫu hình và đo độ biến dạng của mẫu hình đó trên bề mặt.

Sử dụng YOLO với hình ảnh sâu sắc

Trong ROS, hình ảnh độ sâu được biểu diễn bằng sensor_msgs/Image loại tin nhắn, bao gồm các trường để mã hóa, chiều cao, chiều rộng và dữ liệu pixel. Trường mã hóa cho hình ảnh độ sâu thường sử dụng định dạng như "16UC1", biểu thị số nguyên không dấu 16 bit cho mỗi pixel, trong đó mỗi giá trị biểu thị khoảng cách đến đối tượng. Hình ảnh độ sâu thường được sử dụng kết hợp với hình ảnh RGB để cung cấp chế độ xem toàn diện hơn về môi trường.

Sử dụng YOLO , có thể trích xuất và kết hợp thông tin từ cả hình ảnh RGB và độ sâu. Ví dụ, YOLO có thể phát hiện các vật thể trong một hình ảnh RGB và việc phát hiện này có thể được sử dụng để xác định các vùng tương ứng trong hình ảnh độ sâu. Điều này cho phép trích xuất thông tin độ sâu chính xác cho các vật thể được phát hiện, nâng cao khả năng hiểu môi trường của robot theo ba chiều.

Máy ảnh RGB-D

Khi làm việc với hình ảnh độ sâu, điều quan trọng là phải đảm bảo rằng hình ảnh RGB và độ sâu được căn chỉnh chính xác. Các camera RGB-D, chẳng hạn như dòng Intel RealSense , cung cấp hình ảnh RGB và độ sâu được đồng bộ hóa, giúp kết hợp thông tin từ cả hai nguồn dễ dàng hơn. Nếu sử dụng camera RGB và độ sâu riêng biệt, điều quan trọng là phải hiệu chỉnh chúng để đảm bảo căn chỉnh chính xác.

Sử dụng từng bước theo chiều sâu

Trong ví dụ này, chúng tôi sử dụng YOLO để phân đoạn một hình ảnh và áp dụng mặt nạ đã trích xuất để phân đoạn đối tượng trong hình ảnh độ sâu. Điều này cho phép chúng ta xác định khoảng cách của từng pixel của đối tượng quan tâm từ tâm tiêu cự của máy ảnh. Bằng cách lấy thông tin khoảng cách này, chúng ta có thể tính toán khoảng cách giữa máy ảnh và đối tượng cụ thể trong cảnh. Bắt đầu bằng cách nhập các thư viện cần thiết, tạo một nút ROS và khởi tạo một mô hình phân đoạn và một chủ đề ROS.

import time

import rospy
from std_msgs.msg import String

from ultralytics import YOLO

rospy.init_node("ultralytics")
time.sleep(1)

segmentation_model = YOLO("yolov8m-seg.pt")

classes_pub = rospy.Publisher("/ultralytics/detection/distance", String, queue_size=5)

Tiếp theo, định nghĩa một hàm gọi lại xử lý thông điệp ảnh độ sâu đến. Hàm này chờ thông điệp ảnh độ sâu và ảnh RGB, chuyển đổi chúng thành các mảng numpy và áp dụng mô hình phân đoạn cho ảnh RGB. Sau đó, nó trích xuất mặt nạ phân đoạn cho mỗi đối tượng được phát hiện và tính toán khoảng cách trung bình của đối tượng từ máy ảnh bằng cách sử dụng ảnh độ sâu. Hầu hết các cảm biến đều có khoảng cách tối đa, được gọi là khoảng cách clip, vượt quá khoảng cách này, các giá trị được biểu diễn dưới dạng inf (np.inf). Trước khi xử lý, điều quan trọng là phải lọc ra các giá trị null này và gán cho chúng một giá trị 0Cuối cùng, nó công bố các đối tượng được phát hiện cùng với khoảng cách trung bình của chúng đến /ultralytics/detection/distance đề tài.

import numpy as np
import ros_numpy
from sensor_msgs.msg import Image


def callback(data):
    """Callback function to process depth image and RGB image."""
    image = rospy.wait_for_message("/camera/color/image_raw", Image)
    image = ros_numpy.numpify(image)
    depth = ros_numpy.numpify(data)
    result = segmentation_model(image)

    for index, cls in enumerate(result[0].boxes.cls):
        class_index = int(cls.cpu().numpy())
        name = result[0].names[class_index]
        mask = result[0].masks.data.cpu().numpy()[index, :, :].astype(int)
        obj = depth[mask == 1]
        obj = obj[~np.isnan(obj)]
        avg_distance = np.mean(obj) if len(obj) else np.inf

    classes_pub.publish(String(data=str(all_objects)))


rospy.Subscriber("/camera/depth/image_raw", Image, callback)

while True:
    rospy.spin()
Mã hoàn chỉnh
import time

import numpy as np
import ros_numpy
import rospy
from sensor_msgs.msg import Image
from std_msgs.msg import String

from ultralytics import YOLO

rospy.init_node("ultralytics")
time.sleep(1)

segmentation_model = YOLO("yolov8m-seg.pt")

classes_pub = rospy.Publisher("/ultralytics/detection/distance", String, queue_size=5)


def callback(data):
    """Callback function to process depth image and RGB image."""
    image = rospy.wait_for_message("/camera/color/image_raw", Image)
    image = ros_numpy.numpify(image)
    depth = ros_numpy.numpify(data)
    result = segmentation_model(image)

    for index, cls in enumerate(result[0].boxes.cls):
        class_index = int(cls.cpu().numpy())
        name = result[0].names[class_index]
        mask = result[0].masks.data.cpu().numpy()[index, :, :].astype(int)
        obj = depth[mask == 1]
        obj = obj[~np.isnan(obj)]
        avg_distance = np.mean(obj) if len(obj) else np.inf

    classes_pub.publish(String(data=str(all_objects)))


rospy.Subscriber("/camera/depth/image_raw", Image, callback)

while True:
    rospy.spin()

Sử dụng Ultralytics với ROS sensor_msgs/PointCloud2

Phát hiện và phân đoạn trong ROS Gazebo

Các sensor_msgs/PointCloud2 loại tin nhắn là một cấu trúc dữ liệu được sử dụng trong ROS để biểu diễn dữ liệu đám mây điểm 3D. Kiểu thông báo này là một phần không thể thiếu của các ứng dụng robot, cho phép thực hiện các tác vụ như lập bản đồ 3D, nhận dạng đối tượng và định vị.

Đám mây điểm là tập hợp các điểm dữ liệu được xác định trong hệ tọa độ ba chiều. Các điểm dữ liệu này biểu diễn bề mặt bên ngoài của một vật thể hoặc một cảnh, được chụp thông qua công nghệ quét 3D. Mỗi điểm trong đám mây có X, Y, Và Z tọa độ tương ứng với vị trí của nó trong không gian và cũng có thể bao gồm thông tin bổ sung như màu sắc và cường độ.

Khung tham chiếu

Khi làm việc với sensor_msgs/PointCloud2, điều cần thiết là phải xem xét khung tham chiếu của cảm biến mà dữ liệu đám mây điểm được thu thập. Đám mây điểm ban đầu được ghi lại trong khung tham chiếu của cảm biến. Bạn có thể xác định khung tham chiếu này bằng cách lắng nghe /tf_static chủ đề. Tuy nhiên, tùy thuộc vào yêu cầu ứng dụng cụ thể của bạn, bạn có thể cần chuyển đổi đám mây điểm thành một khung tham chiếu khác. Sự chuyển đổi này có thể đạt được bằng cách sử dụng tf2_ros gói cung cấp các công cụ để quản lý khung tọa độ và chuyển đổi dữ liệu giữa chúng.

Thu thập đám mây điểm

Có thể thu được Đám mây điểm bằng nhiều cảm biến khác nhau:

  1. LIDAR (Phát hiện và đo khoảng cách bằng ánh sáng) : Sử dụng các xung laser để đo khoảng cách đến các vật thể và tạo ra bản đồ 3D có độ chính xác cao.
  2. Camera độ sâu : Ghi lại thông tin độ sâu cho từng điểm ảnh, cho phép tái tạo cảnh 3D.
  3. Camera âm thanh nổi : Sử dụng hai hoặc nhiều camera để thu thập thông tin độ sâu thông qua phép đo tam giác.
  4. Máy quét ánh sáng có cấu trúc : Chiếu một mẫu hình đã biết lên bề mặt và đo độ biến dạng để tính độ sâu.

Sử dụng YOLO với Đám mây điểm

Để tích hợp YOLO với sensor_msgs/PointCloud2 loại tin nhắn, chúng ta có thể sử dụng một phương pháp tương tự như phương pháp được sử dụng cho bản đồ độ sâu. Bằng cách tận dụng thông tin màu được nhúng trong đám mây điểm, chúng ta có thể trích xuất hình ảnh 2D, thực hiện phân đoạn trên hình ảnh này bằng cách sử dụng YOLO và sau đó áp dụng mặt nạ kết quả vào các điểm ba chiều để cô lập đối tượng 3D cần quan tâm.

Để xử lý các đám mây điểm, chúng tôi khuyên bạn nên sử dụng Open3D (pip install open3d), thân thiện với người dùng Python thư viện. Open3D cung cấp các công cụ mạnh mẽ để quản lý các cấu trúc dữ liệu đám mây điểm, trực quan hóa chúng và thực hiện các hoạt động phức tạp một cách liền mạch. Thư viện này có thể đơn giản hóa đáng kể quy trình và nâng cao khả năng thao tác và phân tích đám mây điểm của chúng tôi kết hợp với YOLO phân đoạn dựa trên.

Sử dụng Point Clouds từng bước

Nhập các thư viện cần thiết và khởi tạo YOLO mô hình phân đoạn.

import time

import rospy

from ultralytics import YOLO

rospy.init_node("ultralytics")
time.sleep(1)
segmentation_model = YOLO("yolov8m-seg.pt")

Tạo một hàm pointcloud2_to_array, mà biến đổi một sensor_msgs/PointCloud2 tin nhắn vào hai mảng numpy. sensor_msgs/PointCloud2 tin nhắn chứa n điểm dựa trên widthheight của hình ảnh thu được. Ví dụ, một 480 x 640 hình ảnh sẽ có 307,200 điểm. Mỗi điểm bao gồm ba tọa độ không gian (xyz) và màu tương ứng trong RGB Định dạng. Chúng có thể được coi là hai kênh thông tin riêng biệt.

Hàm trả về xyz tọa độ và RGB các giá trị theo định dạng độ phân giải camera gốc (width x height). Hầu hết các cảm biến đều có khoảng cách tối đa, được gọi là khoảng cách kẹp, vượt quá khoảng cách này, các giá trị được biểu thị dưới dạng inf (np.inf). Trước khi xử lý, điều quan trọng là phải lọc ra các giá trị null này và gán cho chúng một giá trị 0.

import numpy as np
import ros_numpy


def pointcloud2_to_array(pointcloud2: PointCloud2) -> tuple:
    """
    Convert a ROS PointCloud2 message to a numpy array.

    Args:
        pointcloud2 (PointCloud2): the PointCloud2 message

    Returns:
        (tuple): tuple containing (xyz, rgb)
    """
    pc_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud2)
    split = ros_numpy.point_cloud2.split_rgb_field(pc_array)
    rgb = np.stack([split["b"], split["g"], split["r"]], axis=2)
    xyz = ros_numpy.point_cloud2.get_xyz_points(pc_array, remove_nans=False)
    xyz = np.array(xyz).reshape((pointcloud2.height, pointcloud2.width, 3))
    nan_rows = np.isnan(xyz).all(axis=2)
    xyz[nan_rows] = [0, 0, 0]
    rgb[nan_rows] = [0, 0, 0]
    return xyz, rgb

Tiếp theo, đăng ký /camera/depth/points chủ đề để nhận được tin nhắn đám mây điểm và chuyển đổi sensor_msgs/PointCloud2 tin nhắn vào các mảng numpy chứa tọa độ XYZ và giá trị RGB (sử dụng pointcloud2_to_array chức năng). Xử lý hình ảnh RGB bằng cách sử dụng YOLO mô hình để trích xuất các đối tượng phân đoạn. Đối với mỗi đối tượng được phát hiện, trích xuất mặt nạ phân đoạn và áp dụng cho cả hình ảnh RGB và tọa độ XYZ để cô lập đối tượng trong không gian 3D.

Việc xử lý mặt nạ rất đơn giản vì nó bao gồm các giá trị nhị phân, với 1 chỉ ra sự hiện diện của đối tượng và 0 chỉ ra sự vắng mặt. Để áp dụng mặt nạ, chỉ cần nhân các kênh gốc với mặt nạ. Thao tác này sẽ cô lập hiệu quả đối tượng quan tâm trong hình ảnh. Cuối cùng, tạo đối tượng đám mây điểm Open3D và trực quan hóa đối tượng được phân đoạn trong không gian 3D với các màu liên quan.

import sys

import open3d as o3d

ros_cloud = rospy.wait_for_message("/camera/depth/points", PointCloud2)
xyz, rgb = pointcloud2_to_array(ros_cloud)
result = segmentation_model(rgb)

if not len(result[0].boxes.cls):
    print("No objects detected")
    sys.exit()

classes = result[0].boxes.cls.cpu().numpy().astype(int)
for index, class_id in enumerate(classes):
    mask = result[0].masks.data.cpu().numpy()[index, :, :].astype(int)
    mask_expanded = np.stack([mask, mask, mask], axis=2)

    obj_rgb = rgb * mask_expanded
    obj_xyz = xyz * mask_expanded

    pcd = o3d.geometry.PointCloud()
    pcd.points = o3d.utility.Vector3dVector(obj_xyz.reshape((ros_cloud.height * ros_cloud.width, 3)))
    pcd.colors = o3d.utility.Vector3dVector(obj_rgb.reshape((ros_cloud.height * ros_cloud.width, 3)) / 255)
    o3d.visualization.draw_geometries([pcd])
Mã hoàn chỉnh
import sys
import time

import numpy as np
import open3d as o3d
import ros_numpy
import rospy

from ultralytics import YOLO

rospy.init_node("ultralytics")
time.sleep(1)
segmentation_model = YOLO("yolov8m-seg.pt")


def pointcloud2_to_array(pointcloud2: PointCloud2) -> tuple:
    """
    Convert a ROS PointCloud2 message to a numpy array.

    Args:
        pointcloud2 (PointCloud2): the PointCloud2 message

    Returns:
        (tuple): tuple containing (xyz, rgb)
    """
    pc_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud2)
    split = ros_numpy.point_cloud2.split_rgb_field(pc_array)
    rgb = np.stack([split["b"], split["g"], split["r"]], axis=2)
    xyz = ros_numpy.point_cloud2.get_xyz_points(pc_array, remove_nans=False)
    xyz = np.array(xyz).reshape((pointcloud2.height, pointcloud2.width, 3))
    nan_rows = np.isnan(xyz).all(axis=2)
    xyz[nan_rows] = [0, 0, 0]
    rgb[nan_rows] = [0, 0, 0]
    return xyz, rgb


ros_cloud = rospy.wait_for_message("/camera/depth/points", PointCloud2)
xyz, rgb = pointcloud2_to_array(ros_cloud)
result = segmentation_model(rgb)

if not len(result[0].boxes.cls):
    print("No objects detected")
    sys.exit()

classes = result[0].boxes.cls.cpu().numpy().astype(int)
for index, class_id in enumerate(classes):
    mask = result[0].masks.data.cpu().numpy()[index, :, :].astype(int)
    mask_expanded = np.stack([mask, mask, mask], axis=2)

    obj_rgb = rgb * mask_expanded
    obj_xyz = xyz * mask_expanded

    pcd = o3d.geometry.PointCloud()
    pcd.points = o3d.utility.Vector3dVector(obj_xyz.reshape((ros_cloud.height * ros_cloud.width, 3)))
    pcd.colors = o3d.utility.Vector3dVector(obj_rgb.reshape((ros_cloud.height * ros_cloud.width, 3)) / 255)
    o3d.visualization.draw_geometries([pcd])

Phân đoạn đám mây điểm với Ultralytics

CÂU HỎI THƯỜNG GẶP

Hệ điều hành Robot (ROS) là gì?

Hệ điều hành Robot (ROS) là một khuôn khổ mã nguồn mở thường được sử dụng trong robot để giúp các nhà phát triển tạo ra các ứng dụng robot mạnh mẽ. Nó cung cấp một bộ sưu tập các thư viện và công cụ để xây dựng và giao tiếp với các hệ thống robot, cho phép phát triển các ứng dụng phức tạp dễ dàng hơn. ROS hỗ trợ giao tiếp giữa các nút bằng cách sử dụng tin nhắn qua các chủ đề hoặc dịch vụ .

Làm thế nào để tôi tích hợp Ultralytics YOLO với ROS để phát hiện đối tượng theo thời gian thực?

Tích hợp Ultralytics YOLO với ROS liên quan đến việc thiết lập môi trường ROS và sử dụng YOLO để xử lý dữ liệu cảm biến. Bắt đầu bằng cách cài đặt các phụ thuộc cần thiết như ros_numpy Và Ultralytics YOLO :

pip install ros_numpy ultralytics

Tiếp theo, tạo một nút ROS và đăng ký vào một chủ đề hình ảnh để xử lý dữ liệu đến. Sau đây là một ví dụ tối thiểu:

import ros_numpy
import rospy
from sensor_msgs.msg import Image

from ultralytics import YOLO

detection_model = YOLO("yolov8m.pt")
rospy.init_node("ultralytics")
det_image_pub = rospy.Publisher("/ultralytics/detection/image", Image, queue_size=5)


def callback(data):
    array = ros_numpy.numpify(data)
    det_result = detection_model(array)
    det_annotated = det_result[0].plot(show=False)
    det_image_pub.publish(ros_numpy.msgify(Image, det_annotated, encoding="rgb8"))


rospy.Subscriber("/camera/color/image_raw", Image, callback)
rospy.spin()

Chủ đề ROS là gì và chúng được sử dụng như thế nào trong Ultralytics YOLO ?

Chủ đề ROS tạo điều kiện thuận lợi cho việc giao tiếp giữa các nút trong mạng ROS bằng cách sử dụng mô hình đăng ký-xuất bản. Chủ đề là kênh được đặt tên mà các nút sử dụng để gửi và nhận tin nhắn không đồng bộ. Trong bối cảnh Ultralytics YOLO , bạn có thể tạo một nút đăng ký vào một chủ đề hình ảnh, xử lý hình ảnh bằng cách sử dụng YOLO cho các nhiệm vụ như phát hiện hoặc phân đoạn và công bố kết quả cho các chủ đề mới.

Ví dụ, đăng ký chủ đề camera và xử lý hình ảnh đến để phát hiện:

rospy.Subscriber("/camera/color/image_raw", Image, callback)

Tại sao sử dụng hình ảnh độ sâu với Ultralytics YOLO trong ROS?

Hình ảnh độ sâu trong ROS, được biểu diễn bởi sensor_msgs/Image, cung cấp khoảng cách của các vật thể từ máy ảnh, rất quan trọng cho các nhiệm vụ như tránh chướng ngại vật, lập bản đồ 3D và định vị. Bằng cách sử dụng thông tin độ sâu cùng với hình ảnh RGB, robot có thể hiểu rõ hơn về môi trường 3D của chúng.

Với YOLO , bạn có thể trích xuất mặt nạ phân đoạn từ hình ảnh RGB và áp dụng các mặt nạ này vào hình ảnh độ sâu để có được thông tin vật thể 3D chính xác, cải thiện khả năng điều hướng và tương tác của robot với môi trường xung quanh.

Làm thế nào tôi có thể hình dung các đám mây điểm 3D với YOLO trong ROS?

Để hình dung các đám mây điểm 3D trong ROS với YOLO :

  1. Chuyển thành sensor_msgs/PointCloud2 tin nhắn tới mảng numpy.
  2. Sử dụng YOLO để phân đoạn hình ảnh RGB.
  3. Áp dụng mặt nạ phân đoạn vào đám mây điểm.

Sau đây là một ví dụ sử dụng Open3D để trực quan hóa:

import sys

import open3d as o3d
import ros_numpy
import rospy
from sensor_msgs.msg import PointCloud2

from ultralytics import YOLO

rospy.init_node("ultralytics")
segmentation_model = YOLO("yolov8m-seg.pt")


def pointcloud2_to_array(pointcloud2):
    pc_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud2)
    split = ros_numpy.point_cloud2.split_rgb_field(pc_array)
    rgb = np.stack([split["b"], split["g"], split["r"]], axis=2)
    xyz = ros_numpy.point_cloud2.get_xyz_points(pc_array, remove_nans=False)
    xyz = np.array(xyz).reshape((pointcloud2.height, pointcloud2.width, 3))
    return xyz, rgb


ros_cloud = rospy.wait_for_message("/camera/depth/points", PointCloud2)
xyz, rgb = pointcloud2_to_array(ros_cloud)
result = segmentation_model(rgb)

if not len(result[0].boxes.cls):
    print("No objects detected")
    sys.exit()

classes = result[0].boxes.cls.cpu().numpy().astype(int)
for index, class_id in enumerate(classes):
    mask = result[0].masks.data.cpu().numpy()[index, :, :].astype(int)
    mask_expanded = np.stack([mask, mask, mask], axis=2)

    obj_rgb = rgb * mask_expanded
    obj_xyz = xyz * mask_expanded

    pcd = o3d.geometry.PointCloud()
    pcd.points = o3d.utility.Vector3dVector(obj_xyz.reshape((-1, 3)))
    pcd.colors = o3d.utility.Vector3dVector(obj_rgb.reshape((-1, 3)) / 255)
    o3d.visualization.draw_geometries([pcd])

Phương pháp này cung cấp hình ảnh 3D của các đối tượng được phân đoạn, hữu ích cho các tác vụ như điều hướng và thao tác.

📅 Được tạo cách đây 5 tháng ✏️ Đã cập nhật cách đây 2 tháng

Bình luận