ROS (Robot Operating System) Kurzanleitung

ROS Introduction (captioned) from Open Robotics on Vimeo.

Was ist ROS?

Das Robot Operating System (ROS) ist ein Open-Source-Framework, das in der Robotikforschung und -industrie weit verbreitet ist. ROS bietet eine Sammlung von Bibliotheken und Tools, die Entwickler bei der Erstellung von Roboteranwendungen unterstützen. ROS wurde für die Arbeit mit verschiedenen Roboterplattformen entwickelt und ist somit ein flexibles und leistungsstarkes Werkzeug für Robotiker.

Hauptfunktionen von ROS

  1. Modulare Architektur: ROS verfügt über eine modulare Architektur, die es Entwicklern ermöglicht, komplexe Systeme durch die Kombination kleinerer, wiederverwendbarer Komponenten, sogenannter Nodes, aufzubauen. Jeder Node führt normalerweise eine spezifische Funktion aus, und die Nodes kommunizieren über Topics oder Services miteinander.

  2. Kommunikations-Middleware: ROS bietet eine robuste Kommunikationsinfrastruktur, die Interprozesskommunikation und verteiltes Rechnen unterstützt. Dies wird durch ein Publish-Subscribe-Modell für Datenströme (Topics) und ein Request-Reply-Modell für Service-Aufrufe erreicht.

  3. Hardwareabstraktion: ROS bietet eine Abstraktionsschicht über der Hardware, die es Entwicklern ermöglicht, geräteunabhängigen Code zu schreiben. Dadurch kann derselbe Code mit verschiedenen Hardware-Setups verwendet werden, was die Integration und das Experimentieren erleichtert.

  4. Tools und Dienstprogramme: ROS wird mit einer umfangreichen Sammlung von Tools und Dienstprogrammen für Visualisierung, Debugging und Simulation geliefert. Zum Beispiel wird RViz zur Visualisierung von Sensordaten und Roboterzustandsinformationen verwendet, während Gazebo eine leistungsstarke Simulationsumgebung für das Testen von Algorithmen und Roboterdesigns bietet.

  5. Umfangreiches Ökosystem: Das ROS-Ökosystem ist riesig und wächst ständig weiter, wobei zahlreiche Pakete für verschiedene Roboteranwendungen verfügbar sind, einschließlich Navigation, Manipulation, Wahrnehmung und mehr. Die Community trägt aktiv zur Entwicklung und Wartung dieser Pakete bei.

Entwicklung der ROS-Versionen

Seit seiner Entwicklung im Jahr 2007 hat sich ROS durch mehrere Versionen weiterentwickelt, von denen jede neue Funktionen und Verbesserungen einführte, um den wachsenden Anforderungen der Robotik-Community gerecht zu werden. Die Entwicklung von ROS lässt sich in zwei Hauptserien unterteilen: ROS 1 und ROS 2. Dieser Leitfaden konzentriert sich auf die Long Term Support (LTS) Version von ROS 1, bekannt als ROS Noetic Ninjemys; der Code sollte jedoch auch mit früheren Versionen funktionieren.

ROS 1 vs. ROS 2

Während ROS 1 eine solide Grundlage für die Roboterentwicklung bot, behebt ROS 2 dessen Mängel durch:

  • Echtzeitleistung: Verbesserte Unterstützung für Echtzeitsysteme und deterministisches Verhalten.
  • Sicherheit: Erweiterte Sicherheitsfunktionen für einen sicheren und zuverlässigen Betrieb in verschiedenen Umgebungen.
  • Skalierbarkeit: Bessere Unterstützung für Multi-Robotersysteme und groß angelegte Bereitstellungen.
  • Plattformübergreifende Unterstützung: Erweiterte Kompatibilität mit verschiedenen Betriebssystemen über Linux hinaus, einschließlich Windows und macOS.
  • Flexible Kommunikation: Verwendung von DDS für eine flexiblere und effizientere Interprozesskommunikation.

ROS Messages und Topics

In ROS wird die Kommunikation zwischen Nodes durch Messages und Topics ermöglicht. Eine Message ist eine Datenstruktur, die die zwischen Nodes ausgetauschten Informationen definiert, während ein Topic ein benannter Kanal ist, über den Messages gesendet und empfangen werden. Nodes können Messages an ein Topic senden (publish) oder von einem Topic abonnieren (subscribe), wodurch sie miteinander kommunizieren können. Dieses Publish-Subscribe-Modell ermöglicht asynchrone Kommunikation und Entkopplung zwischen den Nodes. Jeder Sensor oder Aktuator in einem Robotersystem sendet normalerweise Daten an ein Topic, das dann von anderen Nodes zur Verarbeitung oder Steuerung verwendet werden kann. Für diesen Leitfaden konzentrieren wir uns auf Image, Depth und PointCloud Messages sowie Kamera-Topics.

Einrichten von Ultralytics YOLO mit ROS

Dieser Leitfaden wurde unter Verwendung dieser ROS-Umgebung getestet, die ein Fork des ROSbot ROS-Repositorys ist. Diese Umgebung enthält das Ultralytics YOLO-Paket, einen Docker-Container für ein einfaches Setup, umfassende ROS-Pakete und Gazebo-Welten für schnelle Tests. Sie ist für die Arbeit mit dem Husarion ROSbot 2 PRO konzipiert. Die bereitgestellten Codebeispiele funktionieren in jeder ROS Noetic/Melodic-Umgebung, sowohl in der Simulation als auch in der realen Welt.

Husarion ROSbot 2 PRO autonomous robot platform

Installation der Abhängigkeiten

Neben der ROS-Umgebung musst du die folgenden Abhängigkeiten installieren:

  • ROS NumPy-Paket: Dies ist für die schnelle Konvertierung zwischen ROS Image Messages und NumPy-Arrays erforderlich.

    pip install ros_numpy
  • Ultralytics-Paket:

    pip install ultralytics

Verwendung von Ultralytics mit ROS sensor_msgs/Image

Der sensor_msgs/Image Message-Typ wird in ROS häufig zur Darstellung von Bilddaten verwendet. Er enthält Felder für Kodierung, Höhe, Breite und Pixeldaten und ist somit für die Übertragung von Bildern geeignet, die von Kameras oder anderen Sensoren aufgenommen wurden. Image-Messages werden in Roboteranwendungen häufig für Aufgaben wie visuelle Wahrnehmung, Objekterkennung und Navigation eingesetzt.

Detection and Segmentation in ROS Gazebo

Schritt-für-Schritt-Anleitung zur Bildverwendung

Der folgende Code-Schnipsel demonstriert, wie man das Ultralytics YOLO-Paket mit ROS verwendet. In diesem Beispiel abonnieren wir ein Kamera-Topic, verarbeiten das eingehende Bild mit YOLO und veröffentlichen die erkannten Objekte in neuen Topics für Detection und Segmentation.

Importiere zuerst die notwendigen Bibliotheken und instanziiere zwei Modelle: eines für Segmentation und eines für Detection. Initialisiere einen ROS-Node (mit dem Namen ultralytics), um die Kommunikation mit dem ROS-Master zu ermöglichen. Um eine stabile Verbindung sicherzustellen, fügen wir eine kurze Pause ein, damit der Node genügend Zeit hat, die Verbindung aufzubauen, bevor er fortfährt.

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)

Initialisiere zwei ROS-Topics: eines für Detection und eines für Segmentation. Diese Topics werden verwendet, um die annotierten Bilder zu veröffentlichen und sie für die weitere Verarbeitung zugänglich zu machen. Die Kommunikation zwischen den Nodes erfolgt mithilfe von 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)

Erstelle schließlich einen Subscriber, der auf Messages im Topic /camera/color/image_raw hört und für jede neue Message eine Callback-Funktion aufruft. Diese Callback-Funktion empfängt Messages vom Typ sensor_msgs/Image, wandelt sie mit ros_numpy in ein NumPy-Array um, verarbeitet die Bilder mit den zuvor instanziierten YOLO-Modellen, annotiert die Bilder und veröffentlicht sie dann zurück in die entsprechenden Topics: /ultralytics/detection/image für Detection und /ultralytics/segmentation/image für Segmentation.

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()
Vollständiger Code
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()
Debugging

Das Debugging von ROS (Robot Operating System) Nodes kann aufgrund der verteilten Natur des Systems eine Herausforderung sein. Mehrere Tools können bei diesem Prozess helfen:

  1. rostopic echo <TOPIC-NAME> : Mit diesem Befehl kannst du dir die Nachrichten ansehen, die in einem bestimmten Topic veröffentlicht werden, was dir bei der Überprüfung des Datenflusses hilft.
  2. rostopic list: Verwende diesen Befehl, um alle verfügbaren Topics im ROS-System aufzulisten, um einen Überblick über die aktiven Datenströme zu erhalten.
  3. rqt_graph: Dieses Visualisierungstool zeigt den Kommunikationsgraphen zwischen den Nodes an und bietet Einblicke in die Art und Weise, wie Nodes miteinander verbunden sind und interagieren.
  4. Für komplexere Visualisierungen, wie z.B. 3D-Darstellungen, kannst du RViz verwenden. RViz (ROS Visualization) ist ein leistungsstarkes 3D-Visualisierungstool für ROS. Es ermöglicht dir, den Zustand deines Roboters und seiner Umgebung in Echtzeit zu visualisieren. Mit RViz kannst du Sensordaten (z. B. sensor_msgs/Image), Zustände des Robotermodells und verschiedene andere Arten von Informationen anzeigen, was das Debugging und das Verständnis des Verhaltens deines Robotersystems erleichtert.

Erkannte Klassen veröffentlichen mit std_msgs/String

Standard-ROS-Messages beinhalten auch std_msgs/String Messages. In vielen Anwendungen ist es nicht notwendig, das gesamte annotierte Bild erneut zu veröffentlichen; stattdessen werden nur die Klassen benötigt, die im Sichtfeld des Roboters vorhanden sind. Das folgende Beispiel zeigt, wie man std_msgs/String Messages verwendet, um die erkannten Klassen im Topic /ultralytics/detection/classes erneut zu veröffentlichen. Diese Nachrichten sind leichtgewichtiger und liefern wichtige Informationen, was sie für verschiedene Anwendungen wertvoll macht.

Anwendungsbeispiel

Stell dir einen Lagerroboter vor, der mit einer Kamera und einem Detection-Modell ausgestattet ist. Anstatt große annotierte Bilder über das Netzwerk zu senden, kann der Roboter eine Liste der erkannten Klassen als std_msgs/String Nachrichten veröffentlichen. Wenn der Roboter beispielsweise Objekte wie "box", "pallet" und "forklift" erkennt, veröffentlicht er diese Klassen im Topic /ultralytics/detection/classes. Diese Informationen können dann von einem zentralen Überwachungssystem verwendet werden, um den Inventarbestand in Echtzeit zu verfolgen, die Pfadplanung des Roboters zur Hindernisvermeidung zu optimieren oder spezifische Aktionen auszulösen, wie z.B. das Aufnehmen einer erkannten Box. Dieser Ansatz reduziert die für die Kommunikation erforderliche Bandbreite und konzentriert sich auf die Übertragung kritischer Daten.

Schritt-für-Schritt-Anleitung zur String-Verwendung

This example demonstrates how to use the Ultralytics YOLO package with ROS. In this example, we subscribe to a camera topic, process the incoming image using YOLO, and publish the detected objects to new topic /ultralytics/detection/classes using std_msgs/String messages. The ros_numpy package is used to convert the ROS Image message to a NumPy array for processing with 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()

Verwendung von Ultralytics mit ROS-Tiefenbildern

Zusätzlich zu RGB-Bildern unterstützt ROS Tiefenbilder, die Informationen über den Abstand von Objekten zur Kamera liefern. Tiefenbilder sind entscheidend für Roboteranwendungen wie Hindernisvermeidung, 3D-Kartierung und Lokalisierung.

Ein Tiefenbild ist ein Bild, bei dem jedes Pixel den Abstand von der Kamera zu einem Objekt darstellt. Im Gegensatz zu RGB-Bildern, die Farben erfassen, erfassen Tiefenbilder räumliche Informationen und ermöglichen es Robotern, die 3D-Struktur ihrer Umgebung wahrzunehmen.

Tiefenbilder erhalten

Tiefenbilder können mit verschiedenen Sensoren erfasst werden:

  1. Stereokameras: Verwenden zwei Kameras, um die Tiefe basierend auf der Bilddisparität zu berechnen.
  2. Time-of-Flight (ToF)-Kameras: Messen die Zeit, die das Licht benötigt, um von einem Objekt zurückzukehren.
  3. Strukturlichtsensoren: Projizieren ein Muster und messen dessen Verformung auf Oberflächen.

Verwendung von YOLO mit Tiefenbildern

In ROS werden Tiefenbilder durch den Message-Typ sensor_msgs/Image dargestellt, der Felder für Kodierung, Höhe, Breite und Pixeldaten enthält. Das Kodierungsfeld für Tiefenbilder verwendet oft ein Format wie "16UC1", was auf einen 16-Bit-Integer ohne Vorzeichen pro Pixel hinweist, wobei jeder Wert den Abstand zum Objekt darstellt. Tiefenbilder werden häufig in Verbindung mit RGB-Bildern verwendet, um einen umfassenderen Blick auf die Umgebung zu ermöglichen.

Mit YOLO ist es möglich, Informationen sowohl aus RGB- als auch aus Tiefenbildern zu extrahieren und zu kombinieren. Beispielsweise kann YOLO Objekte in einem RGB-Bild erkennen, und diese Erkennung kann dazu verwendet werden, entsprechende Bereiche im Tiefenbild zu lokalisieren. Dies ermöglicht die Extraktion präziser Tiefeninformationen für erkannte Objekte, was die Fähigkeit des Roboters verbessert, seine Umgebung in drei Dimensionen zu verstehen.

RGB-D-Kameras

Bei der Arbeit mit Tiefenbildern ist es wichtig sicherzustellen, dass die RGB- und Tiefenbilder korrekt ausgerichtet sind. RGB-D-Kameras, wie die Intel RealSense-Serie, liefern synchronisierte RGB- und Tiefenbilder, was die Kombination von Informationen aus beiden Quellen erleichtert. Bei der Verwendung separater RGB- und Tiefenkameras ist eine Kalibrierung entscheidend, um eine genaue Ausrichtung sicherzustellen.

Schritt-für-Schritt-Anleitung zur Tiefenverwendung

In diesem Beispiel verwenden wir YOLO, um ein Bild zu segmentieren und den extrahierten Maskenwert anzuwenden, um das Objekt im Tiefenbild zu segmentieren. Dies ermöglicht uns, den Abstand jedes Pixels des interessierenden Objekts vom Brennpunkt der Kamera zu bestimmen. Durch das Erhalten dieser Abstandsinformationen können wir den Abstand zwischen der Kamera und dem spezifischen Objekt in der Szene berechnen. Beginne mit dem Importieren der notwendigen Bibliotheken, dem Erstellen eines ROS-Nodes und dem Instanziieren eines Segmentierungsmodells sowie eines ROS-Topics.

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)

Definiere als Nächstes eine Callback-Funktion, die die eingehende Tiefenbild-Message verarbeitet. Die Funktion wartet auf die Tiefenbild- und RGB-Bild-Messages, wandelt sie in NumPy-Arrays um und wendet das Segmentierungsmodell auf das RGB-Bild an. Dann extrahiert sie die Segmentierungsmaske für jedes erkannte Objekt und berechnet den durchschnittlichen Abstand des Objekts von der Kamera mithilfe des Tiefenbildes. Die meisten Sensoren haben einen maximalen Abstand, den sogenannten Clip-Abstand, jenseits dessen Werte als inf (np.inf) dargestellt werden. Vor der Verarbeitung ist es wichtig, diese Nullwerte herauszufiltern und ihnen einen Wert von 0 zuzuweisen. Schließlich werden die erkannten Objekte zusammen mit ihren durchschnittlichen Abständen im Topic /ultralytics/detection/distance veröffentlicht.

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()
Vollständiger Code
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()

Verwendung von Ultralytics mit ROS sensor_msgs/PointCloud2

Detection and Segmentation in ROS Gazebo

Der sensor_msgs/PointCloud2 Message-Typ ist eine Datenstruktur, die in ROS verwendet wird, um 3D-Punktwolkendaten darzustellen. Dieser Nachrichtentyp ist integraler Bestandteil von Roboteranwendungen und ermöglicht Aufgaben wie 3D-Kartierung, Objekterkennung und Lokalisierung.

Eine Punktwolke ist eine Sammlung von Datenpunkten, die in einem dreidimensionalen Koordinatensystem definiert sind. Diese Datenpunkte repräsentieren die äußere Oberfläche eines Objekts oder einer Szene, die mittels 3D-Scan-Technologien erfasst wurden. Jeder Punkt in der Wolke verfügt über X-, Y- und Z-Koordinaten, die seiner Position im Raum entsprechen, und kann zusätzlich Informationen wie Farbe und Intensität enthalten.

Referenzrahmen

Bei der Arbeit mit sensor_msgs/PointCloud2 ist es wichtig, den Referenzrahmen des Sensors zu berücksichtigen, von dem die Punktwolkendaten erfasst wurden. Die Punktwolke wird ursprünglich im Referenzrahmen des Sensors erfasst. Du kannst diesen Referenzrahmen bestimmen, indem du das Topic /tf_static abhörst. Je nach deinen spezifischen Anwendungsanforderungen musst du die Punktwolke jedoch möglicherweise in einen anderen Referenzrahmen konvertieren. Diese Transformation kann mit dem tf2_ros-Paket durchgeführt werden, das Tools zur Verwaltung von Koordinatenrahmen und zur Transformation von Daten zwischen diesen bereitstellt.

Punktwolken erhalten

Punktwolken können mit verschiedenen Sensoren erfasst werden:

  1. LIDAR (Light Detection and Ranging): Verwendet Laserpulse, um Abstände zu Objekten zu messen und hochpräzise 3D-Karten zu erstellen.
  2. Tiefenkameras: Erfassen Tiefeninformationen für jedes Pixel, was eine 3D-Rekonstruktion der Szene ermöglicht.
  3. Stereokameras: Nutzen zwei oder mehr Kameras, um Tiefeninformationen durch Triangulation zu erhalten.
  4. Strukturlichtscanner: Projizieren ein bekanntes Muster auf eine Oberfläche und messen die Verformung, um die Tiefe zu berechnen.

Verwendung von YOLO mit Punktwolken

Um YOLO mit Messages vom Typ sensor_msgs/PointCloud2 zu integrieren, können wir eine Methode verwenden, die der für Tiefenkarten verwendeten ähnelt. Durch die Nutzung der in der Punktwolke eingebetteten Farbinformationen können wir ein 2D-Bild extrahieren, eine Segmentierung auf diesem Bild mit YOLO durchführen und dann die resultierende Maske auf die dreidimensionalen Punkte anwenden, um das interessierende 3D-Objekt zu isolieren.

Für die Handhabung von Punktwolken empfehlen wir die Verwendung von Open3D (pip install open3d), einer benutzerfreundlichen Python-Bibliothek. Open3D bietet robuste Tools für die Verwaltung von Punktwolken-Datenstrukturen, deren Visualisierung und die nahtlose Ausführung komplexer Operationen. Diese Bibliothek kann den Prozess erheblich vereinfachen und unsere Fähigkeit verbessern, Punktwolken in Verbindung mit YOLO-basierter Segmentierung zu manipulieren und zu analysieren.

Schritt-für-Schritt-Anleitung zur Punktwolken-Verwendung

Importiere die notwendigen Bibliotheken und instanziiere das YOLO-Modell für die Segmentierung.

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.

Die Funktion gibt die xyz-Koordinaten und RGB-Werte im Format der ursprünglichen Kameraauflösung (width x height) zurück. Die meisten Sensoren haben einen maximalen Abstand, den sogenannten Clip-Abstand, jenseits dessen Werte als inf (np.inf) dargestellt werden. Vor der Verarbeitung ist es wichtig, diese Nullwerte herauszufiltern und ihnen einen Wert von 0 zuzuweisen.

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

Abonniere als Nächstes das Topic /camera/depth/points, um die Punktwolken-Message zu empfangen, und konvertiere die sensor_msgs/PointCloud2-Message mithilfe der Funktion pointcloud2_to_array in NumPy-Arrays, die die XYZ-Koordinaten und RGB-Werte enthalten. Verarbeite das RGB-Bild mit dem YOLO-Modell, um segmentierte Objekte zu extrahieren. Extrahiere für jedes erkannte Objekt die Segmentierungsmaske und wende sie sowohl auf das RGB-Bild als auch auf die XYZ-Koordinaten an, um das Objekt im 3D-Raum zu isolieren.

Die Verarbeitung der Maske ist unkompliziert, da sie aus Binärwerten besteht, wobei 1 das Vorhandensein des Objekts und 0 dessen Abwesenheit anzeigt. Um die Maske anzuwenden, multipliziere einfach die ursprünglichen Kanäle mit der Maske. Diese Operation isoliert effektiv das interessierende Objekt innerhalb des Bildes. Erstelle schließlich ein Open3D-Punktwolkenobjekt und visualisiere das segmentierte Objekt im 3D-Raum mit den zugehörigen Farben.

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])
Vollständiger Code
import sys
import time

import numpy as np
import open3d as o3d
import ros_numpy
import rospy
from sensor_msgs.msg import PointCloud2

from ultralytics import YOLO

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

def pointcloud2_to_array(pointcloud2: PointCloud2) -> tuple:
    """Convert a ROS PointCloud2 message to a numpy array.

    Args:
        pointcloud2 (PointCloud2): the PointCloud2 message

    Returns:
        (tuple): tuple containing (xyz, rgb)
    """
    pc_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud2)
    split = ros_numpy.point_cloud2.split_rgb_field(pc_array)
    rgb = np.stack([split["b"], split["g"], split["r"]], axis=2)
    xyz = ros_numpy.point_cloud2.get_xyz_points(pc_array, remove_nans=False)
    xyz = np.array(xyz).reshape((pointcloud2.height, pointcloud2.width, 3))
    nan_rows = np.isnan(xyz).all(axis=2)
    xyz[nan_rows] = [0, 0, 0]
    rgb[nan_rows] = [0, 0, 0]
    return xyz, rgb

ros_cloud = rospy.wait_for_message("/camera/depth/points", PointCloud2)
xyz, rgb = pointcloud2_to_array(ros_cloud)
result = segmentation_model(rgb)

if not len(result[0].boxes.cls):
    print("No objects detected")
    sys.exit()

classes = result[0].boxes.cls.cpu().numpy().astype(int)
for index, class_id in enumerate(classes):
    mask = result[0].masks.data.cpu().numpy()[index, :, :].astype(int)
    mask_expanded = np.stack([mask, mask, mask], axis=2)

    obj_rgb = rgb * mask_expanded
    obj_xyz = xyz * mask_expanded

    pcd = o3d.geometry.PointCloud()
    pcd.points = o3d.utility.Vector3dVector(obj_xyz.reshape((ros_cloud.height * ros_cloud.width, 3)))
    pcd.colors = o3d.utility.Vector3dVector(obj_rgb.reshape((ros_cloud.height * ros_cloud.width, 3)) / 255)
    o3d.visualization.draw_geometries([pcd])

Point Cloud Segmentation with Ultralytics

FAQ

Was ist das Robot Operating System (ROS)?

Das Robot Operating System (ROS) ist ein Open-Source-Framework, das in der Robotik häufig verwendet wird, um Entwicklern bei der Erstellung robuster Roboteranwendungen zu helfen. Es bietet eine Sammlung von Bibliotheken und Tools für den Aufbau von und die Schnittstellenbildung zu Robotersystemen, was die Entwicklung komplexer Anwendungen erleichtert. ROS unterstützt die Kommunikation zwischen Nodes mithilfe von Messages über Topics oder Services.

Wie integriere ich Ultralytics YOLO mit ROS für die Echtzeit-Objekterkennung?

Die Integration von Ultralytics YOLO mit ROS umfasst die Einrichtung einer ROS-Umgebung und die Verwendung von YOLO zur Verarbeitung von Sensordaten. Beginne mit der Installation der erforderlichen Abhängigkeiten wie ros_numpy und Ultralytics YOLO:

pip install ros_numpy ultralytics

Erstelle als Nächstes einen ROS-Node und abonniere ein Bild-Topic, um die eingehenden Daten zu verarbeiten. Hier ist ein minimales Beispiel:

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

Was sind ROS-Topics und wie werden sie in Ultralytics YOLO verwendet?

ROS-Topics ermöglichen die Kommunikation zwischen Nodes in einem ROS-Netzwerk mithilfe eines Publish-Subscribe-Modells. Ein Topic ist ein benannter Kanal, den Nodes verwenden, um Messages asynchron zu senden und zu empfangen. Im Kontext von Ultralytics YOLO kannst du einen Node so einstellen, dass er ein Bild-Topic abonniert, die Bilder mithilfe von YOLO für Aufgaben wie Detection oder Segmentation verarbeitet und die Ergebnisse in neuen Topics veröffentlicht.

Abonniere zum Beispiel ein Kamera-Topic und verarbeite das eingehende Bild für die Detection:

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

Warum sollte man Tiefenbilder mit Ultralytics YOLO in ROS verwenden?

Tiefenbilder in ROS, die durch sensor_msgs/Image dargestellt werden, liefern den Abstand von Objekten zur Kamera, was entscheidend für Aufgaben wie Hindernisvermeidung, 3D-Kartierung und Lokalisierung ist. Durch die Nutzung von Tiefeninformationen zusammen mit RGB-Bildern können Roboter ihre 3D-Umgebung besser verstehen.

Mit YOLO kannst du Segmentierungsmasken aus RGB-Bildern extrahieren und diese Masken auf Tiefenbilder anwenden, um präzise 3D-Objektinformationen zu erhalten, was die Fähigkeit des Roboters verbessert, zu navigieren und mit seiner Umgebung zu interagieren.

Wie kann ich 3D-Punktwolken mit YOLO in ROS visualisieren?

Um 3D-Punktwolken in ROS mit YOLO zu visualisieren:

  1. Konvertiere sensor_msgs/PointCloud2-Messages in NumPy-Arrays.
  2. Verwende YOLO, um RGB-Bilder zu segmentieren.
  3. Wende die Segmentierungsmaske auf die Punktwolke an.

Hier ist ein Beispiel unter Verwendung von Open3D für die Visualisierung:

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

Dieser Ansatz bietet eine 3D-Visualisierung von segmentierten Objekten, die für Aufgaben wie Navigation und Manipulation in Roboteranwendungen nützlich ist.

Kommentare