- 前言
- ROS中目标检测模型的部署(rospy)
- demo测试
- ROS python模型部署
- Bug处理
Nanodet是我十分喜爱的一个超轻量目标检测算法,以FCOS为主体框架+GFL损失函数来训练模型。Nanodetd的性能要求对嵌入式设备极其友好,只要能装opencv就能无压力部署。于是我把nanodet移植到了ROS中。
现成的源码在这里 ros-nanodet
ROS中目标检测模型的部署(rospy)许多深度学习算法都是用python来写的,转成C++坑比较多,因此我选择先在rospy验证模型在ROS中的实施效果,如果项目对实时性要求较高,再将模型转换为C++的部署。(毕竟写一个C++工程麻烦的多,而且万一部署效果不行那就太坑了~)
demo测试如果想直接使用demo,可以按照以下顺序进行
# 环境要求:ROS Noetic (其它ROS版本应该也行)
# opencv-python 需要有cv2.dnn模块
# 在你喜欢的路径下创建ROS工作空间
mkdir -p ~/nanodet_ws/src
cd ~/yolo_ws/src
git clone https://github.com/stunback/ros-nanodet.git
catkin_make
# 打开三个Terminal,先初始化nanodet ros工作空间的环境
source devel/setup.bash
# 三个Terminal分别
roscore
rosrun usb_cam usb_cam_node
rosrun nanodet_ros ros_nanodet.py
然后就可以看到打开的摄像头和检测结果了~
对于自己训练的nanodet模型,转换成onnx替换src/nanodet-ros/model/中的.onnx和.names文件即可 (要求训练的nanodet的strides=8,16,32)
ROS python模型部署首先准备好要在ros中运行的模型和代码,例如我在工程中使用的nanodet.py(模型推理)与ros_nanodet.py(rospy部署)。模型推理直接采用了opencv中使用nanodet的代码,而rospy部署则完成创建节点、发布和订阅话题、摄像头图像接收的任务。
这里主要介绍用rospy部署模型,
#!/usr/bin/env python3
# 导入ros的lib库和api module
import roslib
import rospy
# 导入ros数据类型,包括std与sensor的数据
from std_msgs.msg import Header
from std_msgs.msg import String
from sensor_msgs.msg import CompressedImage
from sensor_msgs.msg import Image
# 导入其它组件
import os
import time
import cv2
import numpy as np
import sys
# 导入自定义的推理包
import nanodet_ros.nanodet
from nanodet_ros.nanodet import my_nanodet
# 摄像头输入图像的尺寸
IMAGE_WIDTH = 1280
IMAGE_HEIGHT = 720
# 订阅话题时的回调函数
def image_callback_1(image):
# 本ros_nanodet节点接收到当摄像头发布的消息时,会调用该回调函数
global ros_image, nanodet_model, nanodet_result_image
# 从buffer中恢复image
ros_image = np.frombuffer(image.data, dtype=np.uint8).reshape(image.height, image.width, -1)[...,::-1]
# 调用模型进行推理
nanodet_result_image = nanodet_model.detect(ros_image)
cv2.imshow('nanodet_result', nanodet_result_image)
cv2.waitKey(5)
# 将检测结果发布
publish_image(nanodet_result_image)
# 发布话题的函数
def publish_image(imgdata):
# 将需要发布的结果包装成ROS中的sensor image数据结构
image_temp = Image()
header = Header(stamp=rospy.Time.now())
header.frame_id = 'map'
image_temp.height = IMAGE_HEIGHT
image_temp.width = IMAGE_WIDTH
image_temp.encoding = 'rgb8'
image_temp.data = np.array(imgdata).tostring()
# print(imgdata)
# image_temp.is_bigendian=True
image_temp.header = header
image_temp.step = 1280*3
# 发布检测结果消息
image_pub.publish(image_temp)
if __name__ == '__main__':
# 载入模型文件
model_dir = os.path.dirname(nanodet_ros.nanodet.__file__)
model_path = os.path.join(model_dir, 'model/nanodet.onnx')
clsname_path = os.path.join(model_dir, 'model/coco.names')
# 初始化结果图片,用来接收目标检测结果图
nanodet_result_image = np.zeros([IMAGE_HEIGHT, IMAGE_WIDTH, 3])
'''
模型初始化
'''
nanodet_model = my_nanodet(model_path=model_path, clsname_path=clsname_path)
'''
ros节点初始化
'''
rospy.init_node('ros_nanodet')
image_topic_1 = "/usb_cam/image_raw"
# 订阅usb摄像头发布的话题(用于接收待检测图像)
rospy.Subscriber(image_topic_1, Image, image_callback_1, queue_size=1, buff_size=52428800)
rospy.loginfo('detect subscriber done')
# 发布一个result话题(用于将检测结果传给其它需要使用的节点)
image_pub = rospy.Publisher('/nanodet_result_out', Image, queue_size=1)
rospy.spin()
然后在nanodet_ros工作空间下创建nanodet_ros包以及配置相关文件,
cd src
catkin_create_pkg nanodet_ros rospy roscpp std_msgs sensor_msgs
# 根据需要修改package.xml和CMakeLists.txt
# 取消CMakeLists中catkin_python_setup()的注释
# 在scripts中放入部署文件ros_nanodet.py,
# 在src中新建nanodet_ros/,放入model相关文件
# 在本目录下设置setup.py文件,保证scripts中的文件可以找到src中的model
# 以上步骤完成后
catkin_make
# 测试
Bug处理
在测试中可能会出现No module cv2.dnn这样的报错,因为ros自带的Opencv版本为3.2.0
如果在ros noetic中,直接pip新版本opencv就行了
老ros版本可以通过将ros默认的cv2.so库文件修改成新opencv的库文件:
sudo easy_install trash-cli
sudo trash-put /opt/ros/your_ros_version/lib/python_version/dist-packages/cv2.so
pip install opencv-python