Saltar al contenido

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

Introducción a ROS (subtitulado) from Open Robotics on Vimeo.

¿Qué es ROS?

El Sistema Operativo para Robots (ROS) es un marco de código abierto ampliamente utilizado en la investigación y la industria robóticas. 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. Cada nodo suele realizar 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 sólida infraestructura de comunicación que admite la comunicación entre procesos y la informática distribuida. Esto se consigue mediante un modelo de publicación-suscripción para flujos de datos (temas) y un modelo de solicitud-respuesta para llamadas a servicios.

  3. Abstracción del 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, facilitando la integración y la experimentación.

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

  5. Amplio Ecosistema: El ecosistema ROS es amplio y está en continuo crecimiento, con numerosos paquetes disponibles para distintas aplicaciones robóticas, como navegación, manipulación, percepción y otras. 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 ha introducido nuevas funciones y mejoras para satisfacer las crecientes necesidades de la comunidad robótica. El desarrollo de ROS puede clasificarse en dos series principales: ROS 1 y ROS 2. Esta guía se centra en la versión Long Term Support (LTS) de ROS 1, conocida como ROS Noetic Ninjemys, el código también debería funcionar con versiones anteriores.

ROS 1 vs. ROS 2

Mientras que ROS 1 proporcionó una base sólida para el desarrollo robótico, ROS 2 aborda sus deficiencias ofreciendo:

  • Rendimiento en tiempo real: Soporte mejorado 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.
  • Compatibilidad multiplataforma: Compatibilidad ampliada con varios sistemas operativos además de Linux, incluidos Windows y macOS.
  • Comunicación flexible: Uso de DDS para una comunicación entre procesos más flexible y eficaz.

Mensajes y temas de ROS

En ROS, la comunicación entre nodos se facilita mediante mensajes y temas. Un mensaje es una estructura de datos que define la información intercambiada entre nodos, mientras que un tema es un canal con nombre sobre el que se envían y reciben mensajes. Los nodos pueden publicar mensajes en un tema o suscribirse a los 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 consumir otros nodos para procesarlos o controlarlos. Para los fines de esta guía, nos centraremos en los mensajes de Imagen, Profundidad y PointCloud y en los temas de cámara.

Configuración Ultralytics YOLO con ROS

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

Husarion ROSbot 2 PRO

Instalación de dependencias

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

  • Paquete ROS Numpy: Es necesario para una conversión rápida entre los mensajes ROS Image y las matrices numpy.

    pip install ros_numpy
    
  • Ultralytics paquete:

    pip install ultralytics
    

Uso Ultralytics con ROS sensor_msgs/Image

En sensor_msgs/Image tipo de mensaje 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.

Detección y segmentación en 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 su detección y segmentación.

En primer lugar, importa las bibliotecas necesarias e instala dos modelos: uno para segmentación y uno para 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("yolov8m.pt")
segmentation_model = YOLO("yolov8m-seg.pt")
rospy.init_node("ultralytics")
time.sleep(1)

Inicializa dos temas ROS: uno para detección y uno para segmentación. Estos temas se utilizarán para publicar las imágenes anotadas, haciéndolas accesibles para su posterior procesamiento. La comunicación entre nodos se facilita utilizando sensor_msgs/Image Mensajes.

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)

Por último, cree un suscriptor que escuche los mensajes en el /camera/color/image_raw topic y llama a una función de devolución de llamada para cada nuevo mensaje. Esta función de devolución de llamada recibe mensajes de tipo sensor_msgs/Image, los convierte en una matriz numpy usando ros_numpy, procesa las imágenes con el archivo previamente instanciado YOLO modela, anota las imágenes y, a continuación, las vuelve a publicar 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("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()
Depuración

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

  1. rostopic echo <TOPIC-NAME> : Este comando le permite ver los mensajes publicados sobre un tema específico, lo que le ayuda a inspeccionar el flujo de datos.
  2. rostopic list: Utilice este comando para enumerar todos los temas disponibles en el sistema ROS, lo que le proporciona 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 nodos, proporcionando información sobre cómo los nodos están interconectados y cómo interactúan.
  4. Para visualizaciones más complejas, como representaciones en 3D, puedes utilizar RViz. RViz (Visualización ROS) 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 los datos de los sensores (p. ej. sensors_msgs/Image), los estados del modelo de robot y varios otros tipos de información, lo que facilita la depuración y la comprensión del comportamiento de su sistema robótico.

Publicar clases detectadas con std_msgs/String

Los mensajes ROS estándar también incluyen std_msgs/String Mensajes. En muchas aplicaciones, no es necesario volver a publicar toda la imagen anotada; En su lugar, solo se necesitan las clases presentes en la vista del robot. En el ejemplo siguiente se muestra cómo utilizar std_msgs/String mensajes para volver a publicar las clases detectadas en el /ultralytics/detection/classes tema. Estos mensajes son más ligeros y proporcionan información esencial, lo que los hace valiosos para diversas aplicaciones.

Ejemplo de caso de uso

Considera un robot de almacén equipado con una cámara y un objeto modelo de detección. En lugar de enviar grandes imágenes anotadas a través de la red, el robot puede publicar una lista de clases detectadas como std_msgs/String Mensajes. Por ejemplo, cuando el robot detecta objetos como "caja", "palet" y "carretilla elevadora", publica estas clases en el archivo /ultralytics/detection/classes tema. Esta información puede ser utilizada por un sistema de monitoreo central para rastrear el inventario en tiempo real, optimizar la planificación de la ruta del robot para evitar obstáculos o desencadenar 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 cadenas

En este ejemplo se muestra cómo utilizar la función Ultralytics YOLO paquete con ROS. En este ejemplo, nos suscribimos a un tema de cámara, procesamos la imagen entrante usando YOLOy publique los objetos detectados en un nuevo tema /ultralytics/detection/classes Usando std_msgs/String Mensajes. El ros_numpy se utiliza para convertir el mensaje de imagen ROS en una matriz numpy para procesarla 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("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()

Uso Ultralytics con imágenes de profundidad 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, la cartografía 3D y la localización.

Una imagen de profundidad es una imagen en la que cada píxel representa la distancia de la cámara a 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 estereoscópicas: Utiliza dos cámaras para calcular la profundidad basándote en la disparidad de imágenes.
  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: Proyecta un patrón y mide su deformación sobre superficies.

Usando YOLO con imágenes de profundidad

En ROS, las imágenes de profundidad están representadas por el sensor_msgs/Image Tipo de mensaje, que incluye campos para datos de codificación, altura, anchura y píxeles. El campo de codificación para imágenes de profundidad a menudo usa 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 comúnmente junto con las imágenes RGB para proporcionar una vista más completa del entorno.

Usando 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 se puede utilizar para identificar las regiones correspondientes en la imagen de profundidad. Esto permite la extracción de información precisa sobre la profundidad de los objetos detectados, lo que mejora la capacidad del robot para comprender su entorno en tres dimensiones.

Cámaras RGB-D

Cuando se trabaja 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 RealSense deIntel , proporcionan imágenes RGB y de profundidad sincronizadas, lo que facilita la combinación de la información de ambas fuentes. Si se utilizan cámaras RGB y de profundidad independientes, es fundamental calibrarlas para garantizar una alineación precisa.

Profundidad de uso paso a paso

En este ejemplo, usamos 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 de la escena. Comience importando las bibliotecas necesarias, creando un nodo ROS y creando una instancia de 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("yolov8m-seg.pt")

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

A continuación, defina una función de devolución de llamada que procese el mensaje de imagen de profundidad entrante. La función espera los mensajes de imagen de profundidad e imagen RGB, los convierte en matrices numpy y aplica el modelo de segmentación a la imagen RGB. A continuación, extrae la máscara de segmentación de cada objeto detectado y calcula la distancia media del objeto a la cámara utilizando la imagen de profundidad. La mayoría de los sensores tienen una distancia máxima, conocida como distancia de clip, 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. Por último, publica los objetos detectados junto con sus distancias medias al /ultralytics/detection/distance tema.

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

Uso Ultralytics con ROS sensor_msgs/PointCloud2

Detección y segmentación en ROS Gazebo

En sensor_msgs/PointCloud2 tipo de mensaje es una estructura de datos utilizada en ROS para representar datos de nubes de puntos 3D. Este tipo de mensaje forma parte integral de las aplicaciones robóticas, ya que permite tareas como el mapeado 3D, el reconocimiento de objetos y la localización.

Una nube de puntos es un conjunto 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 X, Yy Z coordenadas, que corresponden a su posición en el espacio, y también pueden incluir información adicional como el color y la intensidad.

Marco de referencia

Al trabajar con sensor_msgs/PointCloud2, es esencial tener en cuenta el marco de referencia del sensor desde el que se adquirieron los datos de la nube de puntos. La nube de puntos se captura inicialmente en el marco de referencia del sensor. Puede determinar este sistema de referencia escuchando el /tf_static tema. Sin embargo, en función de los requisitos específicos de la aplicación, es posible que tenga que convertir la nube de puntos en otro sistema de referencia. Esta transformación se puede lograr utilizando el método tf2_ros , que proporciona herramientas para administrar 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 (Light Detection and Ranging): Uses laser pulses to measure distances to objects and create high-precision 3D maps.
  2. Cámaras de profundidad: Capturan la información de profundidad de cada píxel, lo que permite reconstruir la escena en 3D.
  3. Cámaras estereoscópicas: 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.

Usando YOLO con nubes de puntos

Para integrar YOLO con sensor_msgs/PointCloud2 tipo, podemos emplear un método similar al utilizado para los mapas de profundidad. Al aprovechar la información de color incrustada en la nube de puntos, podemos extraer una imagen 2D, realizar la segmentación de esta imagen usando YOLOy, a continuación, aplique la máscara resultante a los puntos tridimensionales para aislar el objeto 3D de interés.

Para manejar nubes de puntos, se recomienda utilizar Open3D (pip install open3d), un sistema de fácil uso Python biblioteca. Open3D proporciona herramientas sólidas para administrar 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 YOLO-Segmentación basada en la segmentación.

Uso paso a paso de nubes de puntos

Importe las bibliotecas necesarias y cree una instancia de la propiedad YOLO modelo de segmentación.

import time

import rospy

from ultralytics import YOLO

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

Crear una función pointcloud2_to_array, que transforma un sensor_msgs/PointCloud2 mensaje en dos matrices numpy. El sensor_msgs/PointCloud2 Los mensajes contienen n puntos basados en el width y height de la imagen adquirida. Por ejemplo, un 480 x 640 La imagen tendrá 307,200 Puntos. Cada punto incluye tres coordenadas espaciales (xyz) y el color correspondiente en RGB formato. Estos pueden considerarse como dos canales de información separados.

La función devuelve el atributo xyz coordenadas y RGB valores en el formato de la resolución original de la cámara (width x height). La mayoría de los sensores tienen una distancia máxima, conocida como distancia de clip, 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.

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 a la /camera/depth/points para recibir el mensaje de nube de puntos y convertir el sensor_msgs/PointCloud2 en matrices numpy que contienen las coordenadas XYZ y los valores RGB (usando el comando pointcloud2_to_array función). Procese la imagen RGB con el comando YOLO modelo para extraer objetos segmentados. Para cada objeto detectado, extraiga la máscara de segmentación y aplíquela tanto a la imagen RGB como a las coordenadas XYZ para aislar el objeto en el espacio 3D.

El procesamiento de la máscara es sencillo, ya que consta de valores binarios, con 1 indicando la presencia del objeto y 0 indicando la ausencia. Para aplicar la máscara, basta con multiplicar los canales originales por la máscara. Esta operación aísla eficazmente el objeto de interés dentro de la imagen. Por último, cree un objeto de nube de puntos Open3D y visualice 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 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])

Segmentación de nubes de puntos con Ultralytics

PREGUNTAS FRECUENTES

¿Qué es el Sistema Operativo para Robots (ROS)?

El Sistema Operativo para Robots (ROS) es un marco 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 sistemas robóticos e interactuar con ellos, lo que facilita el desarrollo de aplicaciones complejas. ROS admite la comunicación entre nodos mediante mensajes sobre 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 utilizar YOLO para procesar los datos de los 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. He aquí un ejemplo mínimo:

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

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

Los temas ROS facilitan la comunicación entre los nodos de 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, procese las imágenes utilizando YOLO para tareas como la detección o la segmentación, y publique 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?

Imágenes de profundidad en ROS, representadas por sensor_msgs/Imageproporcionan la distancia de los objetos a la cámara, crucial para tareas como la evitación de obstáculos, la cartografía 3D y la localización. En utilizando información de profundidad junto con las imágenes RGB, los robots pueden comprender mejor su entorno 3D.

Con YOLO, puedes extraer máscaras de segmentación de las imágenes RGB y aplicarlas a las 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. Convertir sensor_msgs/PointCloud2 mensajes a matrices numpy.
  2. Utiliza YOLO para segmentar imágenes RGB.
  3. Aplica la máscara de segmentación a la nube de puntos.

Aquí tienes un ejemplo que utiliza 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("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])

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

📅 Created 4 months ago ✏️ Updated 18 days ago

Comentarios