Ir al contenido

Gu铆a de inicio r谩pido de ROS (Robot Operating System)

ROS Introduction (subtitulado) from Open Robotics on Vimeo.

驴Qu茅 es ROS?

Robot Operating System (ROS) es un marco de c贸digo abierto ampliamente utilizado en la investigaci贸n y la industria rob贸tica. ROS ofrece 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 principales 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 sobre temas o servicios.

  2. Middleware de comunicaci贸n: ROS ofrece una robusta infraestructura de comunicaci贸n que soporta la comunicaci贸n entre procesos y la computaci贸n 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 distintas configuraciones de hardware, lo que facilita la integraci贸n y la experimentaci贸n.

  4. Herramientas y utilidades: ROS incluye un amplio conjunto de herramientas y utilidades de visualizaci贸n, depuraci贸n y simulaci贸n. Por ejemplo, RViz se utiliza para visualizar datos de sensores e informaci贸n sobre el 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 vasto 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 introduciendo nuevas caracter铆sticas 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 frente a ROS 2

Mientras que ROS 1 proporcionaba 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 eficiente.

Mensajes y temas 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 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 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 el prop贸sito de esta gu铆a, nos centraremos en mensajes de Imagen, Profundidad y PointCloud y temas de c谩mara.

Configuraci贸n de Ultralytics YOLO con ROS

Esta gu铆a ha sido probada utilizando este entorno ROS, que es una bifurcaci贸n del repositorio ROS ROSbot. 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 trabajar con el Husarion ROSbot 2 PRO. Los ejemplos de c贸digo proporcionados funcionar谩n en cualquier entorno ROS Noetic/Melodic, incluyendo tanto simulaci贸n como mundo real.

Husarion ROSbot 2 PRO

Instalaci贸n de dependencias

Aparte del entorno ROS, necesitar谩 instalar las siguientes dependencias:

  • Paquete ROS Numpy: Esto es necesario para la conversi贸n r谩pida entre ROS mensajes de imagen y matrices numpy.

    pip install ros_numpy
    
  • Ultralytics paquete:

    pip install ultralytics
    

Utilice Ultralytics con ROS sensor_msgs/Image

En sensor_msgs/Image tipo de mensaje se utiliza habitualmente en ROS para representar datos de imagen. Contiene campos para codificaci贸n, altura, anchura y datos de p铆xeles, lo que lo hace adecuado para transmitir im谩genes capturadas por c谩maras u otros sensores. Los mensajes de imagen se utilizan ampliamente en aplicaciones rob贸ticas para tareas como la percepci贸n visual, detecci贸n de objetosy la navegaci贸n.

Detecci贸n y segmentaci贸n en ROS Gazebo

Uso de la imagen paso a paso

El siguiente fragmento de c贸digo muestra 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, importe las bibliotecas necesarias e instancie dos modelos: uno para segmentaci贸n y uno para detecci贸n. Inicializar 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)

Inicializar 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 mediante 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 la carpeta /camera/color/image_raw y llama a una funci贸n de llamada de retorno por cada nuevo mensaje. Esta funci贸n recibe mensajes de tipo sensor_msgs/Imagelos convierte en una matriz numpy utilizando ros_numpyprocesa las im谩genes con los modelos de YOLO previamente instanciados, 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 resultar complicada debido a la naturaleza distribuida del sistema. Varias herramientas pueden ayudar en este proceso:

  1. rostopic echo <TOPIC-NAME> : Este comando le permite ver los mensajes publicados sobre un tema espec铆fico, ayud谩ndole a inspeccionar el flujo de datos.
  2. rostopic list: Utilice este comando para listar todos los temas disponibles en el sistema ROS, d谩ndole 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 est谩n interconectados los nodos y c贸mo interact煤an.
  4. Para visualizaciones m谩s complejas, como representaciones en 3D, puede utilizar RViz. RViz (ROS Visualization) es una potente herramienta de visualizaci贸n 3D para ROS. Le permite visualizar el estado de su robot y su entorno en tiempo real. Con RViz, puede ver los datos del sensor (por ejemplo. sensors_msgs/Image), los estados del modelo del robot y 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 est谩ndar de ROS tambi茅n incluyen std_msgs/String mensajes. En muchas aplicaciones, no es necesario volver a publicar toda la imagen anotada; en su lugar, s贸lo se necesitan las clases presentes en la vista del robot. El siguiente ejemplo 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 uso

Consideremos 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", "pal茅" y "carretilla elevadora", publica estas clases en la base de datos /ultralytics/detection/classes tema. A continuaci贸n, un sistema de supervisi贸n central puede utilizar esta informaci贸n para realizar un seguimiento del inventario en tiempo real, optimizar la planificaci贸n de la trayectoria 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 las cadenas

Este ejemplo muestra 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 un nuevo tema /ultralytics/detection/classes utilizando std_msgs/String mensajes. La direcci贸n ros_numpy se utiliza para convertir el mensaje ROS Image en 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("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()

Utilice 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 captan el color, las im谩genes de profundidad captan informaci贸n espacial, lo que permite a los robots percibir la estructura tridimensional de su entorno.

Obtenci贸n de im谩genes de profundidad

Las im谩genes de profundidad pueden obtenerse utilizando varios sensores:

  1. C谩maras estereosc贸picas: Utiliza dos c谩maras para calcular la profundidad en funci贸n de la disparidad de im谩genes.
  2. C谩maras de tiempo de vuelo (ToF): Miden el tiempo que tarda la luz en regresar de un objeto.
  3. Sensores de luz estructurada: Proyectar un patr贸n y medir su deformaci贸n en superficies.

Utilizaci贸n de YOLO con im谩genes de profundidad

En ROS, las im谩genes de profundidad se representan mediante el sensor_msgs/Image que incluye campos de codificaci贸n, altura, anchura y datos de p铆xeles. El campo de codificaci贸n de las im谩genes de profundidad suele utilizar 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 suelen utilizarse junto con las im谩genes RGB para proporcionar una visi贸n m谩s completa del entorno.

YOLO permite extraer y combinar informaci贸n de im谩genes RGB y de profundidad. Por ejemplo, YOLO puede detectar objetos en una imagen RGB y utilizar esta detecci贸n para localizar las regiones correspondientes en la imagen de profundidad. Esto permite extraer 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 Uso paso a paso

En este ejemplo, utilizamos YOLO para segmentar una imagen y aplicamos 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. Obteniendo esta informaci贸n de distancia, podemos calcular la distancia entre la c谩mara y el objeto espec铆fico en la escena. Comience importando las librer铆as 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("yolov8m-seg.pt")

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

A continuaci贸n, define una funci贸n callback que procese el mensaje entrante de la imagen de profundidad. 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 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 procesarlos, es importante filtrar estos valores nulos y asignarles un valor de 0. Por 煤ltimo, publica los objetos detectados junto con sus distancias medias a la /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()

Utilice 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 realizar tareas como el mapeo 3D, el reconocimiento de objetos y la localizaci贸n.

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 mediante tecnolog铆as de escaneado 3D. Cada punto de la nube tiene X, Yy Z coordenadas, que corresponden a su posici贸n en el espacio, y tambi茅n puede incluir informaci贸n adicional como el color y la intensidad.

Marco de referencia

Al trabajar con sensor_msgs/PointCloud2es esencial considerar 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 marco de referencia escuchando el /tf_static tema. Sin embargo, dependiendo de los requisitos espec铆ficos de tu aplicaci贸n, puede que necesites convertir la nube de puntos en otro marco de referencia. Esta transformaci贸n puede realizarse utilizando la funci贸n 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 pueden obtenerse utilizando diversos sensores:

  1. LIDAR (Light Detection and Ranging): Utiliza pulsos l谩ser para medir distancias a objetos y crear mapas 3D de alta precisi贸n.
  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.

Utilizaci贸n de YOLO con nubes de puntos

Para integrar YOLO con sensor_msgs/PointCloud2 podemos emplear un m茅todo similar al utilizado para los mapas de profundidad. Aprovechando la informaci贸n de color incrustada en la nube de puntos, podemos extraer una imagen 2D, realizar una 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 utilizar Open3D (pip install open3d), una biblioteca de f谩cil uso Python . Open3D proporciona s贸lidas herramientas para gestionar estructuras de datos de nubes de puntos, visualizarlas y ejecutar operaciones complejas sin problemas. Esta biblioteca puede simplificar considerablemente el proceso y mejorar nuestra capacidad para manipular y analizar nubes de puntos junto con la segmentaci贸n basada en YOLO.

Nubes de puntos Uso paso a paso

Importe las bibliotecas necesarias e instancie 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("yolov8m-seg.pt")

Crear una funci贸n pointcloud2_to_arrayque transforma un sensor_msgs/PointCloud2 en dos matrices numpy. La direcci贸n sensor_msgs/PointCloud2 los mensajes contienen n puntos en funci贸n del width y height de la imagen adquirida. Por ejemplo, una 480 x 640 imagen tendr谩 307,200 puntos. Cada punto incluye tres coordenadas espaciales (xyz) y el color correspondiente en RGB formato. Pueden considerarse dos canales de informaci贸n distintos.

La funci贸n devuelve el xyz coordenadas y RGB 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 clip, m谩s all谩 de la cual los valores se representan como inf (np.inf). Antes de procesarlos, 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铆base a /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 (utilizando la funci贸n pointcloud2_to_array ). Procese la imagen RGB utilizando el modelo YOLO para extraer los 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 tratamiento de la m谩scara es sencillo, ya que se compone de valores binarios, con 1 que indica 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)?

Robot Operating System (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 permite la comunicaci贸n entre nodos mediante mensajes sobre temas o servicios.

驴C贸mo puedo integrar Ultralytics YOLO con ROS para la detecci贸n de objetos en tiempo real?

La integraci贸n de Ultralytics YOLO con ROS implica la configuraci贸n de un entorno ROS y el uso de YOLO para procesar los datos de los sensores. Comience por instalar las dependencias necesarias como ros_numpy y Ultralytics YOLO :

pip install ros_numpy ultralytics

A continuaci贸n, cree un nodo ROS y suscr铆base 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 utilizando 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 , puede 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, suscribirse a un tema de c谩mara y procesar 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 im谩genes RGB, los robots pueden comprender mejor su entorno 3D.

Con YOLO, puede extraer m谩scaras de segmentaci贸n de im谩genes RGB y aplicarlas a im谩genes de profundidad para obtener informaci贸n precisa de 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 a matrices numpy.
  2. Utilice YOLO para segmentar im谩genes RGB.
  3. Aplique la m谩scara de segmentaci贸n a la nube de puntos.

He aqu铆 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 en 3D de objetos segmentados, 煤til para tareas como la navegaci贸n y la manipulaci贸n.

Creado hace 5 meses 鉁忥笍 Actualizado hace 2 meses

Comentarios