Guida rapida a ROS (Robot Operating System)
ROS Introduction (captioned) from Open Robotics on Vimeo.
Che cos'è ROS?
Il Robot Operating System (ROS) è un framework open source ampiamente utilizzato nella ricerca e nell'industria robotica. ROS fornisce una raccolta di librerie e strumenti per aiutare gli sviluppatori a creare applicazioni robotiche. ROS è progettato per funzionare con diverse piattaforme robotiche, rendendolo uno strumento flessibile e potente per i roboticisti.
Caratteristiche principali di ROS
-
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 svolge solitamente una funzione specifica e i nodi comunicano tra loro utilizzando messaggi tramite argomenti o servizi.
-
Middleware di comunicazione: ROS offre un'infrastruttura di comunicazione robusta che supporta la comunicazione tra processi e il calcolo distribuito. Ciò si ottiene attraverso un modello publish-subscribe per i flussi di dati (argomenti) e un modello request-reply per le chiamate di servizio.
-
Astrazione hardware: ROS fornisce un livello di astrazione sull'hardware, consentendo agli sviluppatori di scrivere codice agnostico rispetto al dispositivo. Ciò permette di utilizzare lo stesso codice con configurazioni hardware diverse, facilitando l'integrazione e la sperimentazione.
-
Strumenti e utilità: ROS viene fornito con una ricca serie 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 design di robot.
-
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 comunità contribuisce attivamente allo sviluppo e alla manutenzione di questi pacchetti.
Evoluzione delle versioni di ROS
Dal suo sviluppo nel 2007, ROS si è evoluto attraverso versioni multiple, ognuna delle quali ha introdotto 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 ne affronta le 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 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 argomenti. Un messaggio è una struttura dati che definisce le informazioni scambiate tra i nodi, mentre un argomento è un canale denominato attraverso il quale i messaggi vengono inviati e ricevuti. I nodi possono pubblicare messaggi su un argomento o sottoscriversi a messaggi da un argomento, consentendo loro di comunicare tra loro. Questo modello publish-subscribe consente una comunicazione asincrona e il disaccoppiamento tra i nodi. Ogni sensore o attuatore in un sistema robotico pubblica tipicamente dati su un argomento, che può poi essere consumato da altri nodi per l'elaborazione o il controllo. Ai fini di questa guida, ci concentreremo sui messaggi Image, Depth e PointCloud e sugli argomenti relativi alle telecamere.
Configurazione di Ultralytics YOLO con ROS
Questa guida è stata testata utilizzando questo ambiente ROS, che è un fork del repository ROSbot ROS. Questo ambiente include il pacchetto Ultralytics YOLO, un container Docker per una configurazione semplice, 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, sia in simulazione che nel mondo reale.
Installazione delle dipendenze
Oltre all'ambiente ROS, dovrai installare le seguenti dipendenze:
-
Pacchetto ROS NumPy: necessario per una rapida conversione tra messaggi ROS Image e array NumPy.
pip install ros_numpy -
Pacchetto Ultralytics:
pip install ultralytics
Usa Ultralytics con sensor_msgs/Image di ROS
The sensor_msgs/Image message type is commonly used in ROS for representing image data. It contains fields for encoding, height, width, and pixel data, making it suitable for transmitting images captured by cameras or other sensors. Image messages are widely used in robotic applications for tasks such as visual perception, object detection, and navigation.
Utilizzo dell'immagine passo dopo passo
Il seguente frammento di codice mostra come utilizzare il pacchetto Ultralytics YOLO con ROS. In questo esempio, ci sottoscriviamo a un argomento della telecamera, elaboriamo l'immagine in arrivo usando YOLO e pubblichiamo gli oggetti rilevati su nuovi argomenti per rilevamento e segmentazione.
Innanzitutto, importa le librerie necessarie e crea due modelli: uno per la segmentazione e uno per il rilevamento. 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 tempo sufficiente per stabilire la connessione prima di procedere.
import time
import rospy
from ultralytics import YOLO
detection_model = YOLO("yolo26m.pt")
segmentation_model = YOLO("yolo26m-seg.pt")
rospy.init_node("ultralytics")
time.sleep(1)Inizializza due argomenti ROS: uno per il rilevamento e uno per la segmentazione. Questi argomenti verranno utilizzati per pubblicare le immagini annotate, rendendole accessibili per un'ulteriore elaborazione. La comunicazione tra i nodi è facilitata utilizzando messaggi sensor_msgs/Image.
from sensor_msgs.msg import Image
det_image_pub = rospy.Publisher("/ultralytics/detection/image", Image, queue_size=5)
seg_image_pub = rospy.Publisher("/ultralytics/segmentation/image", Image, queue_size=5)Infine, crea un sottoscrittore che ascolta i messaggi sull'argomento /camera/color/image_raw e chiama 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 poi le pubblica di nuovo nei rispettivi argomenti: /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("yolo26m.pt")
segmentation_model = YOLO("yolo26m-seg.pt")
rospy.init_node("ultralytics")
time.sleep(1)
det_image_pub = rospy.Publisher("/ultralytics/detection/image", Image, queue_size=5)
seg_image_pub = rospy.Publisher("/ultralytics/segmentation/image", Image, queue_size=5)
def callback(data):
"""Callback function to process image and publish annotated images."""
array = ros_numpy.numpify(data)
if det_image_pub.get_num_connections():
det_result = detection_model(array)
det_annotated = det_result[0].plot(show=False)
det_image_pub.publish(ros_numpy.msgify(Image, det_annotated, encoding="rgb8"))
if seg_image_pub.get_num_connections():
seg_result = segmentation_model(array)
seg_annotated = seg_result[0].plot(show=False)
seg_image_pub.publish(ros_numpy.msgify(Image, seg_annotated, encoding="rgb8"))
rospy.Subscriber("/camera/color/image_raw", Image, callback)
while True:
rospy.spin()Debug
Il debug dei nodi ROS (Robot Operating System) può essere impegnativo a causa della natura distribuita del sistema. Diversi strumenti possono assisterti in questo processo:
rostopic echo <TOPIC-NAME>: questo comando ti consente di visualizzare i messaggi pubblicati su uno specifico argomento, aiutandoti a ispezionare il flusso di dati.rostopic list: usa questo comando per elencare tutti gli argomenti disponibili nel sistema ROS, ottenendo una panoramica dei flussi di dati attivi.rqt_graph: questo strumento di visualizzazione mostra il grafico di comunicazione tra i nodi, fornendo informazioni su come i nodi sono interconnessi e come interagiscono.- 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 il suo ambiente in tempo reale. Con RViz, puoi visualizzare i dati dei sensori (ad es.
sensor_msgs/Image), gli stati del modello del robot e vari altri tipi di informazioni, facilitando il debug e la comprensione del comportamento del tuo sistema robotico.
Pubblica le classi rilevate con std_msgs/String
Standard ROS messages also include std_msgs/String messages. In many applications, it is not necessary to republish the entire annotated image; instead, only the classes present in the robot's view are needed. The following example demonstrates how to use std_msgs/String messages to republish the detected classes on the /ultralytics/detection/classes topic. These messages are more lightweight and provide essential information, making them valuable for various applications.
Caso d'uso di esempio
Considera un robot da magazzino dotato di una telecamera e un modello di rilevamento di oggetti. Invece di inviare grandi immagini annotate sulla rete, il robot può pubblicare un elenco di classi rilevate come messaggi std_msgs/String. Ad esempio, quando il robot rileva oggetti come "box", "pallet" e "forklift", pubblica queste classi sull'argomento /ultralytics/detection/classes. Queste informazioni possono poi 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 necessaria per la comunicazione e si concentra sulla trasmissione di dati critici.
Utilizzo della stringa passo dopo passo
Questo esempio mostra come utilizzare il pacchetto Ultralytics YOLO con ROS. In questo esempio, ci sottoscriviamo a un argomento della telecamera, elaboriamo l'immagine in arrivo usando YOLO e pubblichiamo gli oggetti rilevati sul nuovo argomento /ultralytics/detection/classes utilizzando messaggi std_msgs/String. Il pacchetto ros_numpy 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("yolo26m.pt")
rospy.init_node("ultralytics")
time.sleep(1)
classes_pub = rospy.Publisher("/ultralytics/detection/classes", String, queue_size=5)
def callback(data):
"""Callback function to process image and publish detected classes."""
array = ros_numpy.numpify(data)
if classes_pub.get_num_connections():
det_result = detection_model(array)
classes = det_result[0].boxes.cls.cpu().numpy().astype(int)
names = [det_result[0].names[i] for i in classes]
classes_pub.publish(String(data=str(names)))
rospy.Subscriber("/camera/color/image_raw", Image, callback)
while True:
rospy.spin()Usa Ultralytics con le immagini di profondità di 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 cruciali per applicazioni robotiche come l'evitamento degli 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.
Le immagini di profondità possono essere ottenute utilizzando vari sensori:
- Telecamere stereo: utilizzano due telecamere per calcolare la profondità in base alla disparità dell'immagine.
- Telecamere Time-of-Flight (ToF): misurano il tempo impiegato dalla luce per tornare da un oggetto.
- Sensori a luce strutturata: proiettano un motivo e ne misurano la deformazione sulle superfici.
Utilizzo di YOLO con le immagini di profondità
In ROS, le immagini di profondità sono rappresentate dal tipo di messaggio sensor_msgs/Image, che include campi per codifica, altezza, larghezza e dati dei pixel. Il campo di codifica per le immagini di profondità utilizza spesso un formato come "16UC1", che indica un intero a 16 bit senza segno 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 dalle immagini RGB che da quelle 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à per gli oggetti rilevati, migliorando la capacità del robot di comprendere il suo ambiente in tre dimensioni.
Quando si lavora con le immagini di profondità, è essenziale assicurarsi che le immagini RGB e di profondità siano allineate correttamente. 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 fonti. Se si utilizzano telecamere RGB e di profondità separate, è fondamentale calibrarle per garantire un allineamento accurato.
Utilizzo della profondità passo dopo passo
In questo esempio, utilizziamo YOLO per segmentare un'immagine e applicare la maschera estratta per segmentare l'oggetto nell'immagine di profondità. Ciò ci consente 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 argomento ROS.
import time
import rospy
from std_msgs.msg import String
from ultralytics import YOLO
rospy.init_node("ultralytics")
time.sleep(1)
segmentation_model = YOLO("yolo26m-seg.pt")
classes_pub = rospy.Publisher("/ultralytics/detection/distance", String, queue_size=5)Successivamente, definisci una funzione di callback che elabora il messaggio dell'immagine di profondità in arrivo. 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 clip, 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 sull'argomento /ultralytics/detection/distance.
import numpy as np
import ros_numpy
from sensor_msgs.msg import Image
def callback(data):
"""Callback function to process depth image and RGB image."""
image = rospy.wait_for_message("/camera/color/image_raw", Image)
image = ros_numpy.numpify(image)
depth = ros_numpy.numpify(data)
result = segmentation_model(image)
all_objects = []
for index, cls in enumerate(result[0].boxes.cls):
class_index = int(cls.cpu().numpy())
name = result[0].names[class_index]
mask = result[0].masks.data.cpu().numpy()[index, :, :].astype(int)
obj = depth[mask == 1]
obj = obj[~np.isnan(obj)]
avg_distance = np.mean(obj) if len(obj) else np.inf
all_objects.append(f"{name}: {avg_distance:.2f}m")
classes_pub.publish(String(data=str(all_objects)))
rospy.Subscriber("/camera/depth/image_raw", Image, callback)
while True:
rospy.spin()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("yolo26m-seg.pt")
classes_pub = rospy.Publisher("/ultralytics/detection/distance", String, queue_size=5)
def callback(data):
"""Callback function to process depth image and RGB image."""
image = rospy.wait_for_message("/camera/color/image_raw", Image)
image = ros_numpy.numpify(image)
depth = ros_numpy.numpify(data)
result = segmentation_model(image)
all_objects = []
for index, cls in enumerate(result[0].boxes.cls):
class_index = int(cls.cpu().numpy())
name = result[0].names[class_index]
mask = result[0].masks.data.cpu().numpy()[index, :, :].astype(int)
obj = depth[mask == 1]
obj = obj[~np.isnan(obj)]
avg_distance = np.mean(obj) if len(obj) else np.inf
all_objects.append(f"{name}: {avg_distance:.2f}m")
classes_pub.publish(String(data=str(all_objects)))
rospy.Subscriber("/camera/depth/image_raw", Image, callback)
while True:
rospy.spin()Usa Ultralytics con sensor_msgs/PointCloud2 di ROS
The sensor_msgs/PointCloud2 message type is a data structure used in ROS to represent 3D point cloud data. This message type is integral to robotic applications, enabling tasks such as 3D mapping, object recognition, and localization.
Una 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, catturati tramite tecnologie di scansione 3D. Ogni punto nella nuvola ha coordinate X, Y e Z, che corrispondono alla sua posizione nello spazio, e può anche includere informazioni aggiuntive come colore e intensità.
Quando si lavora con sensor_msgs/PointCloud2, è essenziale considerare il riferimento spaziale del sensore da cui sono stati acquisiti i dati della nuvola di punti. La nuvola di punti viene inizialmente catturata nel riferimento spaziale del sensore. Puoi determinare questo riferimento ascoltando l'argomento /tf_static. Tuttavia, a seconda dei requisiti specifici della tua applicazione, potresti dover convertire la nuvola di punti in un altro riferimento spaziale. Questa trasformazione può essere ottenuta utilizzando il pacchetto tf2_ros, che fornisce strumenti per gestire i frame di coordinate e trasformare i dati tra di loro.
Le nuvole di punti possono essere ottenute utilizzando vari sensori:
- LIDAR (Light Detection and Ranging): utilizza impulsi laser per misurare le distanze dagli oggetti e creare mappe 3D ad alta precisione.
- Telecamere di profondità: catturano informazioni sulla profondità per ogni pixel, consentendo la ricostruzione 3D della scena.
- Telecamere stereo: utilizzano due o più telecamere per ottenere informazioni sulla profondità tramite triangolazione.
- Scanner a luce strutturata: proiettano un motivo noto su una superficie e misurano la deformazione per calcolare la profondità.
Utilizzo di YOLO con le nuvole di punti
Per integrare YOLO con i messaggi di tipo sensor_msgs/PointCloud2, possiamo utilizzare un metodo simile a quello usato 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 usando YOLO e poi applicare la maschera risultante ai punti tridimensionali per isolare l'oggetto 3D di interesse.
Per la gestione delle nuvole di punti, consigliamo di utilizzare Open3D (pip install open3d), una libreria Python intuitiva. Open3D fornisce strumenti robusti per gestire strutture dati di nuvole di punti, visualizzarle ed eseguire operazioni complesse senza problemi. Questa libreria può semplificare significativamente il processo e migliorare la nostra capacità di manipolare e analizzare le nuvole di punti in combinazione con la segmentazione basata su YOLO.
Utilizzo della nuvola di punti passo dopo passo
Importa le librerie necessarie e crea il modello YOLO per la segmentazione.
import time
import rospy
from ultralytics import YOLO
rospy.init_node("ultralytics")
time.sleep(1)
segmentation_model = YOLO("yolo26m-seg.pt")Create a function pointcloud2_to_array, which transforms a sensor_msgs/PointCloud2 message into two NumPy arrays. The sensor_msgs/PointCloud2 messages contain n points based on the width and height of the acquired image. For instance, a 480 x 640 image will have 307,200 points. Each point includes three spatial coordinates (xyz) and the corresponding color in RGB format. These can be considered as two separate channels of information.
The function returns the xyz coordinates and RGB values in the format of the original camera resolution (width x height). Most sensors have a maximum distance, known as the clip distance, beyond which values are represented as inf (np.inf). Before processing, it is important to filter out these null values and assign them a value of 0.
import numpy as np
import ros_numpy
def pointcloud2_to_array(pointcloud2: PointCloud2) -> tuple:
"""Convert a ROS PointCloud2 message to a numpy array.
Args:
pointcloud2 (PointCloud2): the PointCloud2 message
Returns:
(tuple): tuple containing (xyz, rgb)
"""
pc_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud2)
split = ros_numpy.point_cloud2.split_rgb_field(pc_array)
rgb = np.stack([split["b"], split["g"], split["r"]], axis=2)
xyz = ros_numpy.point_cloud2.get_xyz_points(pc_array, remove_nans=False)
xyz = np.array(xyz).reshape((pointcloud2.height, pointcloud2.width, 3))
nan_rows = np.isnan(xyz).all(axis=2)
xyz[nan_rows] = [0, 0, 0]
rgb[nan_rows] = [0, 0, 0]
return xyz, rgbSuccessivamente, sottoscriviti all'argomento /camera/depth/points per ricevere il messaggio della nuvola di punti e converti il messaggio sensor_msgs/PointCloud2 in array NumPy contenenti le coordinate XYZ e i valori RGB (utilizzando la funzione pointcloud2_to_array). 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 che 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, moltiplica semplicemente i canali originali per la maschera. Questa operazione isola efficacemente l'oggetto di interesse all'interno dell'immagine. Infine, crea un oggetto nuvola di punti 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("yolo26m-seg.pt")
def pointcloud2_to_array(pointcloud2: PointCloud2) -> tuple:
"""Convert a ROS PointCloud2 message to a numpy array.
Args:
pointcloud2 (PointCloud2): the PointCloud2 message
Returns:
(tuple): tuple containing (xyz, rgb)
"""
pc_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud2)
split = ros_numpy.point_cloud2.split_rgb_field(pc_array)
rgb = np.stack([split["b"], split["g"], split["r"]], axis=2)
xyz = ros_numpy.point_cloud2.get_xyz_points(pc_array, remove_nans=False)
xyz = np.array(xyz).reshape((pointcloud2.height, pointcloud2.width, 3))
nan_rows = np.isnan(xyz).all(axis=2)
xyz[nan_rows] = [0, 0, 0]
rgb[nan_rows] = [0, 0, 0]
return xyz, rgb
ros_cloud = rospy.wait_for_message("/camera/depth/points", PointCloud2)
xyz, rgb = pointcloud2_to_array(ros_cloud)
result = segmentation_model(rgb)
if not len(result[0].boxes.cls):
print("No objects detected")
sys.exit()
classes = result[0].boxes.cls.cpu().numpy().astype(int)
for index, class_id in enumerate(classes):
mask = result[0].masks.data.cpu().numpy()[index, :, :].astype(int)
mask_expanded = np.stack([mask, mask, mask], axis=2)
obj_rgb = rgb * mask_expanded
obj_xyz = xyz * mask_expanded
pcd = o3d.geometry.PointCloud()
pcd.points = o3d.utility.Vector3dVector(obj_xyz.reshape((ros_cloud.height * ros_cloud.width, 3)))
pcd.colors = o3d.utility.Vector3dVector(obj_rgb.reshape((ros_cloud.height * ros_cloud.width, 3)) / 255)
o3d.visualization.draw_geometries([pcd])
FAQ
Che cos'è il Robot Operating System (ROS)?
Il Robot Operating System (ROS) è un framework open source comunemente usato nella robotica per aiutare gli sviluppatori a creare applicazioni robotiche robuste. Fornisce una raccolta di librerie e strumenti per costruire e interfacciarsi con sistemi robotici, consentendo uno sviluppo più semplice di applicazioni complesse. ROS supporta la comunicazione tra nodi utilizzando messaggi tramite argomenti o servizi.
Come integro Ultralytics YOLO con ROS per il rilevamento di oggetti in tempo reale?
L'integrazione di Ultralytics YOLO con ROS comporta 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 ultralyticsSuccessivamente, crea un nodo ROS e sottoscriviti a un argomento immagine per elaborare i dati in arrivo. Ecco un esempio minimo:
import ros_numpy
import rospy
from sensor_msgs.msg import Image
from ultralytics import YOLO
detection_model = YOLO("yolo26m.pt")
rospy.init_node("ultralytics")
det_image_pub = rospy.Publisher("/ultralytics/detection/image", Image, queue_size=5)
def callback(data):
array = ros_numpy.numpify(data)
det_result = detection_model(array)
det_annotated = det_result[0].plot(show=False)
det_image_pub.publish(ros_numpy.msgify(Image, det_annotated, encoding="rgb8"))
rospy.Subscriber("/camera/color/image_raw", Image, callback)
rospy.spin()Cosa sono gli argomenti ROS e come vengono utilizzati in Ultralytics YOLO?
Gli argomenti ROS facilitano la comunicazione tra i nodi in una rete ROS utilizzando un modello publish-subscribe. Un argomento è un canale denominato che i nodi usano per inviare e ricevere messaggi in modo asincrono. Nel contesto di Ultralytics YOLO, puoi far sì che un nodo si sottoscriva a un argomento immagine, elabori le immagini usando YOLO per attività come rilevamento o segmentazione e pubblichi i risultati su nuovi argomenti.
Ad esempio, sottoscriviti a un argomento della telecamera ed elabora l'immagine in arrivo per il rilevamento:
rospy.Subscriber("/camera/color/image_raw", Image, callback)Perché utilizzare le immagini di profondità con Ultralytics YOLO in ROS?
Le immagini di profondità in ROS, rappresentate da sensor_msgs/Image, forniscono la distanza degli oggetti dalla telecamera, fondamentale per attività come l'evitamento degli ostacoli, la mappatura 3D e la localizzazione. Utilizzando le informazioni di profondità insieme alle immagini RGB, i robot possono comprendere meglio il loro ambiente 3D.
Con YOLO, puoi estrarre maschere di segmentazione dalle immagini RGB e applicare queste maschere alle immagini di profondità per ottenere informazioni precise sull'oggetto 3D, migliorando la capacità del robot di navigare e interagire con l'ambiente circostante.
Come posso visualizzare le nuvole di punti 3D con YOLO in ROS?
Per visualizzare nuvole di punti 3D in ROS con YOLO:
- Converti i messaggi
sensor_msgs/PointCloud2in array NumPy. - Usa YOLO per segmentare le immagini RGB.
- 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("yolo26m-seg.pt")
def pointcloud2_to_array(pointcloud2):
pc_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud2)
split = ros_numpy.point_cloud2.split_rgb_field(pc_array)
rgb = np.stack([split["b"], split["g"], split["r"]], axis=2)
xyz = ros_numpy.point_cloud2.get_xyz_points(pc_array, remove_nans=False)
xyz = np.array(xyz).reshape((pointcloud2.height, pointcloud2.width, 3))
return xyz, rgb
ros_cloud = rospy.wait_for_message("/camera/depth/points", PointCloud2)
xyz, rgb = pointcloud2_to_array(ros_cloud)
result = segmentation_model(rgb)
if not len(result[0].boxes.cls):
print("No objects detected")
sys.exit()
classes = result[0].boxes.cls.cpu().numpy().astype(int)
for index, class_id in enumerate(classes):
mask = result[0].masks.data.cpu().numpy()[index, :, :].astype(int)
mask_expanded = np.stack([mask, mask, mask], axis=2)
obj_rgb = rgb * mask_expanded
obj_xyz = xyz * mask_expanded
pcd = o3d.geometry.PointCloud()
pcd.points = o3d.utility.Vector3dVector(obj_xyz.reshape((-1, 3)))
pcd.colors = o3d.utility.Vector3dVector(obj_rgb.reshape((-1, 3)) / 255)
o3d.visualization.draw_geometries([pcd])Questo approccio fornisce una visualizzazione 3D degli oggetti segmentati, utile per attività come la navigazione e la manipolazione in applicazioni robotiche.