-
Notifications
You must be signed in to change notification settings - Fork 427
Yolov5 OpenVINO目标检测(Intel NUC平台)
Intel CPU在运行视觉导航等算法时实时性要优于Nvidia等平台,如Jetson Tx2,NX。而Nvidia平台在运行深度学习算法方面具有很大优势,两种平台各有利弊。但是,Intel OpenVINO的推出允许NUC平台实时运行深度学习模型,如目前最流行的目标检测程序Yolov5,这样就太好了,仅使用Intel无人机平台就可以完成各种任务。本教程将教你用Prometheus在Intel无人机平台部署Yolov5目标检测。
先来个速度测试,仅使用Intel CPU,没有模型压缩与剪枝等算法,也不依赖其他任何加速硬件。
Intel CPU | Yolov5模型 | 输入分辨率 | 检测帧率 |
---|---|---|---|
Intel i7-10710U (10代NUC) | yolov5s | 256 | 44.5Hz |
Intel i7-10710U (10代NUC) | yolov5s | 320 | 27.7Hz |
Intel i7-10710U (10代NUC) | yolov5s | 384 | 19.8Hz |
Intel i7-10710U (10代NUC) | yolov5s | 512 | 10.1Hz |
Intel i7-6700K (台式机) | yolov5s | 256 | 43.2Hz |
Intel i7-6700K (台式机) | yolov5s | 320 | 27.1Hz |
Intel i7-6700K (台式机) | yolov5s | 384 | 19.2Hz |
Intel i7-6700K (台式机) | yolov5s | 512 | 10.0Hz |
官网教程:
https://docs.openvinotoolkit.org/latest/openvino_docs_install_guides_installing_openvino_linux.html
地址:
https://software.intel.com/content/www/us/en/develop/tools/openvino-toolkit/download.html?operatingsystem=linux&distributions=webdownload&version=2021%203%20(latest)&options=offline
~/inference_engine_samples_build
~/openvino_models
cd ~/Downloads/
tar -xvzf l_openvino_toolkit_p_<version>.tgz
cd l_openvino_toolkit_p_<version>
sudo ./install_GUI.sh
cd /opt/intel/openvino_2021/install_dependencies
sudo -E ./install_openvino_dependencies.sh
cd /opt/intel/openvino_2021/deployment_tools/model_optimizer/install_prerequisites
sudo ./install_prerequisites.sh
如果下载很慢,可以修改
~/.pip/pip.conf
,转到国内源[global] index-url = http://mirrors.aliyun.com/pypi/simple/ [install] trusted-host = mirrors.aliyun.com
sudo apt install python3-pip
cd <path-to-Prometheus>/
./Scripts/install_detection_yolov5openvino.sh
以官方权重为例
cd <path-to-Prometheus>/Modules/object_detection_yolov5openvino/weights
wget https://github.com/ultralytics/yolov5/releases/download/v3.0/yolov5s.pt
运行命令:
cd <path-to-Prometheus>/Modules/object_detection_yolov5openvino
python3 models/export.py --weights weights/yolov5s.pt --img 384 --batch 1
cd <path-to-Prometheus>/Modules/object_detection_yolov5openvino
python3 /opt/intel/openvino_2021/deployment_tools/model_optimizer/mo.py --input_model weights/yolov5s.onnx --model_name weights/yolov5s -s 255 --reverse_input_channels --output Conv_487,Conv_471,Conv_455
cd <path-to-Prometheus>/
./Scripts/start_yolov5openvino_server.sh
# Ctrl+t 打开一个新的命令行页面,并运行:
roslaunch prometheus_detection yolov5_intel_openvino.launch
运行结果如下:
如果想把检测结果图像推流到地面站,可以运行如下代码(不需要推流结果,请自动忽略该步骤)
cd <path-to-Prometheus>/
./Scripts/start_yolov5openvino_server_with_streaming.sh
# Ctrl+t 打开一个新的命令行页面,并运行:
roslaunch prometheus_detection yolov5_intel_openvino.launch
以<path-to-Prometheus>/Modules/object_detection/launch/yolov5_intel_openvino.launch
为例:
<launch>
<node pkg="prometheus_detection" type="yolov5_openvino_client.py" name="yolov5_openvino_client" output="screen">
<param name="output_topic" value="/prometheus/object_detection/yolov5_openvino_det"/>
<param name="camera_parameters" type="string" value="$(find prometheus_detection)/shell/calib_webcam_640x480.yaml" />
<param name="object_names_txt" value="coco"/>
</node>
</launch>
其中:
-
output_topic:检测结果输出话题(消息类型:
MultiDetectionInfo.msg
) - camera_parameters:相机参数文件(为了估计视线角误差、目标位置)
-
object_names_txt:目标类别描述
txt
问题(具体见:<path-to-Prometheus>/Modules/object_detection/py_nodes/yolov5_openvion_client/class_desc/coco.txt
)
默认输出话题,消息类型:
##`MultiDetectionInfo.msg`
Header header
## 检测到的目标数量
int32 num_objs
## 每个目标的检测结果
DetectionInfo[] detection_infos
##`DetectionInfo.msg`
## 是否检测到目标
bool detected
## 目标类别名称
string object_name
## 类别ID
int32 category
## 0表示相机坐标系, 1表示机体坐标系, 2表示惯性坐标系
int32 frame
## 目标位置[相机系下:右方x为正,下方y为正,前方z为正]
float32[3] position
## 目标姿态-欧拉角-(z,y,x)
float32[3] attitude
## 目标姿态-四元数-(qx,qy,qz,qw)
float32[4] attitude_q
## 视线角度[相机系下:右方x角度为正,下方y角度为正]
float32[2] sight_angle
## 偏航角误差
float32 yaw_error
注意:默认情况下每个目标仅有detected
, object_name
, category
, frame
, sight_angle
的输出。
如果想输出position
,需要在类别描述文件(如<path-to-Prometheus>/Modules/object_detection/py_nodes/yolov5_openvion_client/class_desc/coco.txt
)中填写目标的高度与宽度(单位:m
)。
如上图,以人(person)为例,设置宽度
0.5m
,高度1.8m
然后,需要修改源代码,这里以高度估计人距离摄像机的距离,并以此估计position
。
源代码位置:<path-to-Prometheus>/Modules/object_detection/py_nodes/yolov5_openvion_client/yolov5_openvion_client.py
,(112-114
行)
cls==0
用来判断是否为类别—person,cls_hs[cls]
用来读取目标高度(读到的数就是我们写在coco.txt
里的1.8m
),camera_matrix[1][1]
为垂直方向像素焦距(由相机标定参数文件决定),h
物体的像素高度(为实时检测结果,并被归一化到0-1)
下载数据集标注工具,下载地址: Spire Web或者百度网盘 (密码: l9e7) ,数据集管理软件SpireImageTools:gitee地址或者github地址。
-
解压,打开标注软件
SpireImageTools_x.x.x.exe
首先点击Tools->Setting...
,填写一个 save path
(所有的标注文件都会存储在这个文件夹中)
-
将拍摄的视频转为图像 (如果采集的是图像,则跳过这一步骤),点击
Input->Video
, 选择要标注的视频。
然后,点击Tools->Video to Image
点击OK 后,等待完成,结果会存储在:
-
打开需要标注的图像,点击菜单
Input->Image Dir
, 找到需要标注的图像所在文件夹 ,按Ctrl+A
,全选,打开所有图像:
-
点击菜单:
Tools->Annotate Image->Box Label
,开始标注图像
在label
中填写待标注目标名称,然后将对话框拖到一边。
-
开始标注,在主窗口中开始标注,鼠标滚轮放大缩小图像,按住左键移动可视图像区域不断点击左键将目标框包围,使用
Yolo
训练时,点击2个点即可:
标注时,如果点错,按鼠标右键可以取消。标注完成后,如果不满意,可以点击绿色边框(边框会变红,如下图所示),按
Delete
删除
- 继续标注行人类别:
-
全部标注完成后,将标注输出为
Yolo
格式,准备训练——在标注完成之后,按下Ctrl+o
点击OK
即可,需要等待转换。
- 注意,如下两个文件夹是我们训练
Yolov5
需要的
在准备好scaled_images
和Yolo_labels
两个文件夹之后,我们就可以训练Yolov5
了。首先,创建一个car_person.yaml
,将其放到<path-to-Prometheus>/Modules/object_detection_yolov5openvino/data/
文件夹下。car_person.yaml
的具体内容如下:
# train and val data as 1) directory: path/images/, 2) file: path/images.txt, or 3) list: [path1/images/, path2/images/]
train: data/car_person/images/train/
val: data/car_person/images/train/
# number of classes
nc: 2
# class names
names: ['car', 'person']
注意1:
car_person
是自定义名称,我们这次标注的数据集仅有这2个类别。 注意2:names: ['car', 'person']
这里的类别顺序需要跟Yolo_categories.names
里的类别顺序一致。
- 将训练图像与标注拷贝到对应位置
首先,在<path-to-Prometheus>/Modules/object_detection_yolov5openvino/data/
下新建一个文件夹car_person
。然后,在car_person
下再新建2个文件夹images
和labels
。最后,将准备好的scaled_images
拷贝到images
下,并重命名为train
;将准备好的Yolo_labels
拷贝到labels
下,并重命名为train
。
结合
car_person.yaml
里的内容,我想你应该明白上面目录结构的含义啦。
- 开始训练
cd <path-to-Prometheus>/Modules/object_detection_yolov5openvino/
python3 train.py --img 640 --batch 16 --epochs 5 --data data/car_person.yaml --weights weights/yolov5s.pt
显示以上内容说明训练成功!可以增加训练期数(--epochs 5
)提升效果。
- 部署训练好的模型
刚刚训练好的模型会保存在<path-to-Prometheus>/Modules/object_detection_yolov5openvino/runs/exp?/weights/best.pt
,?
需根据自己的情况而定(最新训练的模型?
为最大的数字),将best.pt
重命名为yolov5s.pt
,拷贝到<path-to-Prometheus>/Modules/object_detection_yolov5openvino/weights/
下,然后执行第二
部分3-5
的操作进行OpenVINO部署。
感谢使用Prometheus自主无人机软件平台!