ROS (Robot Operating System) クイックスタートガイド

ROS Introduction (captioned) from Open Robotics on Vimeo.

ROSとは何ですか?

Robot Operating System (ROS) は、ロボット工学の研究や産業界で広く利用されているオープンソースのフレームワークです。ROSは、開発者がロボットアプリケーションを作成するのを支援するためのライブラリとツール群を提供します。ROSは様々なロボットプラットフォームと連携するように設計されており、ロボット研究者にとって柔軟で強力なツールとなっています。

ROSの主な機能

  1. モジュール式アーキテクチャ: ROSはモジュール式のアーキテクチャを採用しており、ノードと呼ばれる小さく再利用可能なコンポーネントを組み合わせることで、開発者は複雑なシステムを構築できます。各ノードは通常特定の機能を実行し、ノード間はトピックまたはサービスを介したメッセージによって通信を行います。

  2. 通信ミドルウェア: ROSは、プロセス間通信と分散コンピューティングをサポートする堅牢な通信インフラストラクチャを提供します。これは、データストリーム(トピック)のためのパブリッシュ・サブスクライブ(発行・購読)モデルと、サービスコールのためのリクエスト・リプライモデルによって実現されています。

  3. ハードウェア抽象化: ROSはハードウェアに対する抽象化レイヤーを提供し、開発者がデバイスに依存しないコードを書くことを可能にします。これにより、同じコードを異なるハードウェア構成で使用できるようになり、統合や実験が容易になります。

  4. ツールとユーティリティ: ROSには、可視化、デバッグ、シミュレーションのための豊富なツールとユーティリティが付属しています。例えば、RVizはセンサーデータやロボットの状態情報を可視化するために使用され、Gazeboはアルゴリズムやロボット設計をテストするための強力なシミュレーション環境を提供します。

  5. 広大なエコシステム: ROSのエコシステムは広大で成長を続けており、ナビゲーション、マニピュレーション、認識など、様々なロボットアプリケーションに対応する多数のパッケージが利用可能です。コミュニティはこれらのパッケージの開発とメンテナンスに積極的に貢献しています。

ROSバージョンの進化

2007年の開発開始以来、ROSは複数のバージョンを経て進化し、各バージョンでロボットコミュニティの増大するニーズに応えるための新機能や改善が導入されてきました。ROSの開発は、ROS 1とROS 2という2つの主要なシリーズに分類できます。本ガイドでは、ROS 1の長期サポート(LTS)バージョンであるROS Noetic Ninjemysに焦点を当てますが、コードは以前のバージョンでも動作するはずです。

ROS 1 と ROS 2 の比較

ROS 1はロボット開発のための強固な基盤を提供しましたが、ROS 2はその欠点を補うために以下を提供します:

  • リアルタイム性能: リアルタイムシステムおよび決定論的動作へのサポート強化。
  • セキュリティ: 様々な環境で安全かつ確実に動作するための強化されたセキュリティ機能。
  • スケーラビリティ: マルチロボットシステムや大規模展開へのより優れたサポート。
  • クロスプラットフォーム対応: Linux以外に、WindowsやmacOSを含む様々なオペレーティングシステムへの互換性拡大。
  • 柔軟な通信: DDSの使用による、より柔軟で効率的なプロセス間通信。

ROSのメッセージとトピック

ROSでは、ノード間の通信はメッセージトピックを通じて促進されます。メッセージはノード間で交換される情報を定義するデータ構造であり、トピックはメッセージが送信・受信される名前付きチャネルです。ノードはトピックにメッセージをパブリッシュ(発行)したり、トピックからメッセージをサブスクライブ(購読)したりすることで、相互に通信できます。このパブリッシュ・サブスクライブモデルにより、ノード間の非同期通信と疎結合が可能になります。ロボットシステムの各センサーやアクチュエータは通常トピックにデータをパブリッシュし、そのデータが他のノードによって処理や制御に使用されます。本ガイドでは、Image、Depth、PointCloudメッセージおよびカメラトピックに焦点を当てます。

Ultralytics YOLO と ROS のセットアップ

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

依存関係のインストール

ROS環境以外に、以下の依存関係をインストールする必要があります:

  • ROS NumPyパッケージ: これは、ROS ImageメッセージとNumPy配列の高速な変換に必要です。

    pip install ros_numpy
  • Ultralytics パッケージ:

    pip install ultralytics

Ultralytics を ROS の sensor_msgs/Image で使用する

sensor_msgs/Image メッセージ型は、ROSで画像データを表現するために一般的に使用されます。これにはエンコーディング、高さ、幅、ピクセルデータのフィールドが含まれており、カメラやその他のセンサーでキャプチャされた画像の伝送に適しています。画像メッセージは、視覚認識、物体検出、ナビゲーションなどのタスクを行うロボットアプリケーションで広く使用されています。

Detection and Segmentation in ROS Gazebo

画像利用のステップバイステップ

以下のコードスニペットは、Ultralytics YOLOパッケージをROSで使用する方法を示しています。この例では、カメラトピックをサブスクライブし、YOLOを使用して入力画像を処理し、検出されたオブジェクトを検出およびセグメンテーション用の新しいトピックにパブリッシュします。

まず、必要なライブラリをインポートし、2つのモデルをインスタンス化します。1つはセグメンテーション用、もう1つは検出用です。ROSマスターとの通信を有効にするために、ROSノード(名前は ultralytics)を初期化します。安定した接続を確保するために、短い一時停止を入れ、ノードが処理を続行する前に接続を確立するための十分な時間を与えます。

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)

2つのROSトピックを初期化します。1つは検出用、もう1つはセグメンテーション用です。これらのトピックは、アノテーション付き画像をパブリッシュし、後の処理のためにアクセス可能にするために使用されます。ノード間の通信には 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)

最後に、/camera/color/image_raw トピックのメッセージをリッスンし、新しいメッセージごとにコールバック関数を呼び出すサブスクライバーを作成します。このコールバック関数は sensor_msgs/Image 型のメッセージを受け取り、ros_numpy を使用してそれをNumPy配列に変換し、前述のYOLOモデルで画像を処理し、画像にアノテーションを付け、最後にそれぞれのトピックにパブリッシュします。検出用には /ultralytics/detection/image、セグメンテーション用には /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()
完成したコード
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()
デバッグ

ROS (Robot Operating System) ノードのデバッグは、システムの分散型性質のため困難な場合があります。このプロセスを支援するいくつかのツールがあります:

  1. rostopic echo <TOPIC-NAME> : このコマンドを使用すると、特定のトピックにパブリッシュされたメッセージを表示でき、データフローを検査するのに役立ちます。
  2. rostopic list: このコマンドを使用して、ROSシステム内で利用可能なすべてのトピックを一覧表示し、アクティブなデータストリームの概要を把握できます。
  3. rqt_graph: この可視化ツールはノード間の通信グラフを表示し、ノードがどのように相互接続され、相互作用しているかについての洞察を提供します。
  4. 3D表現などのより複雑な可視化には、RVizを使用できます。RViz (ROS Visualization) は、ROSのための強力な3D可視化ツールです。これを使用すると、ロボットの状態とその環境をリアルタイムで視覚化できます。RVizでは、センサーデータ(例: sensor_msgs/Image)、ロボットモデルの状態、その他様々な種類の情報を表示できるため、ロボットシステムの動作をデバッグおよび理解しやすくなります。

検出されたクラスを std_msgs/String でパブリッシュする

標準的なROSメッセージには std_msgs/String メッセージも含まれています。多くのアプリケーションでは、アノテーション付き画像全体を再パブリッシュする必要はなく、ロボットの視野内に存在するクラスのみが必要となる場合があります。以下の例では、std_msgs/String メッセージを使用して、検出されたクラスを /ultralytics/detection/classes トピックに再パブリッシュする方法を示します。これらのメッセージは軽量で重要な情報を提供するものであり、様々なアプリケーションにおいて有用です。

使用事例の例

カメラと検出モデルを搭載した倉庫用ロボットを考えます。大きなアノテーション付き画像をネットワーク経由で送信する代わりに、ロボットは検出されたクラスのリストを std_msgs/String メッセージとしてパブリッシュできます。例えば、ロボットが「box」、「pallet」、「forklift」のようなオブジェクトを検出すると、それらのクラスを /ultralytics/detection/classes トピックにパブリッシュします。この情報は、中央監視システムがインベントリをリアルタイムで追跡したり、障害物を避けるためにロボットの経路計画を最適化したり、検出された箱を持ち上げるような特定の動作をトリガーしたりするために使用できます。このアプローチにより、通信に必要な帯域幅が削減され、重要なデータの送信に集中することができます。

String利用のステップバイステップ

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 を ROS の深度画像で使用する

RGB画像に加え、ROSは深度画像をサポートしており、これはカメラからの対象物までの距離に関する情報を提供します。深度画像は、障害物回避、3Dマッピング、位置特定などのロボットアプリケーションにおいて非常に重要です。

深度画像とは、各ピクセルがカメラから対象物までの距離を表す画像です。色をキャプチャするRGB画像とは異なり、深度画像は空間情報をキャプチャし、ロボットが環境の3D構造を認識できるようにします。

深度画像の取得

深度画像は、様々なセンサーを使用して取得できます:

  1. ステレオカメラ: 2つのカメラを使用して、画像の視差に基づいて深度を計算します。
  2. Time-of-Flight (ToF) カメラ: 光が物体から戻ってくるまでの時間を測定します。
  3. 構造化光センサー: パターンを投影し、表面上の変形を測定します。

YOLO を深度画像で使用する

ROSにおいて、深度画像は sensor_msgs/Image メッセージ型で表され、エンコーディング、高さ、幅、およびピクセルデータのフィールドが含まれています。深度画像のエンコーディングフィールドでは、「16UC1」のようなフォーマットがよく使われ、1ピクセルあたり16ビットの符号なし整数であることを示し、各値が対象物までの距離を表します。深度画像は、環境のより包括的なビューを提供するために、RGB画像と組み合わせて使用されることが一般的です。

YOLOを使用すると、RGB画像と深度画像の両方から情報を抽出して組み合わせることが可能です。例えば、YOLOはRGB画像内のオブジェクトを検出し、その検出結果を使用して深度画像の対応する領域を特定できます。これにより、検出されたオブジェクトに対する正確な深度情報の抽出が可能になり、3次元環境を理解するロボットの能力が向上します。

RGB-D カメラ

深度画像を扱う際は、RGB画像と深度画像が正しく位置合わせされていることを確認することが不可欠です。Intel RealSenseシリーズのようなRGB-Dカメラは、同期されたRGB画像と深度画像を提供するため、両方のソースからの情報を組み合わせることが容易になります。個別のRGBカメラと深度カメラを使用する場合は、正確な位置合わせを確実にするためにそれらをキャリブレーションすることが重要です。

深度利用のステップバイステップ

この例では、YOLOを使用して画像をセグメント化し、抽出されたマスクを深度画像に適用してその画像内のオブジェクトをセグメント化します。これにより、対象オブジェクトの各ピクセルがカメラの焦点中心からどれだけ離れているかを決定できます。この距離情報を取得することで、カメラとシーン内の特定のオブジェクト間の距離を計算できます。まず必要なライブラリをインポートし、ROSノードを作成し、セグメンテーションモデルと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)

次に、入力された深度画像メッセージを処理するコールバック関数を定義します。この関数は深度画像とRGB画像のメッセージを待ち、それらをNumPy配列に変換し、RGB画像に対してセグメンテーションモデルを適用します。その後、検出された各オブジェクトのセグメンテーションマスクを抽出し、深度画像を使用してカメラからのオブジェクトの平均距離を計算します。ほとんどのセンサーには最大距離があり、これはクリップ距離と呼ばれ、それを超える値はinf (np.inf)として表現されます。処理の前に、これらのnull値をフィルタリングして 0 を割り当てることが重要です。最後に、検出されたオブジェクトとそれらの平均距離を /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()
完成したコード
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 を ROS の sensor_msgs/PointCloud2 で使用する

Detection and Segmentation in ROS Gazebo

sensor_msgs/PointCloud2 メッセージ型は、3D点群データを表現するためにROSで使用されるデータ構造です。このメッセージ型はロボットアプリケーションに不可欠であり、3Dマッピング、オブジェクト認識、位置特定などのタスクを可能にします。

点群は、3次元座標系内で定義されたデータポイントの集合です。これらのデータポイントは、3Dスキャン技術を通じてキャプチャされたオブジェクトやシーンの外部表面を表します。点群内の各点には、空間内の位置に対応する XYZ 座標があり、色や強度などの追加情報が含まれている場合もあります。

参照フレーム

sensor_msgs/PointCloud2 を扱う際は、点群データが取得されたセンサーの参照フレームを考慮することが不可欠です。点群は最初、センサーの参照フレーム内でキャプチャされます。/tf_static トピックをリッスンすることで、この参照フレームを特定できます。しかし、特定のアプリケーションの要件に応じて、点群を別の参照フレームに変換する必要があるかもしれません。この変換は、座標フレームを管理し、それらの間でデータを変換するためのツールを提供する tf2_ros パッケージを使用して実現できます。

点群の取得

点群は様々なセンサーを使用して取得できます:

  1. LIDAR (Light Detection and Ranging): レーザーパルスを使用して物体までの距離を測定し、高精度な3Dマップを作成します。
  2. 深度カメラ: 各ピクセルの深度情報をキャプチャし、シーンの3D再構築を可能にします。
  3. ステレオカメラ: 2つ以上のカメラを利用して、三角測量により深度情報を取得します。
  4. 構造化光スキャナー: 既知のパターンを表面に投影し、その変形を測定して深度を計算します。

YOLO を点群で使用する

YOLOを sensor_msgs/PointCloud2 型メッセージと統合するには、深度マップに使用される手法と類似した方法を採用できます。点群に埋め込まれた色情報を活用することで、2D画像を抽出し、YOLOを使用してその画像に対してセグメンテーションを実行し、その結果得られたマスクを3次元の点に適用して、対象となる3Dオブジェクトを切り出すことができます。

点群の取り扱いには、ユーザーフレンドリーなPythonライブラリであるOpen3D (pip install open3d)の使用を推奨します。Open3Dは、点群データ構造の管理、視覚化、および複雑な操作をシームレスに実行するための堅牢なツールを提供します。このライブラリは、プロセスを大幅に簡略化し、YOLOベースのセグメンテーションと組み合わせて点群を操作・分析する能力を向上させます。

点群利用のステップバイステップ

必要なライブラリをインポートし、セグメンテーション用のYOLOモデルをインスタンス化します。

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, rgb

Next, subscribe to the /camera/depth/points topic to receive the point cloud message and convert the sensor_msgs/PointCloud2 message into NumPy arrays containing the XYZ coordinates and RGB values (using the pointcloud2_to_array function). Process the RGB image using the YOLO model to extract segmented objects. For each detected object, extract the segmentation mask and apply it to both the RGB image and the XYZ coordinates to isolate the object in 3D space.

マスクの適用は、1 がオブジェクトの存在を示し 0 が不在を示すバイナリ値で構成されているため簡単です。マスクを適用するには、元のチャネルにマスクを掛けるだけです。この操作により、画像内の対象オブジェクトが効果的に切り出されます。最後に、Open3D点群オブジェクトを作成し、関連付けられた色と共に3D空間内のセグメント化されたオブジェクトを視覚化します。

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])
完成したコード
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

Robot Operating System (ROS) とは何ですか?

Robot Operating System (ROS) は、開発者が堅牢なロボットアプリケーションを作成するのを支援するためにロボット工学で一般的に使用されるオープンソースのフレームワークです。これは、ロボットシステムの構築および連携のためのライブラリとツール群を提供し、複雑なアプリケーションの開発を容易にします。ROSは、トピックまたはサービスを介したメッセージを使用して、ノード間の通信をサポートしています。

Ultralytics YOLO を ROS と統合してリアルタイム物体検出を行うにはどうすればよいですか?

Ultralytics YOLOをROSと統合するには、ROS環境のセットアップと、センサーデータ処理のためのYOLOの使用が含まれます。まず、ros_numpy や Ultralytics YOLOのような必要な依存関係をインストールします:

pip install ros_numpy ultralytics

次に、ROSノードを作成し、画像トピックをサブスクライブして入力データを処理します。以下に最小限の例を示します:

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トピックとは何ですか?また、Ultralytics YOLOでどのように使用されますか?

ROSトピックは、パブリッシュ・サブスクライブモデルを使用して、ROSネットワーク内のノード間通信を促進します。トピックは、ノードがメッセージを非同期に送受信するために使用する名前付きチャネルです。Ultralytics YOLOの文脈では、ノードに画像トピックをサブスクライブさせ、検出セグメンテーションなどのタスクのためにYOLOを使用して画像を処理し、結果を新しいトピックにパブリッシュさせることができます。

例えば、カメラトピックをサブスクライブし、検出のために入力画像を処理します:

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

なぜ Ultralytics YOLO を ROS で深度画像と一緒に使用するのですか?

sensor_msgs/Image で表現されるROSの深度画像は、カメラからのオブジェクトの距離を提供し、障害物回避、3Dマッピング、位置特定などのタスクにおいて極めて重要です。RGB画像と共に深度情報を使用することで、ロボットは自身の3D環境をよりよく理解できます。

YOLOを使用すると、RGB画像からセグメンテーションマスクを抽出し、それらのマスクを深度画像に適用して正確な3Dオブジェクト情報を取得できるため、ロボットのナビゲーションや周囲環境との対話能力が向上します。

ROSでYOLOを使用して3D点群を可視化するにはどうすればよいですか?

ROSでYOLOを使用して3D点群を可視化するには:

  1. sensor_msgs/PointCloud2 メッセージをNumPy配列に変換します。
  2. YOLOを使用してRGB画像をセグメント化します。
  3. セグメンテーションマスクを点群に適用します。

以下は、可視化のために Open3D を使用する例です:

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

このアプローチは、セグメント化されたオブジェクトの3D可視化を提供し、ロボットアプリケーションにおけるナビゲーションやマニピュレーションなどのタスクに有用です。

コメント