Краткое руководство по ROS (Robot Operating System)
ROS Introduction (captioned) from Open Robotics on Vimeo.
Что такое ROS?
Robot Operating System (ROS) — это фреймворк с открытым исходным кодом, широко используемый в робототехнических исследованиях и индустрии. ROS предоставляет набор библиотек и инструментов для помощи разработчикам в создании робототехнических приложений. ROS спроектирован для работы с различными роботизированными платформами, что делает его гибким и мощным инструментом для робототехников.
Ключевые особенности ROS
-
Модульная архитектура: ROS имеет модульную архитектуру, позволяющую строить сложные системы путем объединения небольших повторно используемых компонентов, называемых узлами (nodes). Каждый узел обычно выполняет определенную функцию, а узлы обмениваются данными друг с другом с помощью сообщений через топики (topics) или сервисы (services).
-
Коммуникационное связующее ПО: ROS предлагает надежную инфраструктуру связи, поддерживающую межпроцессное взаимодействие и распределенные вычисления. Это достигается за счет модели издатель-подписчик для потоков данных (топиков) и модели запрос-ответ для вызова сервисов.
-
Абстракция оборудования: ROS предоставляет слой абстракции над оборудованием, позволяя тебе писать код, не зависящий от конкретных устройств. Это позволяет использовать один и тот же код с разными аппаратными конфигурациями, облегчая интеграцию и эксперименты.
-
Инструменты и утилиты: ROS поставляется с богатым набором инструментов и утилит для визуализации, отладки и симуляции. Например, RViz используется для визуализации данных датчиков и состояния робота, а Gazebo предоставляет мощную среду симуляции для тестирования алгоритмов и конструкций роботов.
-
Обширная экосистема: Экосистема ROS огромна и постоянно растет, предлагая множество пакетов для различных робототехнических задач, включая навигацию, манипулирование, восприятие и многое другое. Сообщество активно участвует в разработке и поддержке этих пакетов.
Эволюция версий ROS
С момента своей разработки в 2007 году ROS прошел путь через множество версий, каждая из которых внедряла новые функции и улучшения для удовлетворения растущих потребностей робототехнического сообщества. Развитие ROS можно разделить на две основные серии: ROS 1 и ROS 2. В этом руководстве мы сосредоточимся на версии с долгосрочной поддержкой (LTS) ROS 1, известной как ROS Noetic Ninjemys; код должен работать и с более ранними версиями.
ROS 1 против ROS 2
Хотя ROS 1 предоставил прочный фундамент для робототехнической разработки, ROS 2 устраняет его недостатки, предлагая:
- Производительность реального времени: Улучшенная поддержка систем реального времени и детерминированного поведения.
- Безопасность: Усиленные функции безопасности для надежной и стабильной работы в различных средах.
- Масштабируемость: Лучшая поддержка многороботных систем и крупномасштабных развертываний.
- Кроссплатформенная поддержка: Расширенная совместимость с различными операционными системами, помимо Linux, включая Windows и macOS.
- Гибкая связь: Использование DDS для более гибкого и эффективного межпроцессного взаимодействия.
Сообщения и топики ROS
В ROS общение между узлами осуществляется с помощью сообщений и топиков. Сообщение — это структура данных, определяющая информацию, передаваемую между узлами, а топик — это именованный канал, по которому сообщения отправляются и принимаются. Узлы могут публиковать сообщения в топик или подписываться на сообщения из топика, что позволяет им обмениваться данными. Эта модель издатель-подписчик обеспечивает асинхронную коммуникацию и независимость узлов друг от друга. Каждый датчик или исполнительный механизм в робототехнической системе обычно публикует данные в топик, которые затем могут быть использованы другими узлами для обработки или управления. В целях этого руководства мы сосредоточимся на сообщениях Image, Depth, PointCloud и топиках камер.
Настройка Ultralytics YOLO с ROS
Данное руководство было протестировано с использованием этого ROS-окружения, которое является форком репозитория ROSbot ROS. Это окружение включает пакет Ultralytics YOLO, Docker-контейнер для быстрой настройки, полные пакеты ROS и миры Gazebo для оперативного тестирования. Оно разработано для работы с Husarion ROSbot 2 PRO. Приведенные примеры кода будут работать в любой среде ROS Noetic/Melodic, как в симуляции, так и в реальных условиях.
Установка зависимостей
Помимо ROS-окружения, тебе нужно будет установить следующие зависимости:
-
Пакет ROS NumPy: Требуется для быстрого преобразования между ROS-сообщениями Image и массивами NumPy.
pip install ros_numpy -
Пакет Ultralytics:
pip install ultralytics
Используй Ultralytics с ROS sensor_msgs/Image
The sensor_msgs/Image message type is commonly used in ROS for representing image data. It contains fields for encoding, height, width, and pixel data, making it suitable for transmitting images captured by cameras or other sensors. Image messages are widely used in robotic applications for tasks such as visual perception, object detection, and navigation.
Пошаговое использование изображений
Следующий фрагмент кода демонстрирует, как использовать пакет Ultralytics YOLO с ROS. В этом примере мы подписываемся на топик камеры, обрабатываем входящее изображение с помощью YOLO и публикуем обнаруженные объекты в новые топики для детектирования и сегментации.
Сначала импортируй необходимые библиотеки и создай экземпляры двух моделей: одну для сегментации и одну для детектирования. Инициализируй ROS-узел (с именем ultralytics), чтобы включить обмен данными с ROS-мастером. Для обеспечения стабильного соединения мы включаем небольшую паузу, давая узлу достаточно времени для установки связи перед продолжением.
import time
import rospy
from ultralytics import YOLO
detection_model = YOLO("yolo26m.pt")
segmentation_model = YOLO("yolo26m-seg.pt")
rospy.init_node("ultralytics")
time.sleep(1)Инициализируй два ROS-топика: один для детектирования и один для сегментации. Эти топики будут использоваться для публикации аннотированных изображений, делая их доступными для дальнейшей обработки. Общение между узлами осуществляется с помощью сообщений sensor_msgs/Image.
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)Наконец, создай подписчик, который прослушивает сообщения в топике /camera/color/image_raw и вызывает функцию обратного вызова для каждого нового сообщения. Эта функция обратного вызова получает сообщения типа sensor_msgs/Image, преобразует их в массив NumPy с помощью ros_numpy, обрабатывает изображения с помощью ранее созданных моделей YOLO, аннотирует их, а затем публикует обратно в соответствующие топики: /ultralytics/detection/image для детектирования и /ultralytics/segmentation/image для сегментации.
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()Полный код
import time
import ros_numpy
import rospy
from sensor_msgs.msg import Image
from ultralytics import YOLO
detection_model = YOLO("yolo26m.pt")
segmentation_model = YOLO("yolo26m-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()Отладка
Отладка узлов ROS (Robot Operating System) может быть сложной из-за распределенной природы системы. Несколько инструментов могут помочь тебе в этом процессе:
rostopic echo <TOPIC-NAME>: Эта команда позволяет просматривать сообщения, публикуемые в конкретном топике, помогая тебе проверять поток данных.rostopic list: Используй эту команду для вывода списка всех доступных топиков в системе ROS, что даст тебе обзор активных потоков данных.rqt_graph: Этот инструмент визуализации отображает граф коммуникаций между узлами, предоставляя представление о том, как узлы соединены и как они взаимодействуют.- Для более сложных визуализаций, таких как 3D-представления, ты можешь использовать RViz. RViz (ROS Visualization) — это мощный инструмент 3D-визуализации для ROS. Он позволяет визуализировать состояние твоего робота и его окружения в реальном времени. С помощью RViz ты можешь просматривать данные сенсоров (например,
sensor_msgs/Image), состояния модели робота и различные другие типы информации, что облегчает отладку и понимание поведения твоей робототехнической системы.
Публикация обнаруженных классов с помощью std_msgs/String
Standard ROS messages also include std_msgs/String messages. In many applications, it is not necessary to republish the entire annotated image; instead, only the classes present in the robot's view are needed. The following example demonstrates how to use std_msgs/String messages to republish the detected classes on the /ultralytics/detection/classes topic. These messages are more lightweight and provide essential information, making them valuable for various applications.
Пример использования
Представь складского робота, оснащенного камерой и моделью детектирования. Вместо отправки больших аннотированных изображений по сети, робот может публиковать список обнаруженных классов как сообщения std_msgs/String. Например, когда робот обнаруживает такие объекты, как «коробка», «поддон» и «погрузчик», он публикует эти классы в топик /ultralytics/detection/classes. Эта информация затем может быть использована центральной системой мониторинга для отслеживания инвентаря в реальном времени, оптимизации планирования пути робота для объезда препятствий или запуска специфических действий, например, подбора обнаруженной коробки. Такой подход снижает пропускную способность, необходимую для связи, и фокусируется на передаче критически важных данных.
Пошаговое использование строк
Этот пример демонстрирует, как использовать пакет Ultralytics YOLO с ROS. В этом примере мы подписываемся на топик камеры, обрабатываем входящее изображение с помощью YOLO и публикуем обнаруженные объекты в новый топик /ultralytics/detection/classes с использованием сообщений std_msgs/String. Пакет ros_numpy используется для преобразования ROS-сообщения Image в массив NumPy для обработки с помощью 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("yolo26m.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()Использование Ultralytics с картами глубины в ROS
Помимо RGB-изображений, ROS поддерживает карты глубины, которые предоставляют информацию о расстоянии до объектов от камеры. Карты глубины критически важны для робототехнических задач, таких как обход препятствий, 3D-картирование и локализация.
Карта глубины — это изображение, где каждый пиксель представляет расстояние от камеры до объекта. В отличие от RGB-изображений, которые захватывают цвет, карты глубины захватывают пространственную информацию, позволяя роботам воспринимать 3D-структуру своего окружения.
Карты глубины могут быть получены с помощью различных сенсоров:
- Стереокамеры: Используют две камеры для вычисления глубины на основе диспаратности изображений.
- Time-of-Flight (ToF) камеры: Измеряют время, за которое свет возвращается от объекта.
- Датчики структурированного света: Проецируют узор и измеряют его деформацию на поверхностях.
Использование YOLO с картами глубины
В ROS карты глубины представлены типом сообщения sensor_msgs/Image, который включает поля кодировки, высоты, ширины и данных пикселей. Поле кодировки для карт глубины часто использует формат вроде «16UC1», указывающий на 16-битное целое число без знака на пиксель, где каждое значение представляет расстояние до объекта. Карты глубины часто используются вместе с RGB-изображениями для получения более полного представления об окружении.
Используя YOLO, можно извлекать и объединять информацию как из RGB-изображений, так и из карт глубины. Например, YOLO может обнаруживать объекты на RGB-изображении, и это обнаружение может быть использовано для определения соответствующих областей на карте глубины. Это позволяет извлекать точную информацию о глубине для обнаруженных объектов, улучшая способность робота понимать свое окружение в трех измерениях.
При работе с картами глубины важно обеспечить правильное совмещение RGB и карт глубины. RGB-D камеры, такие как серия Intel RealSense, предоставляют синхронизированные RGB-изображения и карты глубины, что упрощает объединение информации из обоих источников. Если используются отдельные RGB-камеры и камеры глубины, крайне важно откалибровать их для обеспечения точного совмещения.
Пошаговое использование глубины
В этом примере мы используем YOLO для сегментации изображения и применяем извлеченную маску для сегментации объекта на карте глубины. Это позволяет нам определить расстояние каждого пикселя интересующего объекта от фокального центра камеры. Получив эту информацию о расстоянии, мы можем вычислить расстояние между камерой и конкретным объектом в сцене. Начни с импорта необходимых библиотек, создания ROS-узла и создания экземпляров модели сегментации и 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("yolo26m-seg.pt")
classes_pub = rospy.Publisher("/ultralytics/detection/distance", String, queue_size=5)Затем определи функцию обратного вызова, которая обрабатывает входящее сообщение карты глубины. Функция ждет сообщения с картой глубины и RGB-изображением, преобразует их в массивы NumPy и применяет модель сегментации к RGB-изображению. Затем она извлекает маску сегментации для каждого обнаруженного объекта и вычисляет среднее расстояние объекта от камеры с помощью карты глубины. Большинство сенсоров имеют максимальное расстояние, известное как дистанция отсечения (clip distance), за пределами которой значения представлены как inf (np.inf). Перед обработкой важно отфильтровать эти нулевые значения и присвоить им значение 0. Наконец, она публикует обнаруженные объекты вместе с их средними расстояниями в топик /ultralytics/detection/distance.
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)
all_objects = []
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
all_objects.append(f"{name}: {avg_distance:.2f}m")
classes_pub.publish(String(data=str(all_objects)))
rospy.Subscriber("/camera/depth/image_raw", Image, callback)
while True:
rospy.spin()Полный код
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("yolo26m-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)
all_objects = []
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
all_objects.append(f"{name}: {avg_distance:.2f}m")
classes_pub.publish(String(data=str(all_objects)))
rospy.Subscriber("/camera/depth/image_raw", Image, callback)
while True:
rospy.spin()Использование Ultralytics с ROS sensor_msgs/PointCloud2
The sensor_msgs/PointCloud2 message type is a data structure used in ROS to represent 3D point cloud data. This message type is integral to robotic applications, enabling tasks such as 3D mapping, object recognition, and localization.
Облако точек — это коллекция точек данных, определенных в трехмерной системе координат. Эти точки данных представляют внешнюю поверхность объекта или сцены, захваченную с помощью технологий 3D-сканирования. Каждая точка в облаке имеет координаты X, Y и Z, которые соответствуют ее положению в пространстве, и может также включать дополнительную информацию, такую как цвет и интенсивность.
При работе с sensor_msgs/PointCloud2 важно учитывать систему координат сенсора, от которого были получены данные облака точек. Облако точек изначально захватывается в системе координат сенсора. Ты можешь определить эту систему координат, прослушивая топик /tf_static. Однако, в зависимости от твоих конкретных требований к приложению, тебе может потребоваться преобразовать облако точек в другую систему координат. Это преобразование можно выполнить с помощью пакета tf2_ros, который предоставляет инструменты для управления координатными фреймами и трансформации данных между ними.
Облака точек могут быть получены с помощью различных сенсоров:
- LIDAR (Light Detection and Ranging): Использует лазерные импульсы для измерения расстояний до объектов и создания 3D-карт высокой точности.
- Камеры глубины: Захватывают информацию о глубине для каждого пикселя, позволяя производить 3D-реконструкцию сцены.
- Стереокамеры: Используют две или более камер для получения информации о глубине посредством триангуляции.
- Сканеры структурированного света: Проецируют известный узор на поверхность и измеряют его деформацию для вычисления глубины.
Использование YOLO с облаками точек
Чтобы интегрировать YOLO с сообщениями типа sensor_msgs/PointCloud2, мы можем применить метод, похожий на тот, что используется для карт глубины. Используя информацию о цвете, встроенную в облако точек, мы можем извлечь 2D-изображение, выполнить сегментацию на этом изображении с помощью YOLO, а затем применить полученную маску к трехмерным точкам, чтобы изолировать 3D-объект, который тебя интересует.
Для работы с облаками точек мы рекомендуем использовать Open3D (pip install open3d) — удобную библиотеку на Python. Open3D предоставляет мощные инструменты для управления структурами данных облаков точек, их визуализации и беспрепятственного выполнения сложных операций. Эта библиотека может значительно упростить процесс и расширить твои возможности по манипулированию и анализу облаков точек в сочетании с сегментацией на основе YOLO.
Пошаговое использование облаков точек
Импортируй необходимые библиотеки и создай экземпляр модели YOLO для сегментации.
import time
import rospy
from ultralytics import YOLO
rospy.init_node("ultralytics")
time.sleep(1)
segmentation_model = YOLO("yolo26m-seg.pt")Create a function pointcloud2_to_array, which transforms a sensor_msgs/PointCloud2 message into two NumPy arrays. The sensor_msgs/PointCloud2 messages contain n points based on the width and height of the acquired image. For instance, a 480 x 640 image will have 307,200 points. Each point includes three spatial coordinates (xyz) and the corresponding color in RGB format. These can be considered as two separate channels of information.
Функция возвращает координаты xyz и значения RGB в формате исходного разрешения камеры (width x height). Большинство сенсоров имеют максимальное расстояние, известное как дистанция отсечения, за пределами которой значения представлены как inf (np.inf). Перед обработкой важно отфильтровать эти нулевые значения и присвоить им значение 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Затем подпишись на топик /camera/depth/points, чтобы получить сообщение облака точек, и преобразуй сообщение sensor_msgs/PointCloud2 в массивы NumPy, содержащие координаты XYZ и значения RGB (используя функцию pointcloud2_to_array). Обработай RGB-изображение с помощью модели YOLO для извлечения сегментированных объектов. Для каждого обнаруженного объекта извлеки маску сегментации и примени ее как к RGB-изображению, так и к координатам XYZ, чтобы изолировать объект в 3D-пространстве.
Обработка маски проста, так как она состоит из бинарных значений, где 1 указывает на присутствие объекта, а 0 — на его отсутствие. Чтобы применить маску, просто умножь исходные каналы на маску. Эта операция эффективно изолирует интересующий объект в пределах изображения. Наконец, создай объект облака точек Open3D и визуализируй сегментированный объект в 3D-пространстве с соответствующими цветами.
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])Полный код
import sys
import time
import numpy as np
import open3d as o3d
import ros_numpy
import rospy
from sensor_msgs.msg import PointCloud2
from ultralytics import YOLO
rospy.init_node("ultralytics")
time.sleep(1)
segmentation_model = YOLO("yolo26m-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])
Часто задаваемые вопросы (FAQ)
Что такое Robot Operating System (ROS)?
Robot Operating System (ROS) — это фреймворк с открытым исходным кодом, обычно используемый в робототехнике, чтобы помочь разработчикам создавать надежные приложения для роботов. Он предоставляет набор библиотек и инструментов для сборки и взаимодействия с робототехническими системами, упрощая разработку сложных приложений. ROS поддерживает связь между узлами с использованием сообщений через топики или сервисы.
Как мне интегрировать Ultralytics YOLO с ROS для обнаружения объектов в реальном времени?
Интеграция Ultralytics YOLO с ROS включает настройку среды ROS и использование YOLO для обработки данных сенсоров. Начни с установки необходимых зависимостей, таких как ros_numpy и Ultralytics YOLO:
pip install ros_numpy ultralyticsЗатем создай узел ROS и подпишись на топик изображения для обработки входящих данных. Вот минимальный пример:
import ros_numpy
import rospy
from sensor_msgs.msg import Image
from ultralytics import YOLO
detection_model = YOLO("yolo26m.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()Что такое топики ROS и как они используются в Ultralytics YOLO?
Топики ROS облегчают связь между узлами в сети ROS, используя модель издатель-подписчик. Топик — это именованный канал, который узлы используют для асинхронной отправки и получения сообщений. В контексте Ultralytics YOLO ты можешь заставить узел подписаться на топик изображения, обработать изображения с помощью YOLO для таких задач, как детектирование или сегментация, и опубликовать результаты в новые топики.
Например, подпишись на топик камеры и обработай входящее изображение для детектирования:
rospy.Subscriber("/camera/color/image_raw", Image, callback)Зачем использовать карты глубины с Ultralytics YOLO в ROS?
Карты глубины в ROS, представленные как sensor_msgs/Image, предоставляют расстояние до объектов от камеры, что важно для таких задач, как обход препятствий, 3D-картирование и локализация. Используя информацию о глубине вместе с RGB-изображениями, роботы могут лучше понимать свое 3D-окружение.
С помощью YOLO ты можешь извлекать маски сегментации из RGB-изображений и применять эти маски к картам глубины, чтобы получить точную 3D-информацию об объектах, улучшая способность робота перемещаться и взаимодействовать с окружением.
Как я могу визуализировать 3D-облака точек с YOLO в ROS?
Чтобы визуализировать 3D-облака точек в ROS с YOLO:
- Преобразуй сообщения
sensor_msgs/PointCloud2в массивы NumPy. - Используй YOLO для сегментации RGB-изображений.
- Примени маску сегментации к облаку точек.
Вот пример с использованием Open3D для визуализации:
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("yolo26m-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])Этот подход обеспечивает 3D-визуализацию сегментированных объектов, полезную для таких задач, как навигация и манипулирование в робототехнических приложениях.