Guia de início rápido do ROS (Sistema Operativo de Robôs)
Introdução ao ROS (legendado) from Open Robotics on Vimeo.
O que é o ERO?
O Sistema Operativo de Robôs (ROS) é uma estrutura de código aberto amplamente utilizada na investigação e na indústria da robótica. O ROS fornece uma coleção de bibliotecas e ferramentas para ajudar os programadores a criar aplicações para robôs. O ROS foi concebido para funcionar com várias plataformas robóticas, o que o torna uma ferramenta flexível e poderosa para os roboticistas.
Principais caraterísticas do ROS
-
Arquitetura Modular: O ROS tem uma arquitetura modular, permitindo aos programadores construir sistemas complexos através da combinação de componentes mais pequenos e reutilizáveis chamados nós. Cada nó tipicamente executa uma função específica, e os nós comunicam uns com os outros usando mensagens sobre tópicos ou serviços.
-
Middleware de comunicação: O ROS oferece uma infraestrutura de comunicação robusta que suporta a comunicação entre processos e a computação distribuída. Isto é conseguido através de um modelo de publicação-subscrição para fluxos de dados (tópicos) e um modelo de pedido-resposta para chamadas de serviço.
-
Abstração de Hardware: O ROS fornece uma camada de abstração sobre o hardware, permitindo que os desenvolvedores escrevam código independente de dispositivo. Isso permite que o mesmo código seja usado com diferentes configurações de hardware, facilitando a integração e a experimentação.
-
Ferramentas e utilitários: O ROS vem com um rico conjunto de ferramentas e utilitários para visualização, depuração e simulação. Por exemplo, o RViz é utilizado para visualizar dados de sensores e informações sobre o estado do robô, enquanto o Gazebo fornece um poderoso ambiente de simulação para testar algoritmos e designs de robôs.
-
Ecossistema extenso: O ecossistema ROS é vasto e está em constante crescimento, com inúmeros pacotes disponíveis para diferentes aplicações robóticas, incluindo navegação, manipulação, perceção e muito mais. A comunidade contribui ativamente para o desenvolvimento e manutenção destes pacotes.
Evolução das versões do ROS
Desde o seu desenvolvimento em 2007, o ROS evoluiu através de várias versões, cada uma introduzindo novas funcionalidades e melhorias para satisfazer as necessidades crescentes da comunidade robótica. O desenvolvimento do ROS pode ser categorizado em duas séries principais: ROS 1 e ROS 2: ROS 1 e ROS 2. Este guia centra-se na versão 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
Enquanto o ROS 1 forneceu uma base sólida para o desenvolvimento de robótica, o ROS 2 resolve as suas deficiências oferecendo:
- Desempenho em tempo real: Suporte melhorado para sistemas em tempo real e comportamento determinístico.
- Segurança: Caraterísticas de segurança melhoradas para um funcionamento seguro e fiável em vários ambientes.
- Escalabilidade: Melhor suporte para sistemas multi-robô e implementações em grande escala.
- Suporte multiplataforma: Compatibilidade alargada com vários sistemas operativos para além do Linux, incluindo o Windows e o macOS.
- Comunicação flexível: Utilização de DDS para uma comunicação inter-processos mais flexível e eficiente.
Mensagens e tópicos do ROS
No ROS, a comunicação entre os nós é facilitada através de mensagens e tópicos. Uma mensagem é uma estrutura de dados que define a informação trocada entre os nós, enquanto um tópico é um canal nomeado através do qual as mensagens são enviadas e recebidas. Os nós podem publicar mensagens num tópico ou subscrever mensagens de um tópico, permitindo-lhes comunicar uns com os outros. Este modelo de publicação e subscrição permite a comunicação assíncrona e a dissociação entre nós. Cada sensor ou atuador de um sistema robótico publica normalmente dados num tópico, que podem depois ser consumidos por outros nós para processamento ou controlo. Para efeitos deste guia, centrar-nos-emos nas mensagens Image, Depth e PointCloud e nos tópicos da câmara.
Configuração de 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 contentor Docker para facilitar a configuração, pacotes ROS abrangentes e mundos Gazebo para testes rápidos. Ele foi projetado para funcionar com o ROSbot 2 PRO da Husarion. Os exemplos de código fornecidos funcionarão em qualquer ambiente ROS Noetic/Melodic, incluindo simulação e mundo real.
Instalação de dependências
Para além do ambiente ROS, é necessário instalar as seguintes dependências:
-
Pacote ROS Numpy: É necessário para a conversão rápida entre mensagens de imagem ROS e matrizes numpy.
-
Ultralytics pacote:
Utilizar Ultralytics com o ROS sensor_msgs/Image
O sensor_msgs/Image
tipo de mensagem é normalmente utilizado no ROS para representar dados de imagem. Contém campos para codificação, altura, largura e dados de pixéis, o que o torna adequado para transmitir imagens captadas por câmaras ou outros sensores. As mensagens de imagem são amplamente utilizadas em aplicações robóticas para tarefas como a perceção visual, deteção de objectose navegação.
Utilização passo-a-passo da imagem
O trecho de código a seguir demonstra como usar o pacote Ultralytics YOLO com o ROS. Neste exemplo, subscrevemos um tópico de câmara, processamos a imagem de entrada utilizando YOLO e publicamos os objectos detectados em novos tópicos para deteção e segmentação.
Em primeiro lugar, importar as bibliotecas necessárias e instanciar dois modelos: um para segmentação e um para deteção. Inicializar um nó ROS (com o nome ultralytics
) para permitir a comunicação com o mestre do ROS. Para garantir uma ligação estável, incluímos uma breve pausa, dando ao nó tempo suficiente para estabelecer a ligação antes de prosseguir.
import time
import rospy
from ultralytics import YOLO
detection_model = YOLO("yolov8m.pt")
segmentation_model = YOLO("yolov8m-seg.pt")
rospy.init_node("ultralytics")
time.sleep(1)
Inicializar dois tópicos do ROS: um para deteção e um para segmentação. Estes tópicos serão utilizados para publicar as imagens anotadas, tornando-as acessíveis para processamento posterior. A comunicação entre os nós é facilitada utilizando sensor_msgs/Image
mensagens.
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)
Por fim, crie um subscritor que ouve mensagens no ficheiro /camera/color/image_raw
e chama uma função de retorno de chamada para cada nova mensagem. Esta função de retorno de chamada recebe mensagens do tipo sensor_msgs/Image
converte-os numa matriz numpy utilizando ros_numpy
processa as imagens com os modelos YOLO previamente instanciados, anota as imagens e publica-as de novo nos respectivos tópicos: /ultralytics/detection/image
para deteçã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("yolov8m.pt")
segmentation_model = YOLO("yolov8m-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
A depuração de nós do ROS (Robot Operating System) pode ser um desafio devido à natureza distribuída do sistema. Várias ferramentas podem ajudar neste processo:
rostopic echo <TOPIC-NAME>
: Este comando permite-lhe ver as mensagens publicadas num tópico específico, ajudando-o a inspecionar o fluxo de dados.rostopic list
: Utilize este comando para listar todos os tópicos disponíveis no sistema ROS, dando-lhe uma visão geral dos fluxos de dados activos.rqt_graph
: Esta ferramenta de visualização apresenta o gráfico de comunicação entre nós, fornecendo informações sobre como os nós estão interligados e como interagem.- Para visualizações mais complexas, como representações em 3D, pode utilizar RViz. RViz (ROS Visualization) é uma poderosa ferramenta de visualização 3D para ROS. Permite-lhe visualizar o estado do seu robô e do seu ambiente em tempo real. Com o RViz, pode visualizar os dados dos sensores (por exemplo
sensors_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.
Publicar classes detectadas com std_msgs/String
As mensagens padrão do ROS também incluem std_msgs/String
mensagens. Em muitas aplicações, não é necessário republicar toda a imagem anotada; em vez disso, apenas são necessárias as classes presentes na vista do robot. O exemplo seguinte demonstra como utilizar std_msgs/String
mensagens para republicar as classes detectadas no /ultralytics/detection/classes
tópico. Estas mensagens são mais leves e fornecem informações essenciais, o que as torna valiosas para várias aplicações.
Exemplo de caso de utilização
Considere-se um robô de armazém equipado com uma câmara e um objeto modelo de deteção. Em vez de enviar grandes imagens anotadas através da rede, o robot pode publicar uma lista de classes detectadas como std_msgs/String
mensagens. Por exemplo, quando o robô detecta objectos como "caixa", "palete" e "empilhador", publica estas classes no /ultralytics/detection/classes
tópico. Esta informação pode então ser utilizada por um sistema de monitorização central para acompanhar o inventário em tempo real, otimizar o planeamento da trajetória do robô para evitar obstáculos ou desencadear acções específicas, como a recolha de uma caixa detectada. Esta abordagem reduz a largura de banda necessária para a comunicação e concentra-se na transmissão de dados críticos.
String Utilização passo a passo
Este exemplo demonstra como usar o pacote Ultralytics YOLO com o ROS. Neste exemplo, subscrevemos um tópico de câmara, processamos a imagem de entrada utilizando YOLO e publicamos os objectos detectados num novo tópico /ultralytics/detection/classes
utilizando std_msgs/String
mensagens. As ros_numpy
é utilizado para converter a mensagem de imagem ROS numa 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("yolov8m.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()
Utilizar Ultralytics com imagens de profundidade do ROS
Para além das imagens RGB, o ROS suporta imagens de profundidade, que fornecem informações sobre a distância dos objectos à câmara. As imagens de profundidade são cruciais para aplicações robóticas como a prevenção de obstáculos, o mapeamento 3D e a localização.
Uma imagem de profundidade é uma imagem em que cada pixel representa a distância da câmara a um objeto. Ao contrário das imagens RGB que captam a cor, as imagens de profundidade captam informações espaciais, permitindo aos robots percecionar a estrutura 3D do seu ambiente.
Obtenção de imagens de profundidade
As imagens de profundidade podem ser obtidas utilizando vários sensores:
- Câmaras estéreo: Utilizar duas câmaras para calcular a profundidade com base na disparidade da imagem.
- Câmaras de tempo de voo (ToF): Medem o tempo que a luz demora a regressar de um objeto.
- Sensores de luz estruturada: Projetar um padrão e medir a sua deformação em superfícies.
Utilizar YOLO com imagens de profundidade
No ROS, as imagens de profundidade são representadas pelo sensor_msgs/Image
tipo de mensagem, que inclui campos para codificação, altura, largura e dados de pixel. O campo de codificação para imagens de profundidade utiliza frequentemente um formato como "16UC1", indicando um número inteiro sem sinal de 16 bits por pixel, em que cada valor representa a distância ao objeto. As imagens de profundidade são normalmente utilizadas em conjunto com imagens RGB para proporcionar uma visão mais abrangente do ambiente.
Utilizando YOLO, é possível extrair e combinar informações de imagens RGB e de profundidade. Por exemplo, o YOLO pode detetar objectos numa imagem RGB, e esta deteção pode ser utilizada para identificar as regiões correspondentes na imagem de profundidade. Isto permite a extração de informações precisas sobre a profundidade dos objectos detectados, melhorando a capacidade do robô para compreender o seu ambiente em três dimensões.
Câmaras RGB-D
Ao trabalhar com imagens de profundidade, é essencial garantir que as imagens RGB e de profundidade estão corretamente alinhadas. As câmaras 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 utilizar câmaras RGB e de profundidade separadas, é crucial calibrá-las para garantir um alinhamento preciso.
Profundidade Utilização passo-a-passo
Neste exemplo, utilizamos YOLO para segmentar uma imagem e aplicamos a máscara extraída para segmentar o objeto na imagem de profundidade. Isto permite-nos determinar a distância de cada pixel do objeto de interesse em relação ao centro focal da câmara. Ao obter esta informação de distância, podemos calcular a distância entre a câmara e o objeto específico na cena. Comece importando as bibliotecas necessárias, criando um nó do ROS e instanciando um modelo de segmentação e um tópico do 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("yolov8m-seg.pt")
classes_pub = rospy.Publisher("/ultralytics/detection/distance", String, queue_size=5)
Em seguida, defina uma função de retorno de chamada que processa a mensagem de imagem de profundidade recebida. A função aguarda as mensagens da imagem de profundidade e da imagem RGB, converte-as em matrizes numpy e aplica o modelo de segmentação à imagem RGB. Em seguida, extrai a máscara de segmentação para cada objeto detectado e calcula a distância média do objeto à câmara utilizando a imagem de profundidade. A maioria dos sensores tem uma distância máxima, conhecida como a distância de recorte, para além da qual os valores são representados como inf (np.inf
). Antes do processamento, é importante filtrar estes valores nulos e atribuir-lhes um valor de 0
. Finalmente, publica os objectos detectados juntamente com as suas distâncias médias ao /ultralytics/detection/distance
tema.
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)
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
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("yolov8m-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)
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
classes_pub.publish(String(data=str(all_objects)))
rospy.Subscriber("/camera/depth/image_raw", Image, callback)
while True:
rospy.spin()
Utilizar Ultralytics com o ROS sensor_msgs/PointCloud2
O sensor_msgs/PointCloud2
tipo de mensagem é uma estrutura de dados usada no ROS para representar dados de nuvem de pontos 3D. Este tipo de mensagem é parte integrante das aplicações robóticas, permitindo tarefas como o mapeamento 3D, o reconhecimento de objectos e a localização.
Uma nuvem de pontos é uma coleção de pontos de dados definidos num sistema de coordenadas tridimensional. Estes pontos de dados representam a superfície externa de um objeto ou de uma cena, capturados através de tecnologias de digitalização 3D. Cada ponto da nuvem tem X
, Y
e Z
coordenadas, que correspondem à sua posição no espaço, e podem também incluir informações adicionais, como a cor e a intensidade.
Quadro de referência
Ao trabalhar com sensor_msgs/PointCloud2
Para obter uma nuvem de pontos, é 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. Pode determinar este quadro de referência ouvindo o /tf_static
tópico. No entanto, dependendo dos requisitos específicos da aplicação, pode ser necessário converter a nuvem de pontos noutra estrutura de referência. Essa transformação pode ser obtida usando a função tf2_ros
que fornece ferramentas para gerir quadros de coordenadas e transformar dados entre eles.
Obtenção de nuvens de pontos
As nuvens de pontos podem ser obtidas utilizando vários sensores:
- LIDAR (Light Detection and Ranging): Utiliza impulsos laser para medir distâncias a objectos e criar mapas 3D de alta precisão.
- Câmaras de profundidade: Capturam informações de profundidade para cada pixel, permitindo a reconstrução 3D da cena.
- Câmaras estéreo: Utilizam duas ou mais câmaras para obter informações de profundidade através de triangulação.
- Scanners de luz estruturada: Projectam um padrão conhecido numa superfície e medem a deformação para calcular a profundidade.
Utilizar YOLO com nuvens de pontos
Para integrar YOLO com sensor_msgs/PointCloud2
Para as mensagens do tipo "nuvem de pontos", podemos utilizar um método semelhante ao utilizado para os mapas de profundidade. Aproveitando as informações de cor incorporadas na nuvem de pontos, podemos extrair uma imagem 2D, efetuar a segmentação desta imagem utilizando 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 a utilização do Open3D (pip install open3d
), uma biblioteca Python de fácil utilização. O Open3D fornece ferramentas robustas para gerir estruturas de dados de nuvens de pontos, visualizá-las e executar operações complexas sem problemas. Esta biblioteca pode simplificar significativamente o processo e melhorar a nossa capacidade de manipular e analisar nuvens de pontos em conjunto com a segmentação baseada em YOLO.
Nuvens de pontos Utilização passo-a-passo
Importar as bibliotecas necessárias e instanciar o modelo YOLO para segmentação.
import time
import rospy
from ultralytics import YOLO
rospy.init_node("ultralytics")
time.sleep(1)
segmentation_model = YOLO("yolov8m-seg.pt")
Criar uma função pointcloud2_to_array
, que transforma a sensor_msgs/PointCloud2
em dois arrays numpy. O sensor_msgs/PointCloud2
as mensagens contêm n
pontos com base no width
e height
da imagem adquirida. Por exemplo, um 480 x 640
a imagem terá 307,200
pontos. Cada ponto inclui três coordenadas espaciais (xyz
) e a cor correspondente em RGB
formato. Estes podem ser considerados como dois canais de informação distintos.
A função devolve o xyz
coordenadas e RGB
valores no formato da resolução original da câmara (width x height
). A maioria dos sensores tem uma distância máxima, conhecida como distância de clipe, para além da qual os valores são representados como inf (np.inf
). Antes do processamento, é importante filtrar estes valores nulos e atribuir-lhes um valor de 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 o /camera/depth/points
para receber a mensagem da nuvem de pontos e converter o sensor_msgs/PointCloud2
em matrizes numpy que contêm as coordenadas XYZ e os valores RGB (utilizando a função pointcloud2_to_array
função). Processe a imagem RGB utilizando o modelo YOLO para extrair objectos segmentados. Para cada objeto detectado, extraia a máscara de segmentação e aplique-a à imagem RGB e às coordenadas XYZ para isolar o objeto no espaço 3D.
O processamento da máscara é simples, uma vez que 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. Por fim, 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 ultralytics import YOLO
rospy.init_node("ultralytics")
time.sleep(1)
segmentation_model = YOLO("yolov8m-seg.pt")
def pointcloud2_to_array(pointcloud2: PointCloud2) -> tuple:
"""
Convert a ROS PointCloud2 message to a numpy array.
Args:
pointcloud2 (PointCloud2): the PointCloud2 message
Returns:
(tuple): tuple containing (xyz, rgb)
"""
pc_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud2)
split = ros_numpy.point_cloud2.split_rgb_field(pc_array)
rgb = np.stack([split["b"], split["g"], split["r"]], axis=2)
xyz = ros_numpy.point_cloud2.get_xyz_points(pc_array, remove_nans=False)
xyz = np.array(xyz).reshape((pointcloud2.height, pointcloud2.width, 3))
nan_rows = np.isnan(xyz).all(axis=2)
xyz[nan_rows] = [0, 0, 0]
rgb[nan_rows] = [0, 0, 0]
return xyz, rgb
ros_cloud = rospy.wait_for_message("/camera/depth/points", PointCloud2)
xyz, rgb = pointcloud2_to_array(ros_cloud)
result = segmentation_model(rgb)
if not len(result[0].boxes.cls):
print("No objects detected")
sys.exit()
classes = result[0].boxes.cls.cpu().numpy().astype(int)
for index, class_id in enumerate(classes):
mask = result[0].masks.data.cpu().numpy()[index, :, :].astype(int)
mask_expanded = np.stack([mask, mask, mask], axis=2)
obj_rgb = rgb * mask_expanded
obj_xyz = xyz * mask_expanded
pcd = o3d.geometry.PointCloud()
pcd.points = o3d.utility.Vector3dVector(obj_xyz.reshape((ros_cloud.height * ros_cloud.width, 3)))
pcd.colors = o3d.utility.Vector3dVector(obj_rgb.reshape((ros_cloud.height * ros_cloud.width, 3)) / 255)
o3d.visualization.draw_geometries([pcd])
FAQ
O que é o Sistema Operativo de Robôs (ROS)?
O Sistema Operativo de Robôs (ROS) é uma estrutura de código aberto normalmente utilizada na robótica para ajudar os programadores a criar aplicações robóticas robustas. Fornece uma coleção de bibliotecas e ferramentas para a construção e interface com sistemas robóticos, permitindo um desenvolvimento mais fácil de aplicações complexas. O ROS suporta a comunicação entre nós através de mensagens sobre tópicos ou serviços.
Como é que integro Ultralytics YOLO com o ROS para deteção de objectos em tempo real?
A integração do Ultralytics YOLO com o ROS envolve a configuração de um ambiente ROS e a utilização do YOLO para o processamento de dados de sensores. Comece por instalar as dependências necessárias, como ros_numpy
e Ultralytics YOLO :
Em seguida, crie um nó ROS e subscreva um tópico de imagem para processar os dados de entrada. Aqui está um exemplo mínimo:
import ros_numpy
import rospy
from sensor_msgs.msg import Image
from ultralytics import YOLO
detection_model = YOLO("yolov8m.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 são utilizados em Ultralytics YOLO ?
Os tópicos do ROS facilitam a comunicação entre os nós em uma rede ROS usando um modelo publicar-subscrever. Um tópico é um canal nomeado que os nós usam para enviar e receber mensagens de forma assíncrona. No contexto de Ultralytics YOLO , é possível fazer com que um nó assine um tópico de imagem, processe as imagens usando YOLO para tarefas como deteção ou segmentação e publique os resultados em novos tópicos.
Por exemplo, subscrever um tópico de câmara e processar a imagem de entrada para deteção:
Porquê utilizar imagens de profundidade com Ultralytics YOLO no ROS?
Imagens de profundidade no ROS, representadas por sensor_msgs/Image
fornecem a distância dos objectos à câmara, crucial para tarefas como a prevenção de obstáculos, o mapeamento 3D e a localização. Por utilização de informação de profundidade juntamente com imagens RGB, os robots podem compreender melhor o seu ambiente 3D.
Com YOLO, é possível extrair máscaras de segmentação de imagens RGB e aplicá-las a imagens de profundidade para obter informações precisas sobre objectos 3D, melhorando a capacidade do robô para navegar e interagir com o ambiente que o rodeia.
Como é que posso visualizar nuvens de pontos 3D com YOLO no ROS?
Para visualizar nuvens de pontos 3D no ROS com YOLO:
- Converter
sensor_msgs/PointCloud2
mensagens para matrizes numpy. - Utilize YOLO para segmentar imagens RGB.
- Aplique a máscara de segmentação à nuvem de pontos.
Eis um exemplo de utilização do 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("yolov8m-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 objectos segmentados, útil para tarefas como a navegação e a manipulação.