Guia de início rápido do ROS (Robot Operating System)

ROS Introduction (captioned) from Open Robotics on Vimeo.

O que é o ROS?

O Robot Operating System (ROS) é uma estrutura de código aberto amplamente utilizada na pesquisa e na indústria de robótica. O ROS fornece uma coleção de bibliotecas e ferramentas para ajudar desenvolvedores a criar aplicações robóticas. O ROS foi projetado para funcionar com várias plataformas robóticas, tornando-o uma ferramenta flexível e poderosa para roboticistas.

Principais recursos do ROS

  1. Arquitetura modular: O ROS possui uma arquitetura modular, permitindo que desenvolvedores construam sistemas complexos combinando componentes menores e reutilizáveis chamados nós. Cada nó executa normalmente uma função específica, e os nós comunicam-se entre si usando mensagens através de tópicos ou serviços.

  2. Middleware de comunicação: O ROS oferece uma infraestrutura de comunicação robusta que suporta comunicação entre processos e computação distribuída. Isso é alcançado por meio de um modelo de publicação-inscrição para fluxos de dados (tópicos) e um modelo de solicitação-resposta para chamadas de serviço.

  3. Abstração de hardware: O ROS fornece uma camada de abstração sobre o hardware, permitindo que desenvolvedores escrevam código independente de dispositivo. Isso possibilita que o mesmo código seja usado com diferentes configurações de hardware, facilitando a integração e a experimentação.

  4. Ferramentas e utilitários: O ROS vem com um conjunto rico de ferramentas e utilitários para visualização, depuração e simulação. Por exemplo, o RViz é usado para visualizar dados de sensores e informações de estado do robô, enquanto o Gazebo fornece um ambiente de simulação poderoso para testar algoritmos e designs de robôs.

  5. Ecossistema extenso: O ecossistema ROS é vasto e cresce continuamente, com inúmeros pacotes disponíveis para diferentes aplicações robóticas, incluindo navegação, manipulação, percepção e mais. A comunidade contribui ativamente para o desenvolvimento e manutenção desses pacotes.

Evolução das versões do ROS

Desde o seu desenvolvimento em 2007, o ROS evoluiu através de múltiplas versões, cada uma introduzindo novos recursos e melhorias para atender às necessidades crescentes da comunidade de robótica. O desenvolvimento do ROS pode ser categorizado em duas séries principais: ROS 1 e ROS 2. Este guia foca na versão de Long Term Support (LTS) do ROS 1, conhecida como ROS Noetic Ninjemys, o código também deve funcionar com versões anteriores.

ROS 1 vs. ROS 2

Embora o ROS 1 tenha fornecido uma base sólida para o desenvolvimento robótico, o ROS 2 aborda suas limitações oferecendo:

  • Desempenho em tempo real: Suporte aprimorado para sistemas de tempo real e comportamento determinístico.
  • Segurança: Recursos de segurança aprimorados para uma operação segura e confiável em vários ambientes.
  • Escalabilidade: Melhor suporte para sistemas de múltiplos robôs e implantações em larga escala.
  • Suporte multiplataforma: Compatibilidade expandida com vários sistemas operacionais além do Linux, incluindo Windows e macOS.
  • Comunicação flexível: Uso de DDS para uma comunicação entre processos mais flexível e eficiente.

Mensagens e tópicos do ROS

No ROS, a comunicação entre nós é facilitada através de mensagens e tópicos. Uma mensagem é uma estrutura de dados que define a informação trocada entre nós, enquanto um tópico é um canal nomeado sobre o qual mensagens são enviadas e recebidas. Os nós podem publicar mensagens em um tópico ou subscrever mensagens de um tópico, permitindo que comuniquem-se entre si. Esse modelo de publicação-inscrição permite comunicação assíncrona e desacoplamento entre nós. Cada sensor ou atuador em um sistema robótico geralmente publica dados em um tópico, que podem então ser consumidos por outros nós para processamento ou controle. Para fins deste guia, focaremos em mensagens de Imagem, Profundidade e PointCloud e tópicos de câmera.

Configurando o Ultralytics YOLO com ROS

Este guia foi testado usando este ambiente ROS, que é um fork do repositório ROSbot ROS. Este ambiente inclui o pacote Ultralytics YOLO, um contêiner Docker para configuração fácil, pacotes ROS abrangentes e mundos Gazebo para testes rápidos. Ele foi projetado para funcionar com o Husarion ROSbot 2 PRO. Os exemplos de código fornecidos funcionarão em qualquer ambiente ROS Noetic/Melodic, incluindo simulação e mundo real.

Husarion ROSbot 2 PRO autonomous robot platform

Instalação de dependências

Além do ambiente ROS, você precisará instalar as seguintes dependências:

  • Pacote ROS NumPy: Isso é necessário para conversão rápida entre mensagens de Imagem do ROS e matrizes NumPy.

    pip install ros_numpy
  • Pacote Ultralytics:

    pip install ultralytics

Use o Ultralytics com ROS sensor_msgs/Image

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.

Detection and Segmentation in ROS Gazebo

Uso passo a passo de imagem

O trecho de código a seguir demonstra como usar o pacote Ultralytics YOLO com ROS. Neste exemplo, subscrevemos a um tópico de câmera, processamos a imagem recebida usando YOLO e publicamos os objetos detectados em novos tópicos para detecção e segmentação.

Primeiro, importe as bibliotecas necessárias e instancie dois modelos: um para segmentação e um para detecção. Inicialize um nó ROS (com o nome ultralytics) para permitir a comunicação com o ROS master. Para garantir uma conexão estável, incluímos uma breve pausa, dando ao nó tempo suficiente para estabelecer a conexão antes de prosseguir.

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)

Inicialize dois tópicos ROS: um para detecção e um para segmentação. Esses tópicos serão usados para publicar as imagens anotadas, tornando-as acessíveis para processamento posterior. A comunicação entre os nós é facilitada usando mensagens 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)

Finalmente, crie um assinante que ouve mensagens no tópico /camera/color/image_raw e chama uma função de callback para cada nova mensagem. Esta função de callback recebe mensagens do tipo sensor_msgs/Image, converte-as em uma matriz NumPy usando ros_numpy, processa as imagens com os modelos YOLO instanciados anteriormente, anota as imagens e, em seguida, publica-as de volta nos respectivos tópicos: /ultralytics/detection/image para detecção e /ultralytics/segmentation/image para segmentação.

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()
Código 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()
Depuração

Depurar nós do ROS (Robot Operating System) pode ser desafiador devido à natureza distribuída do sistema. Várias ferramentas podem auxiliar nesse processo:

  1. rostopic echo <TOPIC-NAME>: Este comando permite visualizar mensagens publicadas em um tópico específico, ajudando a inspecionar o fluxo de dados.
  2. rostopic list: Use este comando para listar todos os tópicos disponíveis no sistema ROS, obtendo uma visão geral dos fluxos de dados ativos.
  3. rqt_graph: Esta ferramenta de visualização exibe o gráfico de comunicação entre os nós, fornecendo insights sobre como os nós estão interconectados e como eles interagem.
  4. Para visualizações mais complexas, como representações 3D, você pode usar o RViz. O RViz (ROS Visualization) é uma poderosa ferramenta de visualização 3D para ROS. Ele permite visualizar o estado do seu robô e seu ambiente em tempo real. Com o RViz, você pode ver dados de sensores (por exemplo, sensor_msgs/Image), estados do modelo do robô e vários outros tipos de informação, facilitando a depuração e a compreensão do comportamento do seu sistema robótico.

Publique classes detectadas com 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 de uso de exemplo

Considere um robô de armazém equipado com uma câmera e um modelo de detecção de objetos. Em vez de enviar grandes imagens anotadas pela rede, o robô pode publicar uma lista de classes detectadas como mensagens std_msgs/String. Por exemplo, quando o robô detecta objetos como "caixa", "palete" e "empilhadeira", ele publica essas classes no tópico /ultralytics/detection/classes. Essa informação pode então ser usada por um sistema de monitoramento central para rastrear o inventário em tempo real, otimizar o planejamento de caminho do robô para evitar obstáculos ou acionar ações específicas, como pegar uma caixa detectada. Essa abordagem reduz a largura de banda necessária para a comunicação e foca na transmissão de dados críticos.

Uso passo a passo de string

Este exemplo demonstra como usar o pacote Ultralytics YOLO com ROS. Neste exemplo, subscrevemos a um tópico de câmera, processamos a imagem recebida usando YOLO e publicamos os objetos detectados em um novo tópico /ultralytics/detection/classes usando mensagens std_msgs/String. O pacote ros_numpy é usado para converter a mensagem de Imagem ROS para uma matriz NumPy para processamento com 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()

Use o Ultralytics com imagens de profundidade do ROS

Além de imagens RGB, o ROS suporta imagens de profundidade, que fornecem informações sobre a distância dos objetos da câmera. Imagens de profundidade são cruciais para aplicações robóticas, como desvio de obstáculos, mapeamento 3D e localização.

Uma imagem de profundidade é uma imagem onde cada pixel representa a distância da câmera até um objeto. Ao contrário das imagens RGB que capturam cores, as imagens de profundidade capturam informações espaciais, permitindo que os robôs percebam a estrutura 3D de seu ambiente.

Obtendo imagens de profundidade

Imagens de profundidade podem ser obtidas usando vários sensores:

  1. Câmeras estéreo: Usam duas câmeras para calcular a profundidade com base na disparidade da imagem.
  2. Câmeras Time-of-Flight (ToF): Medem o tempo que a luz leva para retornar de um objeto.
  3. Sensores de luz estruturada: Projetam um padrão e medem sua deformação em superfícies.

Usando YOLO com imagens de profundidade

No ROS, as imagens de profundidade são representadas pelo tipo de mensagem sensor_msgs/Image, que inclui campos para codificação, altura, largura e dados de pixel. O campo de codificação para imagens de profundidade geralmente usa um formato como "16UC1", indicando um inteiro sem sinal de 16 bits por pixel, onde cada valor representa a distância até o objeto. Imagens de profundidade são comumente usadas em conjunto com imagens RGB para fornecer uma visão mais abrangente do ambiente.

Usando YOLO, é possível extrair e combinar informações de imagens RGB e de profundidade. Por exemplo, o YOLO pode detectar objetos dentro de uma imagem RGB, e essa detecção pode ser usada para localizar regiões correspondentes na imagem de profundidade. Isso permite a extração de informações de profundidade precisas para objetos detectados, aprimorando a capacidade do robô de entender seu ambiente em três dimensões.

Câmeras RGB-D

Ao trabalhar com imagens de profundidade, é essencial garantir que as imagens RGB e de profundidade estejam corretamente alinhadas. Câmeras RGB-D, como a série Intel RealSense, fornecem imagens RGB e de profundidade sincronizadas, facilitando a combinação de informações de ambas as fontes. Se usar câmeras RGB e de profundidade separadas, é crucial calibrá-las para garantir um alinhamento preciso.

Uso passo a passo de profundidade

Neste exemplo, usamos o YOLO para segmentar uma imagem e aplicar a máscara extraída para segmentar o objeto na imagem de profundidade. Isso nos permite determinar a distância de cada pixel do objeto de interesse do centro focal da câmera. Ao obter essas informações de distância, podemos calcular a distância entre a câmera e o objeto específico na cena. Comece importando as bibliotecas necessárias, criando um nó ROS e instanciando um modelo de segmentação e um tópico 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)

Em seguida, defina uma função de callback que processa a mensagem de imagem de profundidade recebida. A função aguarda as mensagens de imagem de profundidade e imagem RGB, converte-as em matrizes NumPy e aplica o modelo de segmentação à imagem RGB. Ela então extrai a máscara de segmentação para cada objeto detectado e calcula a distância média do objeto da câmera usando a imagem de profundidade. A maioria dos sensores tem uma distância máxima, conhecida como distância de corte, além da qual os valores são representados como inf (np.inf). Antes de processar, é importante filtrar esses valores nulos e atribuir-lhes um valor de 0. Finalmente, ele publica os objetos detectados junto com suas distâncias médias no tópico /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()
Código 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()

Use o Ultralytics com sensor_msgs/PointCloud2 do ROS

Detection and Segmentation in ROS Gazebo

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.

Uma nuvem de pontos é uma coleção de pontos de dados definidos dentro de um sistema de coordenadas tridimensional. Esses pontos de dados representam a superfície externa de um objeto ou cena, capturados via tecnologias de escaneamento 3D. Cada ponto na nuvem possui coordenadas X, Y e Z, que correspondem à sua posição no espaço, e também pode incluir informações adicionais, como cor e intensidade.

Quadro de referência

Ao trabalhar com sensor_msgs/PointCloud2, é essencial considerar o quadro de referência do sensor a partir do qual os dados da nuvem de pontos foram adquiridos. A nuvem de pontos é inicialmente capturada no quadro de referência do sensor. Você pode determinar esse quadro de referência ouvindo o tópico /tf_static. No entanto, dependendo dos requisitos específicos da sua aplicação, você pode precisar converter a nuvem de pontos em outro quadro de referência. Essa transformação pode ser alcançada usando o pacote tf2_ros, que fornece ferramentas para gerenciar quadros de coordenadas e transformar dados entre eles.

Obtendo nuvens de pontos

Nuvens de pontos podem ser obtidas usando vários sensores:

  1. LIDAR (Light Detection and Ranging): Usa pulsos de laser para medir distâncias até objetos e criar mapas 3D de alta precisão.
  2. Câmeras de profundidade: Capturam informações de profundidade para cada pixel, permitindo a reconstrução 3D da cena.
  3. Câmeras estéreo: Utilizam duas ou mais câmeras para obter informações de profundidade por triangulação.
  4. Scanners de luz estruturada: Projetam um padrão conhecido sobre uma superfície e medem a deformação para calcular a profundidade.

Usando YOLO com nuvens de pontos

Para integrar o YOLO com mensagens do tipo sensor_msgs/PointCloud2, podemos empregar um método semelhante ao usado para mapas de profundidade. Ao aproveitar as informações de cor incorporadas na nuvem de pontos, podemos extrair uma imagem 2D, realizar a segmentação nesta imagem usando o YOLO e, em seguida, aplicar a máscara resultante aos pontos tridimensionais para isolar o objeto 3D de interesse.

Para lidar com nuvens de pontos, recomendamos o uso do Open3D (pip install open3d), uma biblioteca Python fácil de usar. O Open3D fornece ferramentas robustas para gerenciar estruturas de dados de nuvem de pontos, visualizá-las e executar operações complexas perfeitamente. Esta biblioteca pode simplificar significativamente o processo e aumentar nossa capacidade de manipular e analisar nuvens de pontos em conjunto com a segmentação baseada em YOLO.

Uso passo a passo de nuvem de pontos

Importe as bibliotecas necessárias e instancie o modelo YOLO para segmentação.

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

Em seguida, subscreva ao tópico /camera/depth/points para receber a mensagem de nuvem de pontos e converta a mensagem sensor_msgs/PointCloud2 em matrizes NumPy contendo as coordenadas XYZ e os valores RGB (usando a função pointcloud2_to_array). Processe a imagem RGB usando o modelo YOLO para extrair objetos segmentados. Para cada objeto detectado, extraia a máscara de segmentação e aplique-a tanto à imagem RGB quanto às coordenadas XYZ para isolar o objeto no espaço 3D.

O processamento da máscara é direto, pois consiste em valores binários, com 1 indicando a presença do objeto e 0 indicando a ausência. Para aplicar a máscara, basta multiplicar os canais originais pela máscara. Esta operação isola efetivamente o objeto de interesse dentro da imagem. Finalmente, crie um objeto de nuvem de pontos Open3D e visualize o objeto segmentado no espaço 3D com cores associadas.

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])
Código 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])

Point Cloud Segmentation with Ultralytics

FAQ

O que é o Robot Operating System (ROS)?

O Robot Operating System (ROS) é uma estrutura de código aberto comumente usada em robótica para ajudar desenvolvedores a criar aplicações robóticas robustas. Ele fornece uma coleção de bibliotecas e ferramentas para construir e interagir com sistemas robóticos, permitindo um desenvolvimento mais fácil de aplicações complexas. O ROS suporta comunicação entre nós usando mensagens sobre tópicos ou serviços.

Como integrar o Ultralytics YOLO com ROS para detecção de objetos em tempo real?

Integrar o Ultralytics YOLO com o ROS envolve configurar um ambiente ROS e usar o YOLO para processar dados de sensores. Comece instalando as dependências necessárias como ros_numpy e o Ultralytics YOLO:

pip install ros_numpy ultralytics

Em seguida, crie um nó ROS e subscreva a um tópico de imagem para processar os dados recebidos. Aqui está um exemplo mínimo:

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

O que são tópicos ROS e como eles são usados no Ultralytics YOLO?

Tópicos ROS facilitam a comunicação entre nós em uma rede ROS usando um modelo de publicação-inscrição. Um tópico é um canal nomeado que os nós usam para enviar e receber mensagens de forma assíncrona. No contexto do Ultralytics YOLO, você pode fazer um nó subscrever a um tópico de imagem, processar as imagens usando YOLO para tarefas como detecção ou segmentação e publicar os resultados em novos tópicos.

Por exemplo, subscreva a um tópico de câmera e processe a imagem recebida para detecção:

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

Por que usar imagens de profundidade com o Ultralytics YOLO no ROS?

Imagens de profundidade no ROS, representadas por sensor_msgs/Image, fornecem a distância de objetos da câmera, cruciais para tarefas como desvio de obstáculos, mapeamento 3D e localização. Ao usar informações de profundidade juntamente com imagens RGB, os robôs podem entender melhor seu ambiente 3D.

Com o YOLO, você pode extrair máscaras de segmentação de imagens RGB e aplicar essas máscaras a imagens de profundidade para obter informações precisas de objetos 3D, melhorando a capacidade do robô de navegar e interagir com seu entorno.

Como posso visualizar nuvens de pontos 3D com YOLO no ROS?

Para visualizar nuvens de pontos 3D no ROS com YOLO:

  1. Converta mensagens sensor_msgs/PointCloud2 para matrizes NumPy.
  2. Use o YOLO para segmentar imagens RGB.
  3. Aplique a máscara de segmentação à nuvem de pontos.

Aqui está um exemplo usando Open3D para visualização:

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

Esta abordagem fornece uma visualização 3D de objetos segmentados, útil para tarefas como navegação e manipulação em aplicações robóticas.

Comentários