🎯 将摄像头或图片的 YOLOv5 检测结果,通过 Web 服务提供一个带检测框的实时视频流,前端只需用
<img src="...">即可显示。
🧱 第 0 步:系统环境准备
系统要求
- Ubuntu 22.04
安装 ROS 2 Humble(如未安装)
# 1. 设置 locale
sudo apt update && sudo apt install -y locales
sudo locale-gen en_US en_US.UTF-8
sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
export LANG=en_US.UTF-8
# 2. 添加 ROS 2 源
sudo apt install -y software-properties-common
sudo add-apt-repository -y universe
sudo apt install -y curl
sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
# 3. 安装 ROS 2 Humble Desktop
sudo apt update
sudo apt install -y ros-humble-desktop python3-colcon-common-extensions python3-rosdep
# 4. 初始化 rosdep
sudo rosdep init
rosdep update
# 5. 配置环境变量(加入 ~/.bashrc)
echo "source /opt/ros/humble/setup.bash" >> ~/.bashrc
source ~/.bashrc
📁 第 1 步:创建工作空间
mkdir -p ~/yolov5_ws/src
cd ~/yolov5_ws
🖼️ 第 2 步:准备图像输入源(二选一)
选项 A:用静态图片循环发布(适合测试)
创建 publish_image.py:
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
import cv2
import time
class ImagePublisher(Node):
def __init__(self, image_path):
super().__init__('image_publisher')
self.publisher_ = self.create_publisher(Image, '/image', 10)
self.bridge = CvBridge()
self.image_path = image_path
self.timer = self.create_timer(1.0, self.publish_image) # 每秒发1帧
def publish_image(self):
img = cv2.imread(self.image_path)
if img is not None:
msg = self.bridge.cv2_to_imgmsg(img, "bgr8")
self.publisher_.publish(msg)
self.get_logger().info('Published image')
else:
self.get_logger().error('Failed to load image')
def main(args=None):
rclpy.init(args=args)
# 替换为你自己的图片路径
node = ImagePublisher('/home/pon/test.jpg')
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
准备一张测试图,比如:
wget -O ~/test.jpg https://raw.githubusercontent.com/ultralytics/yolov5/master/data/images/zidane.jpg
选项 B:用 USB 摄像头(可选)
sudo apt install ros-humble-usb-cam
ros2 run usb_cam usb_cam_node_exe --ros-args -p video_device:=/dev/video0 -p image_width:=640 -p image_height:=480
# 默认发布 /image_raw,可 remap 到 /image
🧠 第 3 步:集成 YOLOv5 检测节点
我们使用开源的
yolov5_ros2包(假设你已编译过)
安装依赖
sudo apt update
sudo apt install python3-pip ros-$ROS_DISTRO-vision-msgs
pip3 install -i https://pypi.tuna.tsinghua.edu.cn/simple yolov5
克隆并编译(如未做)
cd ~/yolov5_ws/src
git clone https://github.com/whynotai/yolov5_ros2.git
cd ~/yolov5_ws
rosdep install --from-paths src --ignore-src -y
colcon build --packages-select yolov5_ros2
source install/setup.bash
⚠️ 如果你用的是其他 YOLO 包,只要它发布
/yolo_result(类型vision_msgs/Detection2DArray)即可。
启动 YOLO 节点(CPU 模式)
ros2 run yolov5_ros2 yolo_detect_2d --ros-args -p device:=cpu -p image_topic:=/image
✅ 验证输出:
ros2 topic echo /yolo_result
# 应看到 class_id: person, score, bbox 等字段

🌐 第 4 步:创建 Web 桥接服务(核心)
创建 web_server.py(放在 ~/yolov5_ws):
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Image
from vision_msgs.msg import Detection2DArray
from cv_bridge import CvBridge
import cv2
import threading
import time
from flask import Flask, Response
latest_frame = None
latest_detections = []
frame_lock = threading.Lock()
detection_lock = threading.Lock()
class WebBridgeNode(Node):
def __init__(self):
super().__init__('web_bridge')
self.bridge = CvBridge()
self.create_subscription(Image, '/image', self.image_callback, 10)
self.create_subscription(Detection2DArray, '/yolo_result', self.detection_callback, 10)
def image_callback(self, msg):
global latest_frame
try:
cv_image = self.bridge.imgmsg_to_cv2(msg, "bgr8")
with frame_lock:
latest_frame = cv_image.copy()
except Exception as e:
self.get_logger().error(f"CV Bridge error: {e}")
def detection_callback(self, msg):
global latest_detections
detections = []
for det in msg.detections:
if det.results:
h = det.results[0].hypothesis
detections.append({
"x": det.bbox.center.position.x,
"y": det.bbox.center.position.y,
"w": det.bbox.size_x,
"h": det.bbox.size_y,
"label": h.class_id,
"score": h.score
})
with detection_lock:
latest_detections[:] = detections
app = Flask(__name__)
@app.route('/')
def index():
return "YOLOv5 Stream at <a href='/video_feed'>/video_feed</a>"
def generate_video():
global latest_frame
while True:
with frame_lock:
frame = latest_frame.copy() if latest_frame is not None else None
if frame is not None:
with detection_lock:
for det in latest_detections:
x1 = int(det["x"] - det["w"] / 2)
y1 = int(det["y"] - det["h"] / 2)
x2 = int(det["x"] + det["w"] / 2)
y2 = int(det["y"] + det["h"] / 2)
cv2.rectangle(frame, (x1, y1), (x2, y2), (0, 255, 0), 2)
cv2.putText(frame, f'{det["label"]} {det["score"]:.2f}',
(x1, y1 - 10), cv2.FONT_HERSHEY_SIMPLEX, 0.6, (0, 255, 0), 2)
_, buffer = cv2.imencode('.jpg', frame, [int(cv2.IMWRITE_JPEG_QUALITY), 70])
yield (b'--frame\r\nContent-Type: image/jpeg\r\n\r\n' + buffer.tobytes() + b'\r\n')
else:
time.sleep(0.1)
@app.route('/video_feed')
def video_feed():
return Response(generate_video(), mimetype='multipart/x-mixed-replace; boundary=frame')
def ros_spin():
rclpy.init()
node = WebBridgeNode()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
threading.Thread(target=ros_spin, daemon=True).start()
app.run(host='0.0.0.0', port=5000, threaded=True)
安装依赖:
pip3 install flask opencv-python numpy
▶️ 第 5 步:启动所有组件
打开 三个终端:
终端 1:发布图像
cd ~/yolov5_ws
source /opt/ros/humble/setup.bash
python3 publish_image.py /home/pon/test.jpg

终端 2:运行 YOLO 检测
cd ~/yolov5_ws
source install/setup.bash
ros2 run yolov5_ros2 yolo_detect_2d --ros-args -p device:=cpu -p image_topic:=/image

终端 3:启动 Web 服务
cd ~/yolov5_ws
source install/setup.bash
python3 web_server.py
你会看到:
Running on http://192.168.x.x:5000

🔍 第 6 步:测试
测试方法
- 在浏览器打开:
http://<你的IP>:5000/video_feed - 应看到带绿色框的图像

前端使用
视频流地址:
http://192.168.x.x:5000/video_feed使用方式:
<img src="http://192.168.x.x:5000/video_feed" width="960" />
✅ 目录结构
~/yolov5_ws/
├── src/
│ └── yolov5_ros2/ # YOLOv5 ROS 2 包
├── publish_image.py # 图像发布脚本
├── web_server.py # Web 桥接服务
└── test.jpg # 测试图片
🧪 验证清单
| 步骤 | 命令 | 预期结果 |
|---|---|---|
| 图像发布 | ros2 topic hz /image |
~1 Hz |
| 检测输出 | ros2 topic echo /yolo_result |
有 person 检测 |
| Web 服务 | curl -s http://localhost:5000 |
返回 HTML 提示 |
| 视频流 | 浏览器打开 /video_feed |
显示带框图像 |