前言
- 本系列教程旨在使用
UE5
配置一个具备激光雷达
+深度摄像机
的仿真小车,并使用通过跨平台的方式进行ROS2
和UE5
仿真的通讯,达到小车自主导航的目的。 - 本教程默认有ROS2导航及其gazebo仿真相关方面基础,Nav2相关的学习教程可以参考本人的其他博客Nav2代价地图实现和原理--Nav2源码解读之CostMap2D(上)-CSDN博客
- UE5系列教程:UE5-C++入门教程(一):使用代码创建一个指定目标的移动小球-CSDN博客
- 第一期:基于UE5和ROS2的激光雷达+深度RGBD相机小车的仿真指南(一)---UnrealCV获取深度+分割图像-CSDN博客
- 本教程环境支持:
- UE5.43
- ubuntu 22.04 ros2 humble
- 上一节我们以及获取到了深度和分割图像的图像数据,本节我们来看看如何使用
rosbridge
进行图像传输
ROSbrige-suite
rosbridge
是一个用于在 ROS (Robot Operating System) 和其他编程语言或框架之间进行通信的桥梁。它允许开发者使用不同的编程语言(如 Python、JavaScript、Java、MATLAB 等)来与 ROS 系统进行交互,而无需直接使用 ROS 的 C++ API。rosbridge
主要由两部分组成:- ROS 端:运行在 ROS 系统上的服务器,负责与 ROS 系统进行交互。它可以将 ROS 消息、服务、动作等转换为可以通过网络传输的格式。
- 客户端:运行在非 ROS 系统上的客户端,负责与 ROS 端通信,并将接收到的数据转换为客户端语言或框架可以理解的形式。
rosbridge
支持多种通信协议,包括 WebSocket、TCP 和 UDP。这使得它可以在不同的网络环境中工作,无论是本地网络还是互联网。
安装与基础使用
- 这里推荐使用
humble
版本安装
bash
sudo apt-get install ros-humble-rosbridge-suite
rosbridge
的使用也是非常方便
bash
source /opt/ros/humble/setup.bash
ros2 launch rosbridge_server rosbridge_websocket_launch.xml
- 运行成功后,终端会输出如下内容,这里
rosbridge
默认会打开9090端口进行监听,一会我们发送信息也只需要发送到这里即可
尝试使用发送ROSbrige
一张图片
- 由于我们的UE5仿真及其数据捕获程序运行在windows11,而我们的只要Nav2导航处理程序在ubuntu端,这里我们就需要使用
ROSbrige
进行通讯
1. ip查询
- 在进行
ROSbrige
的websocket
通讯之前,在保证win11和ubuntu处于同一局域网的前提下,我们需要知道ubuntu端的ip地址 - 在ubuntu终端输入
ip adrr show
查看ip地址,这里我的虚拟机ip是192.168.137.129
2. 消息类型确认
- 在查询好ip地址后,我们需要确定传输的消息类型,这里我们传输的是图像类型,那我们就选择最常见的
sensor_msgs/msg/image
类型的图片,我们来查询这个消息下有什么
bash
ros2 interface show sensor_msgs/msg/Image
-
我们会得到以下输出:
-
玩过ROS2的朋友都不陌生吧,那我简单说明一下
uint32 height
:图像的高度uint32 width
:图像的宽度string encoding
:像素的编码方式,包括通道的含义、顺序和大小。uint8 is_bigendian
:表示图像数据是否使用大端字节序。在大多数现代系统中,y一般是0
(小端字节序)。uint32 step
:图像的完整行长度(以字节为单位)。这通常是width * channels * bytes_per_channel
。例如,对于宽度为 640 像素、3 个通道(如 RGB 图像)的图像,步长将是 640 * 3 = 1920 字节。uint8[] data
:实际的图像数据矩阵。其大小是step * rows
,即步长乘以行数。
编写Win11发送端
- 那我们我们就来根据上述
sensor_msgs/msg/image
所需要的消息类型,我们来编写发送端
python
import websocket
import cv2
import base64
import json
import numpy as np
# Ubuntu的IP地址
ubuntu_ip = "192.168.137.129"
# 创建WebSockets连接
ws = websocket.create_connection(f"ws://{ubuntu_ip}:9090")
image_path = r"C:\Users\lzh\Desktop\UE5_ROS2_project\camera\lit.png"
img=cv2.imread(image_path)
print(img.shape)
img=img.astype(np.uint8)
# 将图像数据转换为Base64编码的字符串
encoded_string = base64.b64encode(img).decode('utf-8')
# sensor_msgs/msg/image的JSON表示
msg = {
"op": "publish",
"topic": "/image",
"msg": {
"data": encoded_string,
"height": 480,
"width": 640,
"step": 640 * 3 ,
"encoding": "bgr8"
}
}
while True:
# 发送消息
ws.send(json.dumps(msg))
# 关闭连接
ws.close()
- 上述代码很简单,相信大家都能看得懂,需要注意的是data需要是json可迭代对象,所以这里转换为
base64
编写ubuntu接受端data
- 接收端我采用cpp,创建了一个ament_cmake的功能包
- 那么接收端就更简单了,这里我们只创建一个订阅,用于广播
image
的类型,我们把显示交给rviz2
,直接看代码
cpp
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/image.hpp>
class ImageSubscriber : public rclcpp::Node
{
public:
ImageSubscriber()
: Node("image_subscriber")
{
subscription_ = this->create_subscription<sensor_msgs::msg::Image>(
"image", 10, std::bind(&ImageSubscriber::image_callback, this, std::placeholders::_1));
}
private:
void image_callback(const sensor_msgs::msg::Image::SharedPtr msg) const
{
RCLCPP_INFO(this->get_logger(), "Received image");
}
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr subscription_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
auto node = std::make_shared<ImageSubscriber>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
运行与展示
-
值得一提的是,如果你只运行了win11的发送端和ubuntu的rosbridge,不运行接收端,那么你可能会得到一下错误
-
这是由于在 ROS 中,主题必须先被广告,然后才能接收消息。这意味着在尝试发布消息之前,需要确保有一个节点正在监听
/image
主题,并且已经广告了该主题。 -
我们打开rviz2,选择
Add
,并根据话题选择图像显示插件 -
我们就得到了以下画面
UE5核心类创建及实时数据传输
- 为了更好的数据传输,我们这里进行封装,这里我们写一个发布者
Publisher
基类 connection
将传入外部的websocket
对象,非常常见的设计模式运用,这里就不多说明了
python
class Publisher:
def __init__(self,connection,topic):
self.connection=connection
self.topic = topic
def publish(self,msg):
pub_msg = {
"op": "publish",
"topic": self.topic,
"msg":msg
}
self.connection.send(json.dumps(msg))
class ImagePublisher(Publisher):
def __init__(self,connection,topic,compressed_scale):
self.connection=connection
self.topic = topic
self.compressed_scale=compressed_scale
def publish(self,image):
if image is None:
print('image is None!')
return
h,w=image.shape[0],image.shape[1]
new_h=self.compressed_scale*h
new_w=self.compressed_scale*w
image=cv2.resize(image,(new_w,new_h))
print('h:',new_h,',w:',new_w,'image is publishing')
image = image.astype(np.uint8)
# 将图像数据转换为Base64编码的字符串
encoded_string = base64.b64encode(image).decode('utf-8')
msg = {
"op": "publish",
"topic": self.topic,
"msg": {
"data": encoded_string,
"height": new_h,
"width": new_w,
"step": new_w * 3,
"encoding": "bgr8"
}
}
self.connection.send(json.dumps(msg))
- 同时我们继续书写整个Win11端的核心类
UE5MsgCenter
,这里我们先测试一下功能
python
class UE5MsgCenter:
def __init__(self,ubuntu_remote_ip_):
self.ws = websocket.create_connection(f"ws://{ubuntu_remote_ip_}:9090")
self.ue5_cam_center=UE5CameraCenter()
self.image_pub=ImagePublisher(self.ws,topic='/image',compressed_scale=0.5) self.object_mask_image_pub=ImagePublisher(self.ws,topic='/object_mask_image',compressed_scale=0.5)
def __del__(self):
self.ws.close()
def run(self):
while True:
self.image_pub.publish(self.ue5_cam_center.get_camera_data('lit'))
self.object_mask_image_pub.publish(self.ue5_cam_center.get_camera_data('object_mask'))
- 然后我们再次修改ubuntu订阅端的cpp代码
cpp
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/image.hpp>
class ImageSubscriber : public rclcpp::Node
{
public:
ImageSubscriber()
: Node("image_subscriber")
{
rawImageSub = this->create_subscription<sensor_msgs::msg::Image>(
"image", 10, std::bind(&ImageSubscriber::rawImageCB, this, std::placeholders::_1));
objMaskImageSub= this->create_subscription<sensor_msgs::msg::Image>(
"object_mask_image", 10, std::bind(&ImageSubscriber::objMaskImageCB, this, std::placeholders::_1));
}
private:
void rawImageCB(const sensor_msgs::msg::Image::SharedPtr msg) const
{
RCLCPP_INFO(this->get_logger(), "Received image");
}
void objMaskImageCB(const sensor_msgs::msg::Image::SharedPtr msg) const
{
RCLCPP_INFO(this->get_logger(), "Received image");
}
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr rawImageSub;
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr objMaskImageSub;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
auto node = std::make_shared<ImageSubscriber>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
启动顺序
- 这里有必要说明一下各个平台程序和软件的开启顺序:
- Win11的
UE5
,记得按下开始仿真本关卡!!! - ubuntu的cpp接收端(用于广播消息类型)
- ubuntu的
rosbridge
服务器 - Win11的python的
UE5MsgCenter
- ubuntu的`rviz2
- Win11的
结果展示
-
移动我们在UE5中的观测者小球,同样我们收到消息
深度图像特殊处理
- 这里深度图像Win11发送端我们需要进行特殊处理,我们重新写一个新的类
- 深度图像为灰度图像,是单通道,故设置
step
: new_w,encoding
: "mono8" # 8位灰度图的编码
python
class DepthImagePublisher(Publisher):
def __init__(self,connection,topic,compressed_scale):
self.connection=connection
self.topic = topic
self.compressed_scale=compressed_scale
def publish(self,image):
if image is None:
print('image is None!')
return
h,w=image.shape[0],image.shape[1]
new_h=int(self.compressed_scale*h)
new_w=int(self.compressed_scale*w)
image=cv2.resize(image,(new_w,new_h))
print('h:',new_h,',w:',new_w,'image is publishing')
image = image.astype(np.uint8)
# 将图像数据转换为Base64编码的字符串
encoded_string = base64.b64encode(image).decode('utf-8')
msg = {
"op": "publish",
"topic": self.topic,
"msg": {
"data": encoded_string,
"height": new_h,
"width": new_w,
"step": new_w,
"encoding": "mono8"
}
}
self.connection.send(json.dumps(msg))
- 我们得到如下
完整代码
python
import websocket
import cv2
import base64
import json
import numpy as np
from UE5CameraCenter import UE5CameraCenter
class Publisher:
def __init__(self,connection,topic):
self.connection=connection
self.topic = topic
def publish(self,msg):
pub_msg = {
"op": "publish",
"topic": self.topic,
"msg":msg
}
self.connection.send(json.dumps(msg))
class DepthImagePublisher(Publisher):
def __init__(self,connection,topic,compressed_scale):
self.connection=connection
self.topic = topic
self.compressed_scale=compressed_scale
def publish(self,image):
if image is None:
print('image is None!')
return
h,w=image.shape[0],image.shape[1]
new_h=int(self.compressed_scale*h)
new_w=int(self.compressed_scale*w)
image=cv2.resize(image,(new_w,new_h))
print('h:',new_h,',w:',new_w,'image is publishing')
image = image.astype(np.uint8)
# 将图像数据转换为Base64编码的字符串
encoded_string = base64.b64encode(image).decode('utf-8')
msg = {
"op": "publish",
"topic": self.topic,
"msg": {
"data": encoded_string,
"height": new_h,
"width": new_w,
"step": new_w,
"encoding": "mono8"
}
}
self.connection.send(json.dumps(msg))
class ImagePublisher(Publisher):
def __init__(self,connection,topic,compressed_scale):
self.connection=connection
self.topic = topic
self.compressed_scale=compressed_scale
def publish(self,image):
if image is None:
print('image is None!')
return
h,w=image.shape[0],image.shape[1]
new_h=int(self.compressed_scale*h)
new_w=int(self.compressed_scale*w)
image=cv2.resize(image,(new_w,new_h))
print('h:',new_h,',w:',new_w,'image is publishing')
image = image.astype(np.uint8)
# 将图像数据转换为Base64编码的字符串
encoded_string = base64.b64encode(image).decode('utf-8')
msg = {
"op": "publish",
"topic": self.topic,
"msg": {
"data": encoded_string,
"height": new_h,
"width": new_w,
"step": new_w * 3,
"encoding": "bgr8"
}
}
self.connection.send(json.dumps(msg))
class UE5MsgCenter:
def __init__(self,ubuntu_remote_ip_):
self.ws = websocket.create_connection(f"ws://{ubuntu_remote_ip_}:9090")
self.ue5_cam_center=UE5CameraCenter()
self.image_pub=ImagePublisher(self.ws,topic='/image',compressed_scale=0.5)
self.object_mask_image_pub=ImagePublisher(self.ws,topic='/object_mask_image',compressed_scale=0.5)
self.depth_image_pub=DepthImagePublisher(self.ws,topic='/depth_image',compressed_scale=0.5)
def __del__(self):
self.ws.close()
def run(self):
while True:
self.image_pub.publish(self.ue5_cam_center.get_camera_data('lit'))
self.object_mask_image_pub.publish(self.ue5_cam_center.get_camera_data('object_mask'))
self.depth_image_pub.publish(self.ue5_cam_center.get_camera_data('depth'))
def main():
webs_server = UE5MsgCenter("192.168.137.129")
webs_server.run()
if __name__ =='__main__':
main()
小结
- 本节我们介绍了如何使用
rosbridge
对UE5和ROS2进行通讯 - 下一小节我们将谈谈
UE5``激光雷达
的仿真 - 如有错误,欢迎指出~