ROS (Robot Operating System) hızlı başlangıç kılavuzu

ROS Introduction (captioned) from Open Robotics on Vimeo.

ROS nedir?

Robot Operating System (ROS), robotik araştırmalarında ve endüstrisinde yaygın olarak kullanılan açık kaynaklı bir çerçevedir. ROS, geliştiricilerin robot uygulamaları oluşturmasına yardımcı olmak için bir kütüphane ve araç koleksiyonu sağlar. ROS, çeşitli robotik platformlarla çalışacak şekilde tasarlanmıştır, bu da onu robotik uzmanları için esnek ve güçlü bir araç haline getirir.

ROS'un Temel Özellikleri

  1. Modüler Mimari: ROS, geliştiricilerin düğümler olarak adlandırılan daha küçük, yeniden kullanılabilir bileşenleri birleştirerek karmaşık sistemler oluşturmasına olanak tanıyan modüler bir mimariye sahiptir. Her düğüm genellikle belirli bir işlevi yerine getirir ve düğümler konular veya hizmetler üzerinden mesajlaşarak birbirleriyle iletişim kurar.

  2. İletişim Ara Yazılımı: ROS, süreçler arası iletişimi ve dağıtık bilişimi destekleyen sağlam bir iletişim altyapısı sunar. Bu, veri akışları (konular) için bir yayınla-abone ol modeli ve hizmet çağrıları için bir istek-yanıt modeli aracılığıyla elde edilir.

  3. Donanım Soyutlama: ROS, donanım üzerinde bir soyutlama katmanı sağlayarak geliştiricilerin cihazdan bağımsız kod yazmasını sağlar. Bu, aynı kodun farklı donanım kurulumlarıyla kullanılmasına olanak tanıyarak entegrasyonu ve denemeleri kolaylaştırır.

  4. Araçlar ve Yardımcı Programlar: ROS, görselleştirme, hata ayıklama ve simülasyon için zengin bir araç ve yardımcı program seti ile birlikte gelir. Örneğin, RViz sensör verilerini ve robot durumu bilgilerini görselleştirmek için kullanılırken, Gazebo algoritmaları ve robot tasarımlarını test etmek için güçlü bir simülasyon ortamı sağlar.

  5. Geniş Ekosistem: ROS ekosistemi geniştir ve sürekli büyümektedir; navigasyon, manipülasyon, algılama ve daha fazlası dahil olmak üzere farklı robotik uygulamalar için çok sayıda paket mevcuttur. Topluluk, bu paketlerin geliştirilmesine ve bakımına aktif olarak katkıda bulunur.

ROS Sürümlerinin Evrimi

2007'deki geliştirilmesinden bu yana ROS, robotik topluluğunun artan ihtiyaçlarını karşılamak için her biri yeni özellikler ve iyileştirmeler sunan birden fazla sürüm boyunca evrimleşmiştir. ROS'un gelişimi iki ana seride kategorize edilebilir: ROS 1 ve ROS 2. Bu kılavuz, ROS 1'in Uzun Süreli Destek (LTS) sürümü olan ROS Noetic Ninjemys'e odaklanmaktadır; kod önceki sürümlerle de çalışmalıdır.

ROS 1 ile ROS 2 Karşılaştırması

ROS 1 robotik geliştirme için sağlam bir temel sağlarken, ROS 2 sunduğu şunlarla eksikliklerini gidermektedir:

  • Gerçek Zamanlı Performans: Gerçek zamanlı sistemler ve deterministik davranış için iyileştirilmiş destek.
  • Güvenlik: Çeşitli ortamlarda güvenli ve güvenilir çalışma için geliştirilmiş güvenlik özellikleri.
  • Ölçeklenebilirlik: Çoklu robot sistemleri ve büyük ölçekli dağıtımlar için daha iyi destek.
  • Çapraz Platform Desteği: Windows ve macOS dahil olmak üzere Linux dışındaki çeşitli işletim sistemleriyle genişletilmiş uyumluluk.
  • Esnek İletişim: Daha esnek ve verimli süreçler arası iletişim için DDS kullanımı.

ROS Mesajları ve Konuları

ROS'ta düğümler arasındaki iletişim mesajlar ve konular aracılığıyla kolaylaştırılır. Mesaj, düğümler arasında paylaşılan bilgiyi tanımlayan bir veri yapısıdır; konu ise mesajların gönderilip alındığı adlandırılmış bir kanaldır. Düğümler bir konuya mesaj yayınlayabilir veya bir konudan mesajlara abone olabilir, böylece birbirleriyle iletişim kurabilirler. Bu yayınla-abone ol modeli, düğümler arasında eşzamansız iletişime ve ayrışmaya olanak tanır. Bir robotik sistemdeki her sensör veya aktüatör genellikle bir konuya veri yayınlar ve bu veri daha sonra işleme veya kontrol için diğer düğümler tarafından tüketilebilir. Bu kılavuzun amacı doğrultusunda, Image, Depth ve PointCloud mesajlarına ve kamera konularına odaklanacağız.

Ultralytics YOLO'yu ROS ile Kurma

This guide has been tested using this ROS environment, which is a fork of the ROSbot ROS repository. This environment includes the Ultralytics YOLO package, a Docker container for easy setup, comprehensive ROS packages, and Gazebo worlds for rapid testing. It is designed to work with the Husarion ROSbot 2 PRO. The code examples provided will work in any ROS Noetic/Melodic environment, including both simulation and real-world.

Husarion ROSbot 2 PRO autonomous robot platform

Bağımlılıkların Kurulumu

ROS ortamının yanı sıra, aşağıdaki bağımlılıkları yüklemeniz gerekecektir:

  • ROS NumPy paketi: ROS Image mesajları ile NumPy dizileri arasında hızlı dönüştürme için gereklidir.

    pip install ros_numpy
  • Ultralytics paketi:

    pip install ultralytics

Ultralytics'i ROS sensor_msgs/Image ile kullan

sensor_msgs/Image mesaj türü, ROS'ta görüntü verilerini temsil etmek için yaygın olarak kullanılır. Kodlama, yükseklik, genişlik ve piksel verileri için alanlar içerir; bu da onu kameralar veya diğer sensörler tarafından yakalanan görüntülerin iletimi için uygun hale getirir. Görüntü mesajları robotik uygulamalarda görsel algılama, nesne algılama ve navigasyon gibi görevler için yaygın olarak kullanılır.

Detection and Segmentation in ROS Gazebo

Adım Adım Görüntü Kullanımı

Aşağıdaki kod parçası, Ultralytics YOLO paketinin ROS ile nasıl kullanılacağını göstermektedir. Bu örnekte, bir kamera konusuna abone oluyor, gelen görüntüyü YOLO kullanarak işliyor ve algılanan nesneleri algılama ve segmentasyon için yeni konulara yayınlıyoruz.

Öncelikle gerekli kütüphaneleri içe aktar ve iki model oluştur: biri segmentasyon ve diğeri algılama için. ROS master ile iletişimi sağlamak için bir ROS düğümünü (ultralytics adıyla) başlat. Kararlı bir bağlantı sağlamak için, devam etmeden önce düğümün bağlantıyı kurması için yeterli zamana sahip olmasını sağlayan kısa bir duraklama ekliyoruz.

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)

İki ROS konusu başlat: biri algılama ve diğeri segmentasyon için. Bu konular, açıklama eklenmiş görüntüleri yayınlamak için kullanılacak ve bunları daha ileri işleme için erişilebilir kılacaktır. Düğümler arasındaki iletişim sensor_msgs/Image mesajları kullanılarak kolaylaştırılır.

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)

Son olarak, /camera/color/image_raw konusundaki mesajları dinleyen ve her yeni mesaj için bir geri çağırma işlevini çağıran bir abone oluştur. Bu geri çağırma işlevi, sensor_msgs/Image türündeki mesajları alır, bunları ros_numpy kullanarak bir NumPy dizisine dönüştürür, görüntüleri daha önce oluşturulan YOLO modelleriyle işler, görüntülere açıklama ekler ve ardından bunları ilgili konulara yayınlar: algılama için /ultralytics/detection/image ve segmentasyon için /ultralytics/segmentation/image.

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()
Kodun tamamı
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()
Hata Ayıklama

ROS (Robot Operating System) düğümlerinde hata ayıklama, sistemin dağıtık yapısı nedeniyle zorlu olabilir. Bu sürece yardımcı olabilecek birkaç araç şunlardır:

  1. rostopic echo <TOPIC-NAME> : Bu komut, belirli bir konuda yayınlanan mesajları görmenizi sağlayarak veri akışını incelemenize yardımcı olur.
  2. rostopic list: ROS sistemindeki tüm mevcut konuları listelemek ve aktif veri akışlarına genel bir bakış elde etmek için bu komutu kullanın.
  3. rqt_graph: Bu görselleştirme aracı, düğümler arasındaki iletişim grafiğini görüntüler ve düğümlerin nasıl birbirine bağlandığı ve nasıl etkileşime girdiği hakkında içgörüler sağlar.
  4. 3D temsiller gibi daha karmaşık görselleştirmeler için RViz kullanabilirsiniz. RViz (ROS Visualization), ROS için güçlü bir 3D görselleştirme aracıdır. Robotunuzun ve çevresinin durumunu gerçek zamanlı olarak görselleştirmenize olanak tanır. RViz ile sensör verilerini (örneğin sensor_msgs/Image), robot modeli durumlarını ve çeşitli diğer bilgi türlerini görüntüleyebilir, böylece robotik sisteminizin davranışını daha kolay hata ayıklayabilir ve anlayabilirsiniz.

Algılanan Sınıfları std_msgs/String ile Yayınla

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.

Örnek Kullanım Durumu

Kamera ve nesne algılama modeli ile donatılmış bir depo robotu düşünün. Robot, ağ üzerinden büyük açıklama eklenmiş görüntüleri göndermek yerine, algılanan sınıfların bir listesini std_msgs/String mesajları olarak yayınlayabilir. Örneğin, robot "kutu", "palet" ve "forklift" gibi nesneleri algıladığında, bu sınıfları /ultralytics/detection/classes konusuna yayınlar. Bu bilgiler daha sonra merkezi bir izleme sistemi tarafından envanteri gerçek zamanlı olarak takip etmek, robotun yol planlamasını engellerden kaçınacak şekilde optimize etmek veya algılanan bir kutuyu almak gibi belirli eylemleri tetiklemek için kullanılabilir. Bu yaklaşım, iletişim için gereken bant genişliğini azaltır ve kritik verilerin iletilmesine odaklanır.

Adım Adım String Kullanımı

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

Ultralytics'i ROS Derinlik Görüntüleri ile Kullan

RGB görüntülerine ek olarak ROS, nesnelerin kameradan uzaklığı hakkında bilgi sağlayan derinlik görüntülerini destekler. Derinlik görüntüleri; engellerden kaçınma, 3D haritalama ve konum belirleme gibi robotik uygulamalar için çok önemlidir.

Derinlik görüntüsü, her pikselin kameradan bir nesneye olan mesafeyi temsil ettiği bir görüntüdür. Renk yakalayan RGB görüntülerinin aksine, derinlik görüntüleri mekansal bilgileri yakalayarak robotların çevrelerinin 3D yapısını algılamasını sağlar.

Derinlik Görüntüleri Elde Etme

Derinlik görüntüleri çeşitli sensörler kullanılarak elde edilebilir:

  1. Stereo Kameralar: Görüntü farklılığına dayalı olarak derinliği hesaplamak için iki kamera kullanın.
  2. Uçuş Süresi (ToF) Kameraları: Işığın bir nesneden geri dönmesi için geçen süreyi ölçün.
  3. Yapılandırılmış Işık Sensörleri: Bir desen yansıtın ve yüzeylerdeki bozulmasını ölçün.

YOLO'yu Derinlik Görüntüleriyle Kullanma

ROS'ta derinlik görüntüleri, kodlama, yükseklik, genişlik ve piksel verileri için alanlar içeren sensor_msgs/Image mesaj türü ile temsil edilir. Derinlik görüntüleri için kodlama alanı genellikle piksel başına 16-bit işaretsiz tamsayıyı belirten "16UC1" gibi bir biçim kullanır; burada her değer nesneye olan uzaklığı temsil eder. Derinlik görüntüleri, çevrenin daha kapsamlı bir görünümünü sağlamak için genellikle RGB görüntüleriyle birlikte kullanılır.

YOLO kullanarak, hem RGB hem de derinlik görüntülerinden bilgi çıkarmak ve bunları birleştirmek mümkündür. Örneğin, YOLO bir RGB görüntüsündeki nesneleri algılayabilir ve bu algılama, derinlik görüntüsündeki ilgili bölgeleri belirlemek için kullanılabilir. Bu, algılanan nesneler için hassas derinlik bilgilerinin çıkarılmasına olanak tanır ve robotun çevresini üç boyutlu olarak anlama yeteneğini geliştirir.

RGB-D Kameralar

Derinlik görüntüleri ile çalışırken, RGB ve derinlik görüntülerinin doğru şekilde hizalandığından emin olmak çok önemlidir. Intel RealSense serisi gibi RGB-D kameralar, senkronize RGB ve derinlik görüntüleri sağlayarak her iki kaynaktan gelen bilgilerin birleştirilmesini kolaylaştırır. Ayrı RGB ve derinlik kameraları kullanılıyorsa, doğru hizalamayı sağlamak için bunları kalibre etmek çok önemlidir.

Adım Adım Derinlik Kullanımı

Bu örnekte, bir görüntüyü segmente etmek için YOLO kullanıyor ve nesneyi derinlik görüntüsünde segmente etmek için çıkarılan maskeyi uyguluyoruz. Bu, ilgi duyulan nesnenin her pikselinin kameranın odak merkezinden uzaklığını belirlememize olanak tanır. Bu mesafe bilgilerini elde ederek, kamera ile sahnedeki belirli nesne arasındaki mesafeyi hesaplayabiliriz. Gerekli kütüphaneleri içe aktararak, bir ROS düğümü oluşturarak ve bir segmentasyon modeli ile bir ROS konusu başlatarak başlayın.

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)

Ardından, gelen derinlik görüntüsü mesajını işleyen bir geri çağırma işlevi tanımlayın. İşlev, derinlik görüntüsü ve RGB görüntüsü mesajlarını bekler, bunları NumPy dizilerine dönüştürür ve segmentasyon modelini RGB görüntüsüne uygular. Ardından, her algılanan nesne için segmentasyon maskesini çıkarır ve derinlik görüntüsünü kullanarak nesnenin kameradan ortalama uzaklığını hesaplar. Çoğu sensörün, değerlerin inf (np.inf) olarak temsil edildiği maksimum bir uzaklığı vardır; buna kırpma uzaklığı denir. İşlemeden önce, bu boş değerleri filtrelemek ve onlara 0 değerini atamak önemlidir. Son olarak, algılanan nesneleri ortalama mesafeleriyle birlikte /ultralytics/detection/distance konusuna yayınlar.

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()
Kodun tamamı
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()

Ultralytics'i ROS sensor_msgs/PointCloud2 ile Kullan

Detection and Segmentation in ROS Gazebo

sensor_msgs/PointCloud2 mesaj türü, ROS'ta 3D nokta bulutu verilerini temsil etmek için kullanılan bir veri yapısıdır. Bu mesaj türü, 3D haritalama, nesne tanıma ve konum belirleme gibi görevleri mümkün kılarak robotik uygulamaların ayrılmaz bir parçasıdır.

Nokta bulutu, üç boyutlu bir koordinat sistemi içinde tanımlanan veri noktaları koleksiyonudur. Bu veri noktaları, 3D tarama teknolojileri aracılığıyla yakalanan bir nesnenin veya sahnenin dış yüzeyini temsil eder. Buluttaki her noktanın, uzaydaki konumuna karşılık gelen X, Y ve Z koordinatları vardır ve ayrıca renk ve yoğunluk gibi ek bilgiler de içerebilir.

Referans çerçevesi

sensor_msgs/PointCloud2 ile çalışırken, nokta bulutu verilerinin elde edildiği sensörün referans çerçevesini dikkate almak önemlidir. Nokta bulutu başlangıçta sensörün referans çerçevesinde yakalanır. /tf_static konusunu dinleyerek bu referans çerçevesini belirleyebilirsiniz. Ancak, belirli uygulama gereksinimlerinize bağlı olarak nokta bulutunu başka bir referans çerçevesine dönüştürmeniz gerekebilir. Bu dönüşüm, koordinat çerçevelerini yönetmek ve verileri aralarında dönüştürmek için araçlar sağlayan tf2_ros paketi kullanılarak gerçekleştirilebilir.

Nokta Bulutları Elde Etme

Nokta Bulutları çeşitli sensörler kullanılarak elde edilebilir:

  1. LIDAR (Işık Algılama ve Uzaklık Belirleme): Nesnelere olan mesafeleri ölçmek ve yüksek hassasiyetli 3D haritalar oluşturmak için lazer darbeleri kullanır.
  2. Derinlik Kameraları: Sahnenin 3D olarak yeniden oluşturulmasına olanak tanıyan her piksel için derinlik bilgisini yakalar.
  3. Stereo Kameralar: Üçgenleme yoluyla derinlik bilgisi elde etmek için iki veya daha fazla kamera kullanır.
  4. Yapılandırılmış Işık Tarayıcıları: Bir yüzeye bilinen bir desen yansıtır ve derinliği hesaplamak için bozulmayı ölçer.

YOLO'yu Nokta Bulutlarıyla Kullanma

YOLO'yu sensor_msgs/PointCloud2 türü mesajlarla entegre etmek için, derinlik haritaları için kullanılan yönteme benzer bir yöntem kullanabiliriz. Nokta bulutuna gömülü renk bilgisinden yararlanarak, 2D bir görüntü çıkarabilir, YOLO kullanarak bu görüntü üzerinde segmentasyon gerçekleştirebilir ve ardından ilgili 3D nesneyi izole etmek için ortaya çıkan maskeyi üç boyutlu noktalara uygulayabiliriz.

Nokta bulutlarını işlemek için, kullanıcı dostu bir Python kütüphanesi olan Open3D'yi (pip install open3d) kullanmanızı öneririz. Open3D; nokta bulutu veri yapılarını yönetmek, görselleştirmek ve karmaşık işlemleri sorunsuz bir şekilde yürütmek için sağlam araçlar sağlar. Bu kütüphane, süreci önemli ölçüde basitleştirebilir ve YOLO tabanlı segmentasyon ile birlikte nokta bulutlarını manipüle etme ve analiz etme yeteneğimizi geliştirebilir.

Adım Adım Nokta Bulutu Kullanımı

Gerekli kütüphaneleri içe aktarın ve segmentasyon için YOLO modelini oluşturun.

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.

İşlev, xyz koordinatlarını ve RGB değerlerini orijinal kamera çözünürlüğü (width x height) formatında döndürür. Çoğu sensörün, değerlerin inf (np.inf) olarak temsil edildiği maksimum bir uzaklığı vardır; buna kırpma uzaklığı denir. İşlemeden önce, bu boş değerleri filtrelemek ve onlara 0 değerini atamak önemlidir.

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

Ardından, nokta bulutu mesajını almak için /camera/depth/points konusuna abone olun ve sensor_msgs/PointCloud2 mesajını XYZ koordinatlarını ve RGB değerlerini içeren NumPy dizilerine dönüştürün (pointcloud2_to_array işlevini kullanarak). Segmentasyonlu nesneleri çıkarmak için RGB görüntüsünü YOLO modeliyle işleyin. Her algılanan nesne için segmentasyon maskesini çıkarın ve nesneyi 3D uzayda izole etmek için maskeyi hem RGB görüntüsüne hem de XYZ koordinatlarına uygulayın.

Maskeyi işlemek basittir çünkü nesnenin varlığını gösteren 1 ve yokluğunu gösteren 0 ile ikili değerlerden oluşur. Maskeyi uygulamak için orijinal kanalları maskeyle çarpmanız yeterlidir. Bu işlem, ilgi duyulan nesneyi görüntü içinde etkili bir şekilde izole eder. Son olarak, bir Open3D nokta bulutu nesnesi oluşturun ve segmente edilmiş nesneyi ilişkili renklerle 3D uzayda görselleştirin.

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])
Kodun tamamı
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

SSS

Robot Operating System (ROS) nedir?

Robot Operating System (ROS), geliştiricilerin sağlam robot uygulamaları oluşturmasına yardımcı olmak için robotikte yaygın olarak kullanılan açık kaynaklı bir çerçevedir. Robotik sistemler oluşturmak ve bunlarla arayüz oluşturmak için kütüphane ve araçlar koleksiyonu sağlar, bu da karmaşık uygulamaların geliştirilmesini kolaylaştırır. ROS, konular veya hizmetler üzerinden mesajlar kullanarak düğümler arasındaki iletişimi destekler.

Ultralytics YOLO'yu gerçek zamanlı nesne algılama için ROS ile nasıl entegre ederim?

Ultralytics YOLO'yu ROS ile entegre etmek, bir ROS ortamı kurmayı ve sensör verilerini işlemek için YOLO kullanmayı içerir. ros_numpy ve Ultralytics YOLO gibi gerekli bağımlılıkları yükleyerek başlayın:

pip install ros_numpy ultralytics

Ardından, bir ROS düğümü oluşturun ve gelen verileri işlemek için bir görüntü konusuna abone olun. İşte minimal bir örnek:

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

ROS konuları nelerdir ve Ultralytics YOLO'da nasıl kullanılırlar?

ROS konuları, bir yayınla-abone ol modeli kullanarak bir ROS ağındaki düğümler arasındaki iletişimi kolaylaştırır. Konu, düğümlerin mesajları eşzamansız olarak gönderip almak için kullandığı adlandırılmış bir kanaldır. Ultralytics YOLO bağlamında, bir düğümün bir görüntü konusuna abone olmasını sağlayabilir, algılama veya segmentasyon gibi görevler için YOLO kullanarak görüntüleri işleyebilir ve sonuçları yeni konulara yayınlayabilirsiniz.

Örneğin, bir kamera konusuna abone olun ve algılama için gelen görüntüyü işleyin:

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

Neden ROS'ta Ultralytics YOLO ile derinlik görüntüleri kullanmalı?

ROS'ta sensor_msgs/Image ile temsil edilen derinlik görüntüleri, engellerden kaçınma, 3D haritalama ve konum belirleme gibi görevler için çok önemli olan nesnelerin kameradan olan uzaklığını sağlar. Derinlik bilgilerini RGB görüntüleriyle birlikte kullanarak, robotlar 3D çevrelerini daha iyi anlayabilirler.

YOLO ile RGB görüntülerinden segmentasyon maskeleri çıkarabilir ve bu maskeleri derinlik görüntülerine uygulayarak hassas 3D nesne bilgileri elde edebilir, robotun navigasyon ve çevresiyle etkileşim yeteneğini geliştirebilirsiniz.

ROS'ta YOLO ile 3D nokta bulutlarını nasıl görselleştirebilirim?

ROS'ta YOLO ile 3D nokta bulutlarını görselleştirmek için:

  1. sensor_msgs/PointCloud2 mesajlarını NumPy dizilerine dönüştürün.
  2. RGB görüntülerini segmente etmek için YOLO kullanın.
  3. Segmentasyon maskesini nokta bulutuna uygulayın.

İşte görselleştirme için Open3D kullanan bir örnek:

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

Bu yaklaşım, robotik uygulamalarda navigasyon ve manipülasyon gibi görevler için yararlı olan segmente edilmiş nesnelerin 3D görselleştirmesini sağlar.

Yorumlar