- 在开始正文前,我想向超神 Cauchy和晟哥哥表达由衷的感谢。本文工作基于rdk_model_zoo/YOLOv8-Detect_YUV420SP的版本上,对预处理/后处理,以及部署流程上进行了进一步优化。
- 感谢x5-hobot-spdev相关团队的开源贡献,为本文BPU的C++部署方案优化提供了坚实基础。
尽管目前关于YOLOv8在RDK X5部署的技术博客和教程数量众多,但实际落地应用仍存在显著差距。以YOLO8n为例,一个关键矛盾在于:不超频的话,YOLO8n对于640*640的总体推理耗时基本上在18ms左右 (3ms预处理+10ms推理耗时+5ms后处理)。多数实际场景需要处理高分辨率图像(如4K视频或工业检测),关注的是输入图像至输出结果的耗时。
现有部署方案并没有给出很好的部署方案,有个比较trick的方案就是将大图拆成小图去推理,然后汇总结果输出(不要问我为什么要裁图,我这个6g显存的笔记本也就只能训到这里了
)。如果用默认配置的话,高分辨率输入会导致推理延迟显著增加,这使得许多应用场景的实时性需求无法得到满足。这种理论可行性与工程实践之间的鸿沟,正是当前YOLOv8落地面临的主要瓶颈之一。
目前从demo到落地有以下几个关键问题:
- 延迟问题。如果推理延迟超过0.5s的时候,那么在使用方控制设备时候,就会产生显著影响,特别是在需要实时响应的场景中。在需要根据检测结果实时调整设备位置的场景中,延迟会导致控制指令滞后,造成动作不连贯。
- 开发语言性能瓶颈。为了提高开发效率,整个项目一般以py为主。但
- 对于一些有明确计算需求的场景,py计算效率远不如C++,以后处理为例,py需要5ms,C++优化后,能优化至1ms以内。
- 用C++开多线程,不可避免需要研究BPU的C++部署方案。虽然目前公开的技术资料相对有限,社区支持也待完善,但这正是我们通过实践积累经验、推动技术边界的机会。
- 接口示例文档过少。这个是个非常关键的问题,多线程的优化只能基于C++,但接口的参数说明文档以及examples太少,出问题基本上只能自己去测试,难以获取技术支持。就导致一涉及到多线程等扩展需求,基本上要花非常大量的时间在频繁的接口测试上。
考虑到这些问题,我花费了3个月的时间,来不断地重构完善自己的代码结构,来满足自己的实际落地需求。本博客相关的开发基于OpenWanderary展开,会详细给各位介绍这个工具带来的酷炫优化效果,以及详细的使用方案,以便方便各位部署自己的模型。本文将会给各位带来两个收益:
- 加速推理,降低推理耗时。提高系统实时性。
- 三行代码,极速部署,支持C++和Py。极大降低部署难度。
一 效率优化
这里会对5种不同规模的YOLO模型进行更全面的耗时评测,会统计每次推理的预处理/推理/后处理这几个阶段的耗时。并用3种不同的分辨率进行测试。其中:
- 模型下载地址参考YOLOV8-PTQ模型集。
- 测试数据集。数据集根据分辨率分为三种,对于分辨率较高的图像,会通过crop形式裁出多个子图进行推理,子图推理结束后汇总到一起作为最终输出。
- 低分辨率。从coco数据集中抽出50张,通过预处理resize为640*640,直接输入模型中。
- 中分辨率。分辨率为1920*1080,通过高分辨率数据集resize得到。对应的横向offset为440,列向offset为640,共计6张子图。
- 高分辨率。分辨率为3840*2160,是自己采集了一些城市景色。对应的横向offset为440,列向offset为380,共计30张子图。
先明确下这里单线程和多线程的定义。整个推理流程有预处理/BPU推理/后处理,单线程指的是用一个线程完成这一个Pipeline,多线程指的是用多个线程推理多个子图。
下表是单线程的推理耗时统计,预处理耗时在1-4ms之间,后处理耗时<2ms。而推理部分的耗时,与网络规模有关。特别是子图越多,这个耗时基本上是翻倍增加。用cat /sys/devices/system/bpu/bpu0/ratio,可以发现bpu的资源占用并未达到极限,因此还有优化空间。
| RDK X5推理(单线程),单位ms | |||||||||||||
|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
| 模型类别 | 低分辨率(640*640, 1张子图) | 中分辨率(1920*1080, 6张子图) | 高分辨率(3840*2160, 30张子图) | ||||||||||
| 预处理 | 推理 | 后处理 | 完整流程 | 预处理 | 推理 | 后处理 | 完整流程 | 预处理 | 推理 | 后处理 | 完整流程 | ||
| YOLO8n | 1.78 | 8.04 | 0.80 | 11.84 | 1.10 | 7.78 | 0.53 | 73.25 | 1.18 | 8.01 | 0.73 | 380.83 | |
| YOLO8s | 1.68 | 15.04 | 1.00 | 18.70 | 1.13 | 14.63 | 0.67 | 114.5 | 2.08 | 18.38 | 1.15 | 735.25 | |
| YOLO8m | 2.04 | 33.40 | 1.18 | 37.64 | 1.31 | 34.90 | 1.07 | 239.75 | 2.86 | 37.51 | 1.61 | 1353.00 | |
| YOLO8l | 4.08 | 69.40 | 0.90 | 77.32 | 1.32 | 64.96 | 0.92 | 420.17 | 3.21 | 66.35 | 1.75 | 2236.67 | |
| YOLO8x | 4.02 | 101.30 | 0.96 | 108.18 | 1.21 | 97.82 | 1.04 | 617.42 | 2.89 | 98.54 | 1.58 | 3183.58 | |
我们通过多线程形式对大分辨率图像进行加速,详细数据记录在下表中,这个表可以帮助各位根据自己模型情况去配置自己的线程数。总结来说:
- 线程数并非越多越好,模型中若可用BPU推理的层越多,越没必要开线程。这里的多线程仅仅是用于降低一点预处理和后处理阶段造成的资源浪费而已。
- 如果模型规模较小,推荐线程数开到4,比如YOLO8n这种。其他的2个基本就够了。
==注:在下一节会提供工具来帮助确定最优线程数,有自定义模型的需求,可以自己去测试==
| RDK X5 多线程优化对比 | |||||||||||
|---|---|---|---|---|---|---|---|---|---|---|---|
| 模型类别 | 线程数 | 中分辨率(1920*1080, 6张子图) | 高分辨率(3840*2160, 30张子图) | ||||||||
| 预处理 | 推理 | 后处理 | 完整流程 | 效率提升 | 预处理 | 推理 | 后处理 | 完整流程 | 效率提升 | ||
| YOLO8n | 2 | 1.82 | 8.71 | 0.81 | 45.42 | 161% | 1.49 | 8.49 | 0.81 | 210.08 | 181% |
| 4 | 3.71 | 12.19 | 1.03 | 35.92 | 204% | 2.64 | 10.92 | 1.49 | 145.83 | 261% | |
| 6 | 5.26 | 17.56 | 1.06 | 36.92 | 198% | 2.99 | 17.12 | 1.92 | 138.17 | 276% | |
| YOLO8s | 2 | 1.90 | 17.92 | 0.79 | 75.42 | 152% | 1.925 | 17.34 | 0.92 | 348.33 | 211% |
| 4 | 3.42 | 32.19 | 0.94 | 74.92 | 153% | 2.22 | 36.73 | 1.19 | 338.83 | 217% | |
| 6 | 5.31 | 40.14 | 1.03 | 76.92 | 149% | 2.76 | 54.95 | 2.01 | 341.08 | 216% | |
| YOLO8m | 2 | 1.96 | 49.17 | 1.26 | 179.33 | 134% | 3.25 | 47.53 | 2.27 | 855.5 | 158% |
| 4 | 3.46 | 86.03 | 1.49 | 182.92 | 131% | 3.08 | 99.61 | 2.15 | 850.42 | 159% | |
| 6 | 5.44 | 101.97 | 1.40 | 184.67 | 130% | 3.48 | 146.63 | 3.53 | 851.67 | 159% | |
| YOLO8l | 2 | 2.38 | 102.15 | 1.71 | 355.67 | 118% | 3.11 | 104.82 | 2.02 | 1724.67 | 130% |
| 4 | 3.39 | 174.53 | 2.14 | 355.25 | 118% | 3.89 | 208.21 | 2.91 | 1724.08 | 130% | |
| 6 | 5.38 | 206.22 | 1.72 | 359.58 | 117% | 3.79 | 305.61 | 3.84 | 1722.17 | 130% | |
| YOLO8x | 2 | 2.65 | 161.32 | 1.76 | 551.92 | 112% | 3.49 | 168.38 | 2.27 | 2705.08 | 118% |
| 4 | 3.76 | 270.83 | 2.26 | 553.75 | 111% | 3.42 | 333.32 | 2.44 | 2701.83 | 118% | |
| 6 | 5.17 | 322.29 | 1.87 | 554.75 | 111% | 3.97 | 484.59 | 4.19 | 2703.08 | 118% | |
二 快速集成
训一个模型很容易,量化一个模型也很容易,测试一个模型能否获取想要的结果也是容易的,但将这个需求嵌入到自己项目里是困难的。最大的原因在于,RDK提供的工具多数以Node形式提供,这导致自己的项目必须是ROS项目,且需要花费一些时间解决通信/订阅问题,这里会造成一些延迟。而我的需求,是将一个函数输入到函数/类里,就能直接获取结果,不需要依赖ROS这些。
因此,基于这个需求,我封装了底层的BPU API,暴露class YOLOv8,内部包含预处理/后处理。初始化后,直接输入图像即可返回最终输出的2DBox。这里会先介绍如何使用工具验证自己的模型,然后介绍如何用极少的代码快速部署到自己的项目中。
2.1 工具验证
git clone --recursive https://github.com/Li-Zhaoxi/OpenWanderary.git
cd OpenWanderary
# 切换到当前博客对应版本(避免后续的代码更新导致该博客相关的介绍无法使用)
git checkout 7c74e76d88eac2e9d52c1b971d7d1b5b927c3195
make download # 下载数据(UT依赖数据)
make rely # 编译依赖项
make release # 编译release版本
编译之后,则可在build_release/examples/dnn发现一个编译完的文件stat-dnn-time-consumption,该文件源码在examples/dnn/stat-dnn-time-consumption.cpp中。这个工具目的是提供多种DNN的测试需求,每个需求作为个子命令来暴漏参数。这个工具主要是验证两个问题:
- 确认模型是否有效。推理之后可以选择保存可视化结果,一边确认输出结果的有效性。
- 可加速的线程数。若推理为Crop方式,则可以调整线程数来确定最优加速线程数。
对于当前项目来说,对应的子命令为yolov8,其关联参数如下:
--config:指定模块的配置文件,参考config/stat_yolov8_time_cfg.yaml--thread:内部开的线程数,该线程指的是针对裁图的线程数。--save-root:推理结果保存的根目录,若指定则会绘制推理结果并保存到指定目录下。--input:针对数据的输入配置,比如配置数据集以及裁图信息等。参考文件:config/stat_yolov8_time_cfg.yaml。- 子模块选择:
dataset:处理数据集内的所有图像,需要在input对应的文件中配置好数据集的地址等信息single-image:处理一张图像,如果指定该模式,还需要指定一个参数:--input-image:图像地址
上述指令中,参数--config指定的配置文件主要配置了YOLO的预处理和后处理方式,预处理主要作用是resize并转换为nv12格式。后处理是利用推理出的feature转换为最终的Box2D。
# YOLO预处理: 格式化处理输入图像,按照指定的形式构造模型输入的图像
preprocess:
manager_name: preprocess
processes:
- name:
FormatImage
config:
type: letter_box
width: 640 # 需要resize的大小
height: 640
cvt_nv12: true # 是否转为nv12格式
# YOLO后处理: 利用推理特征转换为Box2D
postprocess:
manger_name: postprocess
processes:
- name:
ConvertYoloFeature
config:
class_num: 80 # 类别名称
reg_num: 16
# NMS的IoU(交并比)阈值
nms_thres: 0.7
# 置信度分数阈值,低于此值的边界框会被直接过滤,不参与后续NMS处理
score_thres: 0.25
box_scales:
1: 8
3: 16
5: 32
# 模型路径以及使用的模型名
model_path: tests/test_data/models/yolov8x_detect_bayese_640x640_nv12_modified.bin
model_name: yolov8x_detect_bayese_640x640_nv12
批量处理一批小图的输入配置:config/stat_yolov8_time_inputs.yaml
# 数据集加载(用于批量处理数据集的模式)
data_loader:
name:
SimpleImageDataset
config:
input:
# 指定图像根目录
image_root: tests/test_data/tiny_coco/val
# 图像名文件,记录目录下的文件名列表
name_list_path: tests/test_data/tiny_coco/val_names.txt
# 类别名称,用于可视化标记Label
type_names: tests/test_data/tiny_coco/type_names.json
# 裁图配置(不进行任何裁图)
crop_info:
size_w: -1
size_h: -1
offset_w: -1
offset_h: -1
drop_gap: false
大图处理的输入配置:config/stat_yolov8_large_images_time_inputs.yaml
type_names: tests/test_data/tiny_coco/type_names.json
# 裁图模式:
crop_info:
# 每个小图的size
size_w: 640
size_h: 640
# 下一个小图的offset
offset_w: 640
offset_h: 640
# 是否丢弃边界图像(边界图像的size小于crop的size)
drop_gap: false
这里提供三种测试需求对应的指令
# 批量处理一个数据集数据集模式
./build_release/examples/dnn/stat-dnn-time-consumption yolov8 \
--config config/stat_yolov8_time_cfg.yaml \
--input config/stat_yolov8_time_inputs.yaml \
--thread 1 \
--save-root .cache/ \
dataset
# 单图测试模式
./build_release/examples/dnn/stat-dnn-time-consumption yolov8 \
--config config/stat_yolov8_time_cfg.yaml \
--input config/stat_yolov8_time_inputs.yaml \
--thread 1 \
--save-root .cache/ \
single-image \
--input-image tests/test_data/tiny_coco/val/000000017627.jpg
# 大图推理模式
./build_release/examples/dnn/stat-dnn-time-consumption yolov8 \
--config config/stat_yolov8_time_cfg.yaml \
--input config/stat_yolov8_large_images_time_inputs.yaml \
--thread 2 \
--save-root .cache/ \
single-image \
--input-image tests/test_data/utils/street.jpg
对应单图效果如下
2.2 项目集成
为了方便集成到自己项目里,我单独创建了一个仓库,以便更清晰的介绍继承的方式。
git clone --recursive https://github.com/Li-Zhaoxi/OpenWanderary-examples
cd OpenWanderary-examples
git checkout 5c8a8724737e9e52f49afb66131b6209b41f6084
# 第一次执行需要安装依赖
make rely
# 编译wdr库
make wdr
# 安装wdr库,包含C++和Py.
make install
# 编译用例
make example
注意,make install时会自动将编译的库和头文件安装到/usr/local/include和/usr/local/lib中,而py包会安装到用户目录下。py包所调用函数也是C++的封装。
下面将根据项目类型,分别介绍C++项目和Py项目的使用方式
2.2.1 C++项目集成
C++项目集成时,需要先在自己项目中导入包find_package(wdr REQUIRED),库依赖了C++17,如果没有添加set(CMAKE_CXX_STANDARD 17)的需要补上。
在link到实际可执行文件或者其他动态库时,需要在库的后面额外连接target_link_libraries(${BIN} wdr::wdr_visualization wdr::wdr_apps)即可。
配置之后,可以参考examples/yolo8_image.cpp的内容将YOLO推理Class嵌入到自己项目中,这里介绍下关键函数的用法。不考虑配置的话,调用方式总共有三步:
- 步骤1:初始化。
YOLOv8 yolov8("yolov8", cfg, 1);- 参数1
const std::string &appname。记录当前APP名称,主要用于输出Log信息。 - 参数2
const wdr::json &cfg。配置信息,在前面工具验证中已经有介绍,细节可以参考项目中configs/stat_yolov8_time_cfg.yaml。 - 参数3
int thread_num。线程数,用于加速crop小图的推理效率。
- 参数1
- 步骤2:ROI确认。
- 如果输入图像很小,无需crop。则直接配置
const auto rois = wdr::ImageCropROIs(img.size(), cv::Size(-1, -1), cv::Size(-1, -1), false);即可,roi就是完整图像。 - 如果输入图像很大,则参考
const auto rois = wdr::ImageCropROIs(img.size(), cv::Size(640, 640), cv::Size(640, 640), false);配置切分参数即可
- 如果输入图像很小,无需crop。则直接配置
- 步骤3:推理。
const auto box2ds = yolov8.run(img, rois, nullptr);输入只有两个,图像和切分ROI。第三个参数用于统计各个阶段耗时的,实际应用时无需指定。
#include <string>
#include <vector>
#include <glog/logging.h>
#include <wanderary/apps/yolo.h>
#include <wanderary/utils/convertor.h>
#include <wanderary/utils/yaml_utils.h>
#include <wanderary/visualization/draw_boxes.h>
using YOLOv8 = wdr::apps::YOLOv8;
using Box2DDrawer = wdr::vis::Box2DDrawer;
Box2DDrawer CreateDrawer(const std::string &names_path) {
const auto names = wdr::LoadJson(names_path);
const int class_num = names.size();
std::vector<std::string> class_names(class_num);
for (const auto &item : names.items())
class_names[std::stoi(item.key())] = item.value();
return Box2DDrawer(class_num, class_names);
}
int main(int argc, char **argv) {
// 数据加载
const std::string cfgpath = "configs/stat_yolov8_time_cfg.yaml";
const std::string imgpath = "data/000000460347.jpg";
const std::string typespath = "data/coco_type_names.json";
const std::string savepath = ".cache/000000460347_res.jpg";
// 加载配置/图像/可视化
const auto cfg = wdr::LoadYaml<wdr::json>(cfgpath);
const auto img = cv::imread(imgpath);
Box2DDrawer drawer = CreateDrawer(typespath);
// YOLO初始化
YOLOv8 yolov8("yolov8", cfg, 1);
// 推理
const auto rois =
wdr::ImageCropROIs(img.size(), cv::Size(-1, -1), cv::Size(-1, -1), false);
const auto box2ds = yolov8.run(img, rois, nullptr);
// 可视化
cv::Mat vis;
img.copyTo(vis);
drawer.draw(box2ds, &vis);
cv::imwrite(savepath, vis);
LOG(INFO) << "Save visualization to " << savepath;
return 0;
}
2.2.2 Py项目集成
Py项目集成时,更简单了,直接import wanderary即可。
配置之后,可以参考examples/yolo8_image.cpp的内容将YOLO推理Class嵌入到自己项目中,这里介绍下关键函数的用法。不考虑配置的话,调用方式总共有三步:
- 步骤1:初始化。
yolo = YOLOv8("yolov8", cfg, 1),参数含义同C++。 - 步骤2:ROI确认。
- 如果输入图像很小,无需crop。则直接配置
rois = ImageCropROIs(img.shape[1::-1], (-1, -1), (-1, -1), False)即可,roi就是完整图像。 - 如果输入图像很大,则参考
rois = ImageCropROIs(img.shape[1::-1], (640, 640), (640, 640), False)配置切分参数即可
- 如果输入图像很小,无需crop。则直接配置
- 步骤3:推理。
bbox2ds = yolo.run(img, rois)。输入只有两个,图像和切分ROI。返回值就是List[Box2D]。
import json
import cv2
import yaml
from wanderary import Box2DDrawer, ImageCropROIs, YOLOv8
def create_drawer(class_num, names_path):
class_names = [""] * 80
with open(names_path, "r") as f:
names = json.load(f)
for i, name in enumerate(names):
class_names[int(i)] = name
return Box2DDrawer(80, class_names)
if __name__ == '__main__':
cfgpath = "configs/stat_yolov8_time_cfg.yaml"
imgpath = "data/000000460347.jpg"
typespath = "data/coco_type_names.json"
savepath = ".cache/000000460347_pyres.jpg"
# 加载配置/图像/可视化
with open(cfgpath, 'r') as f:
cfg = yaml.safe_load(f)
img = cv2.imread(imgpath)
drawer = create_drawer(80, typespath)
# 初始化
yolo = YOLOv8("yolov8", cfg, 1)
# 推理
rois = ImageCropROIs(img.shape[1::-1], (-1, -1), (-1, -1), False)
bbox2ds = yolo.run(img, rois)
# 可视化
vis = drawer.draw(bbox2ds, img)
cv2.imwrite(savepath, vis)
三 小结——从Demo到工程化的跨越
作为开发者,BPU部署是技术落地无法绕过的课题,而工程化与Demo演示本质上是两个维度的挑战。回顾这4个月的业余开发历程(6月至今),从架构设计到初版发布,经历了多次重构与性能调优,最终版本已能有效加速项目落地——至少在我的实际应用中验证了这一点。
版本迭代说明。各位可以发现我在clone代码时,配置了checkout信息,这是为应对未来接口变更的兼容性设计。YOLO推理模块新增完整测试功能,可通过tests/samples跟踪最新版使用方式。
性能边界与扩展方向。当前方案已逼近YOLO单机推理的算力极限,如需更大规模部署,建议考虑硬件升级,采用更高性能的开发板。或者分布式方案,构建推理集群(这两项正是我后续的重点开发计划)






