ros中无人车和无人机跨平台数据传递,使用 UDP 进行跨平台传输(python代码)
核心流程: 无人机发布 ros消息→ 序列化为 UDP 数据包 → 通过 UDP发送给地面站
1.数据介绍
1.1 自定义数据类型
GroundObject.msg 文件的内容应为:
float64 UTC_time # in ms
int32 VehicleNumber
VEHICLE_OBJ_COOP[] VehicleObjectCOOP
VEHICLE_OBJ_COOP.msg 文件的内容应为:
int32 class # 0:unknown 1:car 2:pedestrian
int32 ismove
int32 vehicleclass # 0:HM 1:LM 3:objects
float64 lon # longitude
float64 lat # latitude
1.2 文件夹结构
your_ros_workspace/
├── src/
│ ├── your_package/
│ │ ├── msg/
│ │ │ ├── GroundObject.msg
│ │ │ ├── VEHICLE_OBJ_COOP.msg
│ │ ├── src/
│ │ │ ├── ground_udp_publisher.py
│ │ │ ├── ground_udp_subscriber.py
│ │ ├── CMakeLists.txt
│ │ ├── package.xml
1.3 CMakeLists.txt修改
在 CMakeLists.txt 中,需要确保自定义消息的生成和依赖性已经添加。
cmake_minimum_required(VERSION 3.0.2)
project(your_package)
find_package(catkin REQUIRED COMPONENTS
rospy
std_msgs
message_generation
)
add_message_files(
FILES
GroundObject.msg
VEHICLE_OBJ_COOP.msg
)
generate_messages(
DEPENDENCIES
std_msgs
)
catkin_package(
CATKIN_DEPENDS message_runtime std_msgs
)
include_directories(
${catkin_INCLUDE_DIRS}
)
1.4 package.xml
在 package.xml 中,添加对 message_generation 和 message_runtime 的依赖:
<package format="2">
<name>your_package</name>
<version>0.0.0</version>
<description>UDP communication between vehicle and drone</description>
<maintainer email="your_email@example.com">Your Name</maintainer>
<license>BSD</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>message_generation</build_depend>
<build_depend>rospy</build_depend>
<exec_depend>message_runtime</exec_depend>
<exec_depend>rospy</exec_depend>
</package>
2.UDP 发送代码(drone_udp.py)
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy
from my_drone.msg import GroundObject, VEHICLE_OBJ_COOP
import time
import socket
import json
def drone_publisher():
# 初始化ROS节点
rospy.init_node('drone_publisher', anonymous=True)
# 定义UDP的地址和端口
udp_ip = "192.168.153.63" # 地面端接收的IP
udp_port = 5004 # 地面端接收的端口
# 创建UDP socket
udp_socket = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
rate = rospy.Rate(0.1) # 1 Hz
while not rospy.is_shutdown():
# 创建GroundObject消息
ground_msg = GroundObject()
# 获取当前UTC时间,单位为毫秒
ground_msg.UTC_time = time.time() * 1000.0
ground_msg.VehicleNumber = 2
# 创建两个车辆对象
vehicle1 = VEHICLE_OBJ_COOP()
vehicle1.type = 1 # Car
vehicle1.ismove = 1
vehicle1.vehicleclass = 0 # HM
vehicle1.lon = 116.391389
vehicle1.lat = 39.9075
vehicle2 = VEHICLE_OBJ_COOP()
vehicle2.type = 2 # Pedestrian
vehicle2.ismove = 0
vehicle2.vehicleclass = 3 # Objects
vehicle2.lon = 116.384
vehicle2.lat = 39.915
# 将车辆对象添加到GroundObject消息中
ground_msg.VehicleObjectCOOP = [vehicle1, vehicle2]
# 序列化ground_msg到JSON格式
ground_msg_json = json.dumps({
"UTC_time": ground_msg.UTC_time,
"VehicleNumber": ground_msg.VehicleNumber,
"VehicleObjectCOOP": [
{
"type": vehicle1.type,
"ismove": vehicle1.ismove,
"vehicleclass": vehicle1.vehicleclass,
"lon": vehicle1.lon,
"lat": vehicle1.lat
},
{
"type": vehicle2.type,
"ismove": vehicle2.ismove,
"vehicleclass": vehicle2.vehicleclass,
"lon": vehicle2.lon,
"lat": vehicle2.lat
}
]
})
# 通过UDP发送JSON数据
udp_socket.sendto(ground_msg_json.encode('utf-8'), (udp_ip, udp_port))
rospy.loginfo("GroundObject message sent via UDP")
# 按设定的频率睡眠
rate.sleep()
if __name__ == '__main__':
try:
drone_publisher()
except rospy.ROSInterruptException:
pass
2.1代码解释
socket:Python 的网络通信库,提供了 UDP 和 TCP 的接口。
#创建一个 UDP socket。AF_INET 指的是 IPv4 协议,SOCK_DGRAM 指的是 UDP 协议。
socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
“,”.join([…]):遍历 msg.VehicleObjectCOOP 数组中的每个对象,将每个对象的属性(class, ismove, vehicleclass, lon, lat)提取出来,构成一个逗号分隔的字符串。
#将序列化后的字符串 data 编码为字节,并通过 sendto 函数发送到 udp_ip 和 udp_port 指定的无人机地址。
udp_socket.sendto(ground_msg_json.encode('utf-8'), (udp_ip, udp_port))
#订阅 ROS 话题 ground_data_topic,当收到消息时,调用 send_udp_message 函数。该函数会将收到的 ROS 消息通过 UDP 发送出去。
rospy.Subscriber("ground_data_topic", 1_GroundObject, send_udp_message)
3.UDP 接受代码(ground_udp.py)
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy
from my_drone.msg import GroundObject, VEHICLE_OBJ_COOP
import socket
import json
import time
def udp_receiver():
# 初始化ROS节点
rospy.init_node('udp_receiver', anonymous=True)
#pub = rospy.Publisher('/ground_object_info', GroundObject, queue_size=10)
# 定义UDP监听的地址和端口
udp_ip = "0.0.0.0" # 监听所有IP
udp_port = 5004 # 与无人机端的发送端口保持一致
# 创建UDP socket
udp_socket = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
udp_socket.bind((udp_ip, udp_port))
rospy.loginfo("Listening for UDP messages...")
while not rospy.is_shutdown():
# 接收UDP数据
data, addr = udp_socket.recvfrom(1024)
#rospy.loginfo(f"Received message from {addr}")
rospy.loginfo("Received message from {}".format(addr))
# 将JSON数据反序列化
ground_msg_dict = json.loads(data.decode('utf-8'))
# 创建GroundObject消息
ground_msg = GroundObject()
ground_msg.UTC_time = ground_msg_dict["UTC_time"]
ground_msg.VehicleNumber = ground_msg_dict["VehicleNumber"]
# 创建车辆对象并反序列化
ground_msg.VehicleObjectCOOP = []
for vehicle_dict in ground_msg_dict["VehicleObjectCOOP"]:
vehicle = VEHICLE_OBJ_COOP()
vehicle.type = vehicle_dict["type"]
vehicle.ismove = vehicle_dict["ismove"]
vehicle.vehicleclass = vehicle_dict["vehicleclass"]
vehicle.lon = vehicle_dict["lon"]
vehicle.lat = vehicle_dict["lat"]
ground_msg.VehicleObjectCOOP.append(vehicle)
# 发布消息
current_time = time.time() * 1000.0 # 转换成毫秒
# 消息的UTC时间
msg_time = ground_msg.UTC_time
# 计算延迟
delay = current_time - msg_time
rospy.loginfo("Communication delay: %.2f ms" % delay)
rospy.loginfo("udp message received")
#pub.publish(ground_msg)
if __name__ == '__main__':
try:
udp_receiver()
except rospy.ROSInterruptException:
pass
4.编译和运行
cd ~/your_ros_workspace
catkin_make
编译成功后,使用以下命令使环境变量生效:
source devel/setup.bash
4.2 启动 ROS 节点(启动无人车和无人机的 UDP 发布和订阅节点。)
在无人机端启动发布节点
rosrun your_package drone_udp.py
在无人车启动接受节点
rosrun your_package ground_udp.py
这样,无人机上的 ROS 信息将通过 UDP 协议发送到地面站,地面站再将这些信息发布为 ROS 话题,进行进一步的处理。