Guía de inicio rápido de ROS (Robot Operating System)

ROS Introduction (captioned) from Open Robotics on Vimeo.

¿Qué es ROS?

El Robot Operating System (ROS) es un framework de código abierto muy utilizado en la investigación y la industria de la robótica. ROS proporciona una colección de bibliotecas y herramientas para ayudar a los desarrolladores a crear aplicaciones robóticas. ROS está diseñado para funcionar con diversas plataformas robóticas, lo que lo convierte en una herramienta flexible y potente para los roboticistas.

Características clave de ROS

  1. Arquitectura modular: ROS tiene una arquitectura modular que permite a los desarrolladores construir sistemas complejos combinando componentes más pequeños y reutilizables llamados nodos. Normalmente, cada nodo realiza una función específica y los nodos se comunican entre sí mediante mensajes a través de temas o servicios.

  2. Middleware de comunicación: ROS ofrece una infraestructura de comunicación robusta que admite la comunicación entre procesos y la computación distribuida. Esto se logra mediante un modelo de publicación-suscripción para flujos de datos (temas) y un modelo de solicitud-respuesta para llamadas de servicio.

  3. Abstracción de hardware: ROS proporciona una capa de abstracción sobre el hardware, lo que permite a los desarrolladores escribir código independiente del dispositivo. Esto permite utilizar el mismo código con diferentes configuraciones de hardware, lo que facilita la integración y la experimentación.

  4. Herramientas y utilidades: ROS viene con un amplio conjunto de herramientas y utilidades para la visualización, la depuración y la simulación. Por ejemplo, RViz se utiliza para visualizar datos de sensores e información del estado del robot, mientras que Gazebo ofrece un potente entorno de simulación para probar algoritmos y diseños de robots.

  5. Ecosistema extenso: El ecosistema de ROS es vasto y sigue creciendo, con numerosos paquetes disponibles para diferentes aplicaciones robóticas, como la navegación, la manipulación, la percepción y más. La comunidad contribuye activamente al desarrollo y mantenimiento de estos paquetes.

Evolución de las versiones de ROS

Desde su desarrollo en 2007, ROS ha evolucionado a través de múltiples versiones, cada una de las cuales introduce nuevas funciones y mejoras para satisfacer las crecientes necesidades de la comunidad robótica. El desarrollo de ROS se puede clasificar en dos series principales: ROS 1 y ROS 2. Esta guía se centra en la versión de soporte a largo plazo (LTS) de ROS 1, conocida como ROS Noetic Ninjemys, aunque el código también debería funcionar con versiones anteriores.

ROS 1 frente a ROS 2

Aunque ROS 1 proporcionó una base sólida para el desarrollo robótico, ROS 2 soluciona sus carencias ofreciendo:

  • Rendimiento en tiempo real: Mejor soporte para sistemas en tiempo real y comportamiento determinista.
  • Seguridad: Funciones de seguridad mejoradas para un funcionamiento seguro y fiable en diversos entornos.
  • Escalabilidad: Mejor soporte para sistemas multi-robot y despliegues a gran escala.
  • Soporte multiplataforma: Compatibilidad ampliada con varios sistemas operativos más allá de Linux, incluidos Windows y macOS.
  • Comunicación flexible: Uso de DDS para una comunicación entre procesos más flexible y eficiente.

Mensajes y temas de ROS

En ROS, la comunicación entre nodos se facilita a través de mensajes y temas. Un mensaje es una estructura de datos que define la información intercambiada entre los nodos, mientras que un tema es un canal con nombre a través del cual se envían y reciben los mensajes. Los nodos pueden publicar mensajes en un tema o suscribirse a mensajes de un tema, lo que les permite comunicarse entre sí. Este modelo de publicación-suscripción permite la comunicación asíncrona y el desacoplamiento entre nodos. Cada sensor o actuador de un sistema robótico suele publicar datos en un tema, que luego pueden ser consumidos por otros nodos para su procesamiento o control. Para los fines de esta guía, nos centraremos en los mensajes de Imagen, Profundidad y Nube de puntos (PointCloud) y en los temas de cámara.

Configuración de Ultralytics YOLO con ROS

Esta guía se ha probado usando este entorno ROS, que es una bifurcación del repositorio ROSbot ROS. Este entorno incluye el paquete Ultralytics YOLO, un contenedor Docker para una fácil configuración, paquetes ROS completos y mundos Gazebo para pruebas rápidas. Está diseñado para funcionar con el Husarion ROSbot 2 PRO. Los ejemplos de código proporcionados funcionarán en cualquier entorno ROS Noetic/Melodic, tanto en simulación como en el mundo real.

Husarion ROSbot 2 PRO autonomous robot platform

Instalación de dependencias

Además del entorno ROS, necesitarás instalar las siguientes dependencias:

  • Paquete ROS NumPy: Es necesario para la conversión rápida entre mensajes de Imagen de ROS y matrices NumPy.

    pip install ros_numpy
  • Paquete Ultralytics:

    pip install ultralytics

Utiliza Ultralytics con sensor_msgs/Image de ROS

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.

Detection and Segmentation in ROS Gazebo

Uso paso a paso de la imagen

El siguiente fragmento de código demuestra cómo utilizar el paquete Ultralytics YOLO con ROS. En este ejemplo, nos suscribimos a un tema de cámara, procesamos la imagen entrante utilizando YOLO y publicamos los objetos detectados en nuevos temas para la detección y la segmentación.

Primero, importa las bibliotecas necesarias e instancia dos modelos: uno para la segmentación y otro para la detección. Inicializa un nodo ROS (con el nombre ultralytics) para permitir la comunicación con el maestro ROS. Para garantizar una conexión estable, incluimos una breve pausa, dando al nodo tiempo suficiente para establecer la conexión antes de continuar.

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)

Inicializa dos temas ROS: uno para la detección y otro para la segmentación. Estos temas se utilizarán para publicar las imágenes anotadas, haciéndolas accesibles para su posterior procesamiento. La comunicación entre los nodos se facilita mediante mensajes 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)

Finalmente, crea un suscriptor que escuche los mensajes en el tema /camera/color/image_raw y llame a una función de devolución de llamada (callback) por cada mensaje nuevo. Esta función de callback recibe mensajes de tipo sensor_msgs/Image, los convierte en una matriz NumPy usando ros_numpy, procesa las imágenes con los modelos YOLO previamente instanciados, anota las imágenes y luego las publica de nuevo en los temas respectivos: /ultralytics/detection/image para la detección y /ultralytics/segmentation/image para la segmentació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()
Código completo
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()
Depuración

Depurar nodos de ROS (Robot Operating System) puede ser un desafío debido a la naturaleza distribuida del sistema. Varias herramientas pueden ayudar en este proceso:

  1. rostopic echo <TOPIC-NAME> : Este comando te permite ver los mensajes publicados en un tema específico, ayudándote a inspeccionar el flujo de datos.
  2. rostopic list: Usa este comando para listar todos los temas disponibles en el sistema ROS, dándote una visión general de los flujos de datos activos.
  3. rqt_graph: Esta herramienta de visualización muestra el gráfico de comunicación entre los nodos, proporcionando información sobre cómo están interconectados los nodos y cómo interactúan.
  4. Para visualizaciones más complejas, como representaciones en 3D, puedes utilizar RViz. RViz (ROS Visualization) es una potente herramienta de visualización 3D para ROS. Te permite visualizar el estado de tu robot y su entorno en tiempo real. Con RViz, puedes ver datos de sensores (por ejemplo, sensor_msgs/Image), estados del modelo del robot y otros diversos tipos de información, lo que facilita la depuración y la comprensión del comportamiento de tu sistema robótico.

Publicar clases detectadas con 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.

Caso de uso de ejemplo

Considera un robot de almacén equipado con una cámara y un modelo de detección de objetos. En lugar de enviar grandes imágenes anotadas a través de la red, el robot puede publicar una lista de clases detectadas como mensajes std_msgs/String. Por ejemplo, cuando el robot detecta objetos como "caja", "palé" y "carretilla elevadora", publica estas clases en el tema /ultralytics/detection/classes. Esta información puede ser utilizada por un sistema de monitorización central para realizar un seguimiento del inventario en tiempo real, optimizar la planificación de rutas del robot para evitar obstáculos o activar acciones específicas, como recoger una caja detectada. Este enfoque reduce el ancho de banda necesario para la comunicación y se centra en la transmisión de datos críticos.

Uso paso a paso de String

Este ejemplo demuestra cómo utilizar el paquete Ultralytics YOLO con ROS. En este ejemplo, nos suscribimos a un tema de cámara, procesamos la imagen entrante usando YOLO y publicamos los objetos detectados en un nuevo tema /ultralytics/detection/classes usando mensajes std_msgs/String. El paquete ros_numpy se utiliza para convertir el mensaje de Imagen de ROS a una matriz NumPy para su procesamiento con 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()

Utilizar Ultralytics con imágenes de profundidad de ROS

Además de las imágenes RGB, ROS admite imágenes de profundidad, que proporcionan información sobre la distancia de los objetos a la cámara. Las imágenes de profundidad son cruciales para aplicaciones robóticas como la evitación de obstáculos, el mapeo 3D y la localización.

Una imagen de profundidad es una imagen donde cada píxel representa la distancia desde la cámara hasta un objeto. A diferencia de las imágenes RGB que capturan el color, las imágenes de profundidad capturan información espacial, lo que permite a los robots percibir la estructura 3D de su entorno.

Obtención de imágenes de profundidad

Las imágenes de profundidad se pueden obtener utilizando varios sensores:

  1. Cámaras estéreo: Utilizan dos cámaras para calcular la profundidad basándose en la disparidad de la imagen.
  2. Cámaras de tiempo de vuelo (ToF): Miden el tiempo que tarda la luz en volver de un objeto.
  3. Sensores de luz estructurada: Proyectan un patrón y miden su deformación en las superficies.

Uso de YOLO con imágenes de profundidad

En ROS, las imágenes de profundidad están representadas por el tipo de mensaje sensor_msgs/Image, que incluye campos para la codificación, la altura, la anchura y los datos de píxeles. El campo de codificación para las imágenes de profundidad a menudo utiliza un formato como "16UC1", que indica un entero sin signo de 16 bits por píxel, donde cada valor representa la distancia al objeto. Las imágenes de profundidad se utilizan habitualmente junto con las imágenes RGB para proporcionar una visión más completa del entorno.

Utilizando YOLO, es posible extraer y combinar información tanto de imágenes RGB como de profundidad. Por ejemplo, YOLO puede detectar objetos dentro de una imagen RGB, y esta detección puede utilizarse para señalar regiones correspondientes en la imagen de profundidad. Esto permite la extracción de información precisa de profundidad para los objetos detectados, mejorando la capacidad del robot para comprender su entorno en tres dimensiones.

Cámaras RGB-D

Al trabajar con imágenes de profundidad, es esencial asegurarse de que las imágenes RGB y de profundidad estén correctamente alineadas. Las cámaras RGB-D, como la serie Intel RealSense, proporcionan imágenes RGB y de profundidad sincronizadas, lo que facilita la combinación de información de ambas fuentes. Si se utilizan cámaras RGB y de profundidad separadas, es crucial calibrarlas para garantizar una alineación precisa.

Uso paso a paso de la profundidad

En este ejemplo, utilizamos YOLO para segmentar una imagen y aplicar la máscara extraída para segmentar el objeto en la imagen de profundidad. Esto nos permite determinar la distancia de cada píxel del objeto de interés desde el centro focal de la cámara. Al obtener esta información de distancia, podemos calcular la distancia entre la cámara y el objeto específico en la escena. Comienza importando las bibliotecas necesarias, creando un nodo ROS e instanciando un modelo de segmentación y un tema 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)

A continuación, define una función de callback que procese el mensaje de imagen de profundidad entrante. La función espera los mensajes de imagen de profundidad y de imagen RGB, los convierte en matrices NumPy y aplica el modelo de segmentación a la imagen RGB. Luego, extrae la máscara de segmentación para cada objeto detectado y calcula la distancia media del objeto desde la cámara utilizando la imagen de profundidad. La mayoría de los sensores tienen una distancia máxima, conocida como distancia de recorte, más allá de la cual los valores se representan como inf (np.inf). Antes de procesar, es importante filtrar estos valores nulos y asignarles un valor de 0. Finalmente, publica los objetos detectados junto con sus distancias medias en el tema /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()
Código completo
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()

Utiliza Ultralytics con sensor_msgs/PointCloud2 de ROS

Detection and Segmentation in ROS Gazebo

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.

Una nube de puntos es una colección de puntos de datos definidos dentro de un sistema de coordenadas tridimensional. Estos puntos de datos representan la superficie externa de un objeto o una escena, capturada a través de tecnologías de escaneo 3D. Cada punto de la nube tiene coordenadas X, Y y Z, que corresponden a su posición en el espacio, y también puede incluir información adicional como color e intensidad.

Marco de referencia

Al trabajar con sensor_msgs/PointCloud2, es esencial considerar el marco de referencia del sensor desde el cual se adquirieron los datos de la nube de puntos. La nube de puntos se captura inicialmente en el marco de referencia del sensor. Puedes determinar este marco de referencia escuchando el tema /tf_static. Sin embargo, dependiendo de los requisitos específicos de tu aplicación, es posible que necesites convertir la nube de puntos a otro marco de referencia. Esta transformación se puede lograr utilizando el paquete tf2_ros, que proporciona herramientas para gestionar marcos de coordenadas y transformar datos entre ellos.

Obtención de nubes de puntos

Las nubes de puntos se pueden obtener utilizando varios sensores:

  1. LIDAR (detección y alcance de luz): Utiliza pulsos láser para medir distancias a objetos y crear mapas 3D de alta precisión.
  2. Cámaras de profundidad: Capturan información de profundidad para cada píxel, permitiendo la reconstrucción 3D de la escena.
  3. Cámaras estéreo: Utilizan dos o más cámaras para obtener información de profundidad mediante triangulación.
  4. Escáneres de luz estructurada: Proyectan un patrón conocido sobre una superficie y miden la deformación para calcular la profundidad.

Uso de YOLO con nubes de puntos

Para integrar YOLO con mensajes de tipo sensor_msgs/PointCloud2, podemos emplear un método similar al utilizado para los mapas de profundidad. Aprovechando la información de color integrada en la nube de puntos, podemos extraer una imagen 2D, realizar la segmentación en esta imagen utilizando YOLO y luego aplicar la máscara resultante a los puntos tridimensionales para aislar el objeto 3D de interés.

Para manejar nubes de puntos, recomendamos usar Open3D (pip install open3d), una biblioteca de Python fácil de usar. Open3D proporciona herramientas robustas para gestionar estructuras de datos de nubes de puntos, visualizarlas y ejecutar operaciones complejas sin problemas. Esta biblioteca puede simplificar significativamente el proceso y mejorar nuestra capacidad para manipular y analizar nubes de puntos junto con la segmentación basada en YOLO.

Uso paso a paso de nubes de puntos

Importa las bibliotecas necesarias e instancia el modelo YOLO para la segmentación.

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.

The function returns the xyz coordinates and RGB values in the format of the original camera resolution (width x height). Most sensors have a maximum distance, known as the clip distance, beyond which values are represented as inf (np.inf). Before processing, it is important to filter out these null values and assign them a value of 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

A continuación, suscríbete al tema /camera/depth/points para recibir el mensaje de nube de puntos y convertir el mensaje sensor_msgs/PointCloud2 en matrices NumPy que contengan las coordenadas XYZ y los valores RGB (usando la función pointcloud2_to_array). Procesa la imagen RGB utilizando el modelo YOLO para extraer los objetos segmentados. Para cada objeto detectado, extrae la máscara de segmentación y aplícala tanto a la imagen RGB como a las coordenadas XYZ para aislar el objeto en el espacio 3D.

Procesar la máscara es sencillo ya que consiste en valores binarios, con 1 indicando la presencia del objeto y 0 indicando la ausencia. Para aplicar la máscara, simplemente multiplica los canales originales por la máscara. Esta operación aísla eficazmente el objeto de interés dentro de la imagen. Finalmente, crea un objeto de nube de puntos Open3D y visualiza el objeto segmentado en el espacio 3D con los colores asociados.

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])
Código completo
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])

Point Cloud Segmentation with Ultralytics

Preguntas frecuentes

¿Qué es el Robot Operating System (ROS)?

El Robot Operating System (ROS) es un framework de código abierto utilizado habitualmente en robótica para ayudar a los desarrolladores a crear aplicaciones robóticas robustas. Proporciona una colección de bibliotecas y herramientas para construir e interactuar con sistemas robóticos, lo que facilita el desarrollo de aplicaciones complejas. ROS admite la comunicación entre nodos mediante mensajes a través de temas o servicios.

¿Cómo integro Ultralytics YOLO con ROS para la detección de objetos en tiempo real?

Integrar Ultralytics YOLO con ROS implica configurar un entorno ROS y usar YOLO para procesar datos de sensores. Empieza por instalar las dependencias necesarias como ros_numpy y Ultralytics YOLO:

pip install ros_numpy ultralytics

A continuación, crea un nodo ROS y suscríbete a un tema de imagen para procesar los datos entrantes. Aquí tienes un ejemplo mínimo:

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()

¿Qué son los temas de ROS y cómo se utilizan en Ultralytics YOLO?

Los temas de ROS facilitan la comunicación entre nodos en una red ROS mediante un modelo de publicación-suscripción. Un tema es un canal con nombre que los nodos utilizan para enviar y recibir mensajes de forma asíncrona. En el contexto de Ultralytics YOLO, puedes hacer que un nodo se suscriba a un tema de imagen, procesar las imágenes usando YOLO para tareas como detección o segmentación, y publicar los resultados en nuevos temas.

Por ejemplo, suscríbete a un tema de cámara y procesa la imagen entrante para su detección:

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

¿Por qué utilizar imágenes de profundidad con Ultralytics YOLO en ROS?

Las imágenes de profundidad en ROS, representadas por sensor_msgs/Image, proporcionan la distancia de los objetos a la cámara, algo crucial para tareas como la evitación de obstáculos, el mapeo 3D y la localización. Al utilizar información de profundidad junto con imágenes RGB, los robots pueden comprender mejor su entorno 3D.

Con YOLO, puedes extraer máscaras de segmentación de imágenes RGB y aplicar estas máscaras a imágenes de profundidad para obtener información precisa de los objetos en 3D, mejorando la capacidad del robot para navegar e interactuar con su entorno.

¿Cómo puedo visualizar nubes de puntos 3D con YOLO en ROS?

Para visualizar nubes de puntos 3D en ROS con YOLO:

  1. Convierte los mensajes sensor_msgs/PointCloud2 a matrices NumPy.
  2. Usa YOLO para segmentar imágenes RGB.
  3. Aplica la máscara de segmentación a la nube de puntos.

Aquí tienes un ejemplo utilizando Open3D para la visualización:

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])

Este enfoque proporciona una visualización 3D de los objetos segmentados, útil para tareas como la navegación y la manipulación en aplicaciones robóticas.

Comentarios