Vai al contenuto

Guida rapida a ROS (Robot Operating System)

Introduzione a ROS (con didascalie) da Open Robotics su Vimeo.

Cos'è ROS?

Il Robot Operating System (ROS) è un framework open source ampiamente utilizzato nella ricerca e nell'industria della robotica. ROS fornisce una raccolta di librerie e strumenti per aiutare gli sviluppatori a creare applicazioni robotiche. ROS è progettato per funzionare con varie piattaforme robotiche, rendendolo uno strumento flessibile e potente per i robotici.

Caratteristiche principali di ROS

  1. Architettura Modulare: ROS ha un'architettura modulare, che consente agli sviluppatori di costruire sistemi complessi combinando componenti più piccoli e riutilizzabili chiamati nodi. Ogni nodo in genere esegue una funzione specifica e i nodi comunicano tra loro utilizzando messaggi su argomenti o servizi.

  2. Middleware di comunicazione: ROS offre una solida infrastruttura di comunicazione che supporta la comunicazione inter-processo e il calcolo distribuito. Ciò si ottiene attraverso un modello publish-subscribe per i flussi di dati (topics) e un modello request-reply per le chiamate di servizio.

  3. Astrazione hardware: ROS fornisce un livello di astrazione sull'hardware, consentendo agli sviluppatori di scrivere codice indipendente dal dispositivo. Ciò consente di utilizzare lo stesso codice con diverse configurazioni hardware, facilitando l'integrazione e la sperimentazione.

  4. Strumenti e utilità: ROS è dotato di un ricco set di strumenti e utilità per la visualizzazione, il debug e la simulazione. Ad esempio, RViz viene utilizzato per visualizzare i dati dei sensori e le informazioni sullo stato del robot, mentre Gazebo fornisce un potente ambiente di simulazione per testare algoritmi e progetti di robot.

  5. Ecosistema esteso: L'ecosistema ROS è vasto e in continua crescita, con numerosi pacchetti disponibili per diverse applicazioni robotiche, tra cui navigazione, manipolazione, percezione e altro ancora. La community contribuisce attivamente allo sviluppo e alla manutenzione di questi pacchetti.

Evoluzione delle versioni di ROS

Dal suo sviluppo nel 2007, ROS si è evoluto attraverso molteplici versioni, ognuna delle quali introduce nuove funzionalità e miglioramenti per soddisfare le crescenti esigenze della comunità robotica. Lo sviluppo di ROS può essere suddiviso in due serie principali: ROS 1 e ROS 2. Questa guida si concentra sulla versione Long Term Support (LTS) di ROS 1, nota come ROS Noetic Ninjemys; il codice dovrebbe funzionare anche con le versioni precedenti.

ROS 1 vs. ROS 2

Mentre ROS 1 ha fornito una solida base per lo sviluppo robotico, ROS 2 affronta le sue carenze offrendo:

  • Prestazioni in tempo reale: Supporto migliorato per sistemi in tempo reale e comportamento deterministico.
  • Sicurezza: Funzionalità di sicurezza avanzate per un funzionamento sicuro e affidabile in vari ambienti.
  • Scalabilità: Migliore supporto per sistemi multi-robot e implementazioni su larga scala.
  • Supporto Multipiattaforma: Compatibilità estesa con vari sistemi operativi oltre a Linux, inclusi Windows e macOS.
  • Comunicazione flessibile: Utilizzo di DDS per una comunicazione inter-processo più flessibile ed efficiente.

Messaggi e argomenti ROS

In ROS, la comunicazione tra i nodi è facilitata tramite messaggi e topic. Un messaggio è una struttura dati che definisce le informazioni scambiate tra i nodi, mentre un topic è un canale denominato su cui i messaggi vengono inviati e ricevuti. I nodi possono pubblicare messaggi su un topic o sottoscrivere messaggi da un topic, consentendo loro di comunicare tra loro. Questo modello publish-subscribe consente la comunicazione asincrona e il disaccoppiamento tra i nodi. Ogni sensore o attuatore in un sistema robotico in genere pubblica dati su un topic, che può quindi essere utilizzato da altri nodi per l'elaborazione o il controllo. Ai fini di questa guida, ci concentreremo sui messaggi Image, Depth e PointCloud e sui topic della telecamera.

Configurazione di Ultralytics YOLO con ROS

Questa guida è stata testata utilizzando questo ambiente ROS, che è un fork del repository ROS ROSbot. Questo ambiente include il pacchetto Ultralytics YOLO, un container Docker per una facile configurazione, pacchetti ROS completi e mondi Gazebo per test rapidi. È progettato per funzionare con Husarion ROSbot 2 PRO. Gli esempi di codice forniti funzioneranno in qualsiasi ambiente ROS Noetic/Melodic, inclusi sia la simulazione che il mondo reale.

Husarion ROSbot 2 PRO

Installazione delle dipendenze

Oltre all'ambiente ROS, sarà necessario installare le seguenti dipendenze:

  • Pacchetto ROS Numpy: Questo è necessario per una conversione rapida tra i messaggi ROS Image e gli array numpy.

    pip install ros_numpy
    
  • Pacchetto Ultralytics:

    pip install ultralytics
    

Utilizza Ultralytics con ROS sensor_msgs/Image

Il sensor_msgs/Image message type è comunemente usato in ROS per rappresentare i dati delle immagini. Contiene campi per la codifica, l'altezza, la larghezza e i dati dei pixel, rendendolo adatto alla trasmissione di immagini acquisite da telecamere o altri sensori. I messaggi di immagine sono ampiamente utilizzati nelle applicazioni robotiche per attività come la percezione visiva, il rilevamento di oggetti, e navigazione.

Detection e segmentazione in ROS Gazebo

Utilizzo passo dopo passo dell'immagine

Il seguente frammento di codice dimostra come utilizzare il pacchetto Ultralytics YOLO con ROS. In questo esempio, ci abboniamo a un topic della telecamera, elaboriamo l'immagine in entrata utilizzando YOLO e pubblichiamo gli oggetti rilevati su nuovi topic per il rilevamento e la segmentazione.

Innanzitutto, importa le librerie necessarie e crea due istanze di modelli: uno per segmentazione e uno per detection. Inizializza un nodo ROS (con il nome ultralytics) per abilitare la comunicazione con il master ROS. Per garantire una connessione stabile, includiamo una breve pausa, dando al nodo il tempo sufficiente per stabilire la connessione prima di procedere.

import time

import rospy

from ultralytics import YOLO

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

Inizializza due topic ROS: uno per detection e uno per segmentazione. Questi argomenti verranno utilizzati per pubblicare le immagini annotate, rendendole accessibili per ulteriori elaborazioni. La comunicazione tra i nodi è facilitata tramite sensor_msgs/Image messages.

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)

Infine, crea un subscriber che ascolti i messaggi sul /camera/color/image_raw topic e richiama una funzione di callback per ogni nuovo messaggio. Questa funzione di callback riceve messaggi di tipo sensor_msgs/Image, li converte in un array numpy usando ros_numpy, elabora le immagini con i modelli YOLO precedentemente istanziati, annota le immagini e quindi le pubblica nuovamente nei rispettivi topic: /ultralytics/detection/image per il rilevamento e /ultralytics/segmentation/image per la segmentazione.

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()
Codice completo
import time

import ros_numpy
import rospy
from sensor_msgs.msg import Image

from ultralytics import YOLO

detection_model = YOLO("yolo11m.pt")
segmentation_model = YOLO("yolo11m-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()
Debug

Il debug dei nodi ROS (Robot Operating System) può essere impegnativo a causa della natura distribuita del sistema. Diversi strumenti possono assistere in questo processo:

  1. rostopic echo <TOPIC-NAME> : Questo comando ti permette di visualizzare i messaggi pubblicati su un topic specifico, aiutandoti a ispezionare il flusso di dati.
  2. rostopic list: Utilizza questo comando per elencare tutti i topic disponibili nel sistema ROS, fornendoti una panoramica dei flussi di dati attivi.
  3. rqt_graph: Questo strumento di visualizzazione mostra il grafo di comunicazione tra i nodi, fornendo informazioni su come i nodi sono interconnessi e su come interagiscono.
  4. Per visualizzazioni più complesse, come le rappresentazioni 3D, puoi utilizzare RViz. RViz (ROS Visualization) è un potente strumento di visualizzazione 3D per ROS. Ti consente di visualizzare lo stato del tuo robot e del suo ambiente in tempo reale. Con RViz, puoi visualizzare i dati dei sensori (ad esempio, sensors_msgs/Image), gli stati del modello del robot e vari altri tipi di informazioni, rendendo più facile il debug e la comprensione del comportamento del tuo sistema robotico.

Pubblica le classi rilevate con std_msgs/String

I messaggi ROS standard includono anche std_msgs/String messages. In molte applicazioni, non è necessario ripubblicare l'intera immagine annotata; invece, sono necessarie solo le classi presenti nella visuale del robot. Il seguente esempio dimostra come utilizzare std_msgs/String messages per ripubblicare le classi rilevate sul /ultralytics/detection/classes topic. Questi messaggi sono più leggeri e forniscono informazioni essenziali, rendendoli preziosi per varie applicazioni.

Esempio di caso d'uso

Considera un robot di magazzino dotato di una telecamera e di un oggetto modello di detection. Invece di inviare grandi immagini annotate sulla rete, il robot può pubblicare un elenco di classi rilevate come std_msgs/String messages. Ad esempio, quando il robot rileva oggetti come "box", "pallet" e "forklift", pubblica queste classi nel /ultralytics/detection/classes topic. Queste informazioni possono quindi essere utilizzate da un sistema di monitoraggio centrale per tracciare l'inventario in tempo reale, ottimizzare la pianificazione del percorso del robot per evitare ostacoli o attivare azioni specifiche come il prelievo di una scatola rilevata. Questo approccio riduce la larghezza di banda richiesta per la comunicazione e si concentra sulla trasmissione di dati critici.

Guida dettagliata all'utilizzo delle stringhe

Questo esempio dimostra come utilizzare il pacchetto Ultralytics YOLO con ROS. In questo esempio, ci si iscrive a un topic della telecamera, si elabora l'immagine in entrata utilizzando YOLO e si pubblicano gli oggetti rilevati in un nuovo topic. /ultralytics/detection/classes utilizzando std_msgs/String messages. Il ros_numpy il pacchetto viene utilizzato per convertire il messaggio ROS Image in un array numpy per l'elaborazione 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("yolo11m.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()

Utilizza Ultralytics con immagini di profondità ROS

Oltre alle immagini RGB, ROS supporta le immagini di profondità, che forniscono informazioni sulla distanza degli oggetti dalla telecamera. Le immagini di profondità sono fondamentali per applicazioni robotiche come l'evitamento di ostacoli, la mappatura 3D e la localizzazione.

Un'immagine di profondità è un'immagine in cui ogni pixel rappresenta la distanza dalla telecamera a un oggetto. A differenza delle immagini RGB che catturano il colore, le immagini di profondità catturano informazioni spaziali, consentendo ai robot di percepire la struttura 3D del loro ambiente.

Ottenere immagini di profondità

Le immagini di profondità possono essere ottenute utilizzando vari sensori:

  1. Telecamere stereo: Utilizza due telecamere per calcolare la profondità in base alla disparità dell'immagine.
  2. Telecamere Time-of-Flight (ToF): Misura il tempo impiegato dalla luce per tornare da un oggetto.
  3. Sensori di luce strutturata: Proietta un modello e misura la sua deformazione sulle superfici.

Utilizzo di YOLO con immagini di profondità

In ROS, le immagini di profondità sono rappresentate da sensor_msgs/Image message type, che include campi per la codifica, l'altezza, la larghezza e i dati dei pixel. Il campo di codifica per le immagini di profondità utilizza spesso un formato come "16UC1", che indica un intero senza segno a 16 bit per pixel, dove ogni valore rappresenta la distanza dall'oggetto. Le immagini di profondità sono comunemente utilizzate insieme alle immagini RGB per fornire una visione più completa dell'ambiente.

Utilizzando YOLO, è possibile estrarre e combinare informazioni sia da immagini RGB che di profondità. Ad esempio, YOLO può rilevare oggetti all'interno di un'immagine RGB e questo rilevamento può essere utilizzato per individuare le regioni corrispondenti nell'immagine di profondità. Ciò consente l'estrazione di informazioni precise sulla profondità degli oggetti rilevati, migliorando la capacità del robot di comprendere il suo ambiente in tre dimensioni.

Telecamere RGB-D

Quando si lavora con immagini di profondità, è essenziale assicurarsi che le immagini RGB e di profondità siano correttamente allineate. Le telecamere RGB-D, come la serie Intel RealSense, forniscono immagini RGB e di profondità sincronizzate, rendendo più facile combinare le informazioni da entrambe le sorgenti. Se si utilizzano telecamere RGB e di profondità separate, è fondamentale calibrarle per garantire un allineamento accurato.

Utilizzo dettagliato passo dopo passo per la stima della profondità

In questo esempio, utilizziamo YOLO per segmentare un'immagine e applicare la maschera estratta per segmentare l'oggetto nell'immagine di profondità. Questo ci permette di determinare la distanza di ogni pixel dell'oggetto di interesse dal centro focale della telecamera. Ottenendo queste informazioni sulla distanza, possiamo calcolare la distanza tra la telecamera e l'oggetto specifico nella scena. Inizia importando le librerie necessarie, creando un nodo ROS e istanziando un modello di segmentazione e un topic 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("yolo11m-seg.pt")

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

Successivamente, definisci una funzione di callback che elabora il messaggio dell'immagine di profondità in entrata. La funzione attende i messaggi dell'immagine di profondità e dell'immagine RGB, li converte in array numpy e applica il modello di segmentazione all'immagine RGB. Quindi estrae la maschera di segmentazione per ogni oggetto rilevato e calcola la distanza media dell'oggetto dalla telecamera utilizzando l'immagine di profondità. La maggior parte dei sensori ha una distanza massima, nota come distanza di clipping, oltre la quale i valori sono rappresentati come inf (np.inf). Prima dell'elaborazione, è importante filtrare questi valori nulli e assegnare loro un valore di 0. Infine, pubblica gli oggetti rilevati insieme alle loro distanze medie dal /ultralytics/detection/distance topic.

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

Utilizza Ultralytics con ROS sensor_msgs/PointCloud2

Detection e segmentazione in ROS Gazebo

Il sensor_msgs/PointCloud2 message type è una struttura dati utilizzata in ROS per rappresentare dati di nuvole di punti 3D. Questo tipo di messaggio è fondamentale per le applicazioni robotiche, consentendo attività come la mappatura 3D, il riconoscimento di oggetti e la localizzazione.

Una nuvola di punti è una raccolta di punti dati definiti all'interno di un sistema di coordinate tridimensionale. Questi punti dati rappresentano la superficie esterna di un oggetto o di una scena, catturata tramite tecnologie di scansione 3D. Ogni punto nella nuvola ha X, Y, e Z coordinate, che corrispondono alla sua posizione nello spazio, e possono anche includere informazioni aggiuntive come colore e intensità.

Frame di riferimento

Quando si lavora con sensor_msgs/PointCloud2, è essenziale considerare il sistema di riferimento del sensore da cui sono stati acquisiti i dati della nuvola di punti. La nuvola di punti viene inizialmente acquisita nel sistema di riferimento del sensore. È possibile determinare questo sistema di riferimento ascoltando il /tf_static topic. Tuttavia, a seconda dei requisiti specifici dell'applicazione, potrebbe essere necessario convertire la nuvola di punti in un altro sistema di riferimento. Questa trasformazione può essere ottenuta utilizzando il tf2_ros package, che fornisce strumenti per la gestione dei sistemi di riferimento e la trasformazione dei dati tra di essi.

Ottenere nuvole di punti

Le nuvole di punti possono essere ottenute utilizzando vari sensori:

  1. LIDAR (Light Detection and Ranging): utilizza impulsi laser per misurare le distanze dagli oggetti e creare mappe 3D ad alta precisione.
  2. Telecamere di profondità: Acquisiscono informazioni sulla profondità per ogni pixel, consentendo la ricostruzione 3D della scena.
  3. Telecamere Stereo: Utilizza due o più telecamere per ottenere informazioni sulla profondità tramite triangolazione.
  4. Scanner a Luce Strutturata: Proietta un modello noto su una superficie e misura la deformazione per calcolare la profondità.

Utilizzo di YOLO con nuvole di punti

Per integrare YOLO con sensor_msgs/PointCloud2 messaggi di tipo, possiamo impiegare un metodo simile a quello utilizzato per le mappe di profondità. Sfruttando le informazioni sul colore incorporate nella nuvola di punti, possiamo estrarre un'immagine 2D, eseguire la segmentazione su questa immagine utilizzando YOLO e quindi applicare la maschera risultante ai punti tridimensionali per isolare l'oggetto 3D di interesse.

Per la gestione di nuvole di punti, consigliamo di utilizzare Open3D (pip install open3d), una libreria python di facile utilizzo. Open3D fornisce strumenti robusti per la gestione delle strutture di dati point cloud, la loro visualizzazione e l'esecuzione di operazioni complesse senza problemi. Questa libreria può semplificare notevolmente il processo e migliorare la nostra capacità di manipolare e analizzare le point cloud in combinazione con la segmentazione basata su YOLO.

Utilizzo passo passo delle nuvole di punti

Importa le librerie necessarie e crea un'istanza del modello YOLO per la segmentazione.

import time

import rospy

from ultralytics import YOLO

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

Crea una funzione pointcloud2_to_array, che trasforma un sensor_msgs/PointCloud2 message in due array numpy. Il sensor_msgs/PointCloud2 messages contengono n punti in base al width e height dell'immagine acquisita. Ad esempio, un 480 x 640 l'immagine avrà 307,200 punti. Ogni punto include tre coordinate spaziali (xyz) e il colore corrispondente in RGB formato. Questi possono essere considerati come due canali di informazione separati.

La funzione restituisce xyz coordinate e RGB valori nel formato della risoluzione originale della fotocamera (width x height). La maggior parte dei sensori ha una distanza massima, nota come distanza di clipping, oltre la quale i valori sono rappresentati come inf (np.inf). Prima dell'elaborazione, è importante filtrare questi valori nulli e assegnare loro un valore di 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

Successivamente, iscriviti al /camera/depth/points topic per ricevere il messaggio della nuvola di punti e convertire il sensor_msgs/PointCloud2 message in array numpy contenenti le coordinate XYZ e i valori RGB (utilizzando il pointcloud2_to_array funzione). Elabora l'immagine RGB utilizzando il modello YOLO per estrarre gli oggetti segmentati. Per ogni oggetto rilevato, estrai la maschera di segmentazione e applicala sia all'immagine RGB sia alle coordinate XYZ per isolare l'oggetto nello spazio 3D.

L'elaborazione della maschera è semplice poiché consiste in valori binari, con 1 che indica la presenza dell'oggetto e 0 che indica l'assenza. Per applicare la maschera, è sufficiente moltiplicare i canali originali per la maschera. Questa operazione isola efficacemente l'oggetto di interesse all'interno dell'immagine. Infine, crea un oggetto point cloud Open3D e visualizza l'oggetto segmentato nello spazio 3D con i colori associati.

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])
Codice 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("yolo11m-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])

Segmentazione di nuvole di punti con Ultralytics

FAQ

Cos'è il Robot Operating System (ROS)?

Il Robot Operating System (ROS) è un framework open source comunemente utilizzato nella robotica per aiutare gli sviluppatori a creare applicazioni robotiche robuste. Fornisce una raccolta di librerie e strumenti per la costruzione e l'interfacciamento con sistemi robotici, consentendo uno sviluppo più semplice di applicazioni complesse. ROS supporta la comunicazione tra i nodi utilizzando messaggi su argomenti o servizi.

Come posso integrare Ultralytics YOLO con ROS per il rilevamento di oggetti in tempo reale?

L'integrazione di Ultralytics YOLO con ROS implica la configurazione di un ambiente ROS e l'utilizzo di YOLO per l'elaborazione dei dati dei sensori. Inizia installando le dipendenze richieste come ros_numpy e Ultralytics YOLO:

pip install ros_numpy ultralytics

Successivamente, crea un nodo ROS e sottoscrivi un topic di immagine per elaborare i dati in entrata. Ecco un esempio minimale:

import ros_numpy
import rospy
from sensor_msgs.msg import Image

from ultralytics import YOLO

detection_model = YOLO("yolo11m.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()

Cosa sono i topic ROS e come vengono utilizzati in Ultralytics YOLO?

I topic ROS facilitano la comunicazione tra i nodi in una rete ROS utilizzando un modello publish-subscribe. Un topic è un canale denominato che i nodi utilizzano per inviare e ricevere messaggi in modo asincrono. Nel contesto di Ultralytics YOLO, puoi fare in modo che un nodo si sottoscriva a un topic di immagini, elabori le immagini utilizzando YOLO per attività come il rilevamento o la segmentazione, e pubblichi i risultati su nuovi topic.

Ad esempio, iscriviti a un topic della telecamera ed elabora l'immagine in entrata per il rilevamento:

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

Perché usare immagini di profondità con Ultralytics YOLO in ROS?

Immagini di profondità in ROS, rappresentate da sensor_msgs/Image, fornisce la distanza degli oggetti dalla telecamera, fondamentale per attività come l'elusione di ostacoli, la mappatura 3D e la localizzazione. Tramite utilizzando informazioni sulla profondità insieme alle immagini RGB, i robot possono comprendere meglio il loro ambiente 3D.

Con YOLO, puoi estrarre maschere di segmentazione da immagini RGB e applicare queste maschere a immagini di profondità per ottenere informazioni precise sugli oggetti 3D, migliorando la capacità del robot di navigare e interagire con l'ambiente circostante.

Come posso visualizzare nuvole di punti 3D con YOLO in ROS?

Per visualizzare nuvole di punti 3D in ROS con YOLO:

  1. Converti sensor_msgs/PointCloud2 messages in array numpy.
  2. Utilizza YOLO per segmentare immagini RGB.
  3. Applica la maschera di segmentazione alla nuvola di punti.

Ecco un esempio che utilizza Open3D per la visualizzazione:

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

Questo approccio fornisce una visualizzazione 3D di oggetti segmentati, utile per attività come la navigazione e la manipolazione in applicazioni di robotica.



📅 Creato 1 anno fa ✏️ Aggiornato 6 giorni fa

Commenti