【RDK X5新板体验】将HIKCamera-Cpp-SDK使用Cython封装到Python,高效驱动海康工业相机
参加了9月22日的地瓜机器人开发者日活动~也是十分荣幸地被地瓜机器人评为”星推官“,在现场第一时间抢到了8GB内存的RDK X5
板卡,也算是首批体验用户了,那么话不多说,马上开始体验!
一、相比RDK X3
的主要提升
1.1 外观与接口
首先从外观上看看RDK X5
相比RDK X3
的改动与变化。
- 主芯片外形有改变,不太清楚为什么中间一块方形区域是镜面材质。
- 板卡上增加了
GPU
,优化图形处理。 - 天线集成为板载模块,支持
5GHz
频段WIFI信号。 - 新增音频信号
TRS
接口(耳机圆孔)。 - 40pin引脚排针改用了接地气的地瓜色。
- 新增CAN总线通信接口。(RMer有福了!)
- USB接口升级到了
USB3.0
*4个。 - 两路MIPI摄像头接口布局优化,PIN数改变。
- 调试串口接口由排针改为
Micro USB
接口,集成CH340
串口转USB模块。 - 新增闪连接口。(行业首创)
- 板卡上元器件数量剧增,元件布局更加美观,PCB走线更加流畅标准,总体做工细节也都不错。
1.2 性能与功能
由于增加了WI-FI6
与GPU
核心,网络连接与Desktop
图形桌面都是极致体验,不过个人还是更喜欢命令行。(手动狗头)
CPU
也提升到了8核,之前做了一份C++多线程后处理,结合Cython
实现Python
接口的加速后处理工具,估计过段时间要根据8核心的CPU
再做更新了,仅从核心数来算后处理速度能提升一倍,实际由于算力的提高应该不止,敬请期待。
根据官方数据,RDK X5
的板端推理综合算力为10TOPS
,相比RDK X3
提升了一倍,实测了多个模型的推理时间,都缩减为RDK X3
的一半不到。
二、USB 3.0 工业相机驱动体验
由于个人方向问题,RDK X5
的功能我不一定全都有用到,社区也也有较为全面测评报告,本博客就专注体验测评一下我在未来的项目与比赛中会用到的部分。
身为一名RMer
并且负责视觉算法,拿到RDK X5
后的第一件事就是研究使用RDK X5
如何使用工业相机,工业相机的效果和驱动方法都不同于普通USB相机,这里使用的是海康的MV-CS016-10UC USB彩色
型号相机,github链接奉上:HIK_Camera_TEF_Driver。
2.1 SDK的获取
海康这款相机的USB接口遵循USB3.0 Vision
协议,到海康的资料库寻找到通用USB设备SDK,发现并没有与RDK X5
的Arrch64
架构匹配的SDK版本,也不开放源码,我试过了反编译,不过以失败告终,无奈只能另辟蹊径。
于是咨询了一下这款相机的购买者,大哥发来一份ROS2
的源码,跑了下例程果然跑通了。
在这份工程中寻找到与海康有关的5个头文件和5个适用于Arm64
架构的链接库文件,靠这些文件就可以驱动相机了。
这边也附上正确的工业相机SDK获取链接,海康机器人:视觉产品/工业相机/工业面阵相机全系列,在该页面下选择自己的相机型号。
2.2 相机设置
SDK是C文件,一般使用ROS于Python进行交互,但是本文将展示绕过ROS,直接使用Cython将C++类转换到Python,便于Python直接调用。而SDK中也涉及了相机参数的调整,但对于快速体验来说工作量太大,可以直接使用海康配套的MVS上位机软件,调整好合适参数后设为默认参数,在嵌入式开发板上直接调取图像。
MVS上位机客户端及文档可以在海康机器人下载中心找到。各个参数的配置方法在官方文档中都有说明。接下来主要说明一下参数配置要点。
2.2.1 用户参数设置User Set Control
User Set Selector
:不能选择Default
,否则设定无法保存,可以先选User Set 1
。User Set Default
:同User Set Selector
选项一致。User Set Save
:做更改后需要点击这里保存
2.2.2 曝光时间设置
这是影响帧率的根本原因,相机曝光时间越短,同一时间内可曝光次数越多,CMOS的感光亮就越少,相机画面动态模糊越少,画面亮度越暗,反之亦然。所以需要寻找一个符合帧率需求且动态模糊少并且亮度足够的曝光时间。
- 当相机未在采集数据时,在
Acquisition Control
下将Exposure Mode
设为Timed
- 将
Exposure Time Mode
设为Standard
- 如果想自动动态调整曝光时间,将
Exposure Auto
设为Continuous
,然后在Auto Exposure Time Lower Limit
和Auto Exposure Time Upper Limit
中设置最低和最高曝光时间。 - 如果想固定曝光时间,将
Exposure Auto
设为Off
并在Exposure Time
中设置曝光时间,单位一般为微秒us
,相机帧率 <= 1/曝光时间(国际单位),这里我需要100帧左右,因此将曝光时间设置为10000us
。
2.2.3 图像亮度设置
- 调整完曝光时间后,相机的画面大概率是十分黑暗的,首先需要将相机的物理光圈开到最大(光圈值越小光圈最大)。
- 通过数字增益可以牺牲一部分画质提升画面亮度,在
Analog Control
下启动Digital Shift Enable
选项,然后修改Digital Shift
的值。 - 由于锁定了曝光时间,我们需要开启自动模拟增益来实时调整画面亮度,在
Analog Control
页面下将Gain Auto
设为Continuous
,然后修改Auto Gain Lower Limit
和Auto Gain Upper Limit
来调整自动模拟增益区间,最后在Brightness
下设置所期望画面亮度。
2.2.4 图片格式设置
工业相机不支持内部resize
,以我这款相机为例,原始分辨率为1440x1080
,但后续目标检测模型输入尺寸为640x640
,为了避免在板端进行resize
操作过度耗时,可以通过相机设置来降低画质。
-
在
Image Format Control
下将Binning Selector
选为Region 0
(一般为默认参数),然后将Binning Horizontal
和Binning Vertical
都选为“2”,此时可以发现图像的像素被融合为原来的一半。 -
完成
Binning
的设置后,我的相机像素被调整为720x540
,为了调整至640x640
或其他大小,可以在板端裁区图像的左右两侧,并在上下两侧填充图像,而裁剪部分工作也可以直接通过相机设置完成。在Image Format Control
下调整Width
、Height
、Offset X
和Offset Y
,具体效果如下图。
-
还需要调整输出图像格式,在
Image Format Control
下将ADCBit depth
调整为8 Bits
以便于后续图像数据被转换为uint8
类型图像数据,如果需要使用我的例程,还需要调整像素格式,将Pixel Format
调整为Bayer RG 8
,否则需要自行修改代码。
相机设置部分内容到此为止,完成后一定要记得在User Set Control
中保存设置并设置为默认参数。
2.3 使用SDK获取图像
2.3.1 程序工作流程
为了顺利从相机中获取图像,需要遵循通信协议规定的驱动流程,且由为了快速体验,我的例程项目中不涉及任何相机参数的调整,需要先再官方上位机MVS
中调整并设为默认参数,再在板卡中直接获取图像。相机的SDK中有所有结构体和函数的具体说明,这里我说明一下有用到的部分。
程序工作流程如下图所示。
每个流程对应的函数如下:
- 获取设备列表
MV_CC_EnumDevices()
- 创建设备句柄
MV_CC_CreateHandle()
- 启动设备
MV_CC_OpenDevice()
- 获取设备参数
MV_CC_GetIntValue()
- 开始取流
MV_CC_StartGrabbing()
- 获取图像
MV_CC_GetOneFrameTimeout()
- 停止取流
MV_CC_StopGrabbing()
- 关闭设备
MV_CC_CloseDevice()
- 销毁句柄
MV_CC_DestroyHandle()
具体函数参数可以在SDK的5个头文件中找到中文注释。
需要特别说明的是MV_CC_GetOneFrameTimeout()
函数会在获取图像数据前清空缓冲区以保证获取的图像是最新的数据,SDK中也有不清空缓冲区,依次从缓冲区中读取图像数据的函数,但为了保证实时性我们还是使用前者,而为了让程序被MV_CC_GetOneFrameTimeout()
卡住的时间段能被充分利用,我们在C++程序中使用多线程封装,以保证等待数据期间程序还能进行其他工作。
2.3.2 多线程封装
C++
中的HIK_VideoCapture
类定义如下:
class HIK_VideoCapture{
private:
int nRet = MV_OK; // ret变量
void* handle; // 相机句柄
MV_CC_DEVICE_INFO_LIST stDeviceList; // 设备列表
MVCC_INTVALUE stParam; // 照相参数
MV_FRAME_OUT_INFO_EX stImageInfo; // 图像信息结构体
std::thread background; // 声明后台线程
public:
int nWidth=0, nHeight=0; // 图片大小
int Photograph_ret = 0; // 拍摄函数的错误码,0为无错误
// 构造函数
HIK_VideoCapture(void);
// 初始化
int Init_Video(void);
// 获取图像并覆盖pData
void Photograph(unsigned char* pData, const int timeout);
// Photograph的多线程封装
void Photograph_background(unsigned char* pData, const int timeout);
// 等待拍摄完成
void Photograph_join();
// 关闭相机
void Close_Video(void);
通过Photograph
方法获取相机图像,通过Photograph_background
方法将Photograph
放入多线程封装中,以让其在后台运行,并准备Photograph_ret
成员作为后台线程运行状态的标识变量以指示Photograph
方法的工作情况。
其他方法与成员都为相机的初始化、启动、查错、关闭与内存清理服务,各个方法的具体实现详情可见我github仓库HIK_Camera_TEF_Driver中的HIK_TEF_Driver_module/HIK_TEF_Driver.cpp
文件。
2.4 Cython编译
2.4.1 Cpp2Python接口封装
在我的github仓库HIK_Camera_TEF_Driver中的HIK_TEF_Driver_module/HIK_TEF_Driver.cpp
文件和HIK_TEF_Driver_module/HIK_TEF_Driver.hpp
文件中的函数定义实际上已经实现了海康这款工业相机的C驱动方法,但为了让Python
也可以调用相机获取图像,我们使用Cython
将C++
的类与方法封装为Python
类与方法。
在此解释github仓库HIK_Camera_TEF_Driver中的HIK_TEF_Driver_module/__HIK_TEF_Driver__.pyx
文件中的封装方法。
私有成员、构造函数与析构函数
HIK_Video
类的初始化无需传入参数。HIK_Video
类的成员c_obj
用于与C++
类交互,image
是储存图像的容器。HIK_Video
类实例化时,成员的c_obj
类也随之实例化,成员image
被赋予None
值。类销毁时c_obj
和image
也随之销毁。
cdef class HIK_Video:
cdef HIK_VideoCapture* c_obj
cdef public image
def __cinit__(self):
self.c_obj = new HIK_VideoCapture()
self.image = None
def __dealloc__(self):
del self.c_obj
del self.image
初始化并启动相机Init_Video()
该方法调用C++
类HIK_VideoCapture()
的Init_Video()
方法并返回HIK_VideoCapture()
的nHeight
和nWidth
成员,并转换为python
的int
类型返回。
<int>self.c_obj.Init_Video()
:错误码
0
:无错误
-1
:获取设备列表失败
-2
:无设备连接
-3
:句柄创建失败
-4
:设备启动失败
-5
:Width获取失败
-6
:Height获取失败<int>self.c_obj.nHeight
:图像高度<int>self.c_obj.nWidth
:图像宽度
def Init_Video(self):
return <int>self.c_obj.Init_Video(), <int>self.c_obj.nHeight, <int>self.c_obj.nWidth
拍摄图像Photograph(timeout = 1000)
该方法为image
成员分配空间,并调用C++
类HIK_VideoCapture()
的Photograph_background()
方法创建线程后从相机读取图像并在后台线程等待数据传输,无返回值。
timeout
:最大等待时间,至少需要大于1/相机帧率
,单位毫秒
,默认为值为1000
。
def Photograph(self, timeout = 1000):
self.image = np.zeros((self.c_obj.nHeight, self.c_obj.nWidth), dtype=np.uint8)
self.c_obj.Photograph_background(<unsigned char*>cnp.PyArray_DATA(self.image), 1000)
查询拍摄是否完成isimagereturned(self)
:
该方法查询C++
类HIK_VideoCapture()
的成员hotograph_ret
查询拍摄是否完成,返回布尔值。
# 查询拍摄是否完成
def isimagereturned(self):
if <int>self.c_obj.Photograph_ret == -2:
return False
else:
return True
获取图像get_image(self)
使用该方法前务必保证Photograph(timeout = 1000)
方法至少被调用过一次,该方法会调用C++
类HIK_VideoCapture()
的Photograph_join()
方法等待并关闭后台拍摄线程。查询C++
类HIK_VideoCapture()
的Photograph_ret
成员并将其转换为python
的int
类型并返回,并将数据已被新图像覆盖的image
成员由Bayer RG 8
转换为RGB
格式的opencv-python
图像一并返回。
<int>self.c_obj.Photograph_ret
:错误码
0
:无错误
-1
:获取错误
-2
:线程未结束- cv2.cvtColor(self.image, cv2.COLOR_BayerRG2RGB):
RGB
格式的opencv-python
图像
def get_image(self):
# 结束线程
self.c_obj.Photograph_join()
# 将Bayer RG转为BGR图像并返回
return <int>self.c_obj.Photograph_ret, cv2.cvtColor(self.image, cv2.COLOR_BayerRG2RGB)
关闭摄像头Close_Video()
该方法会调用C++
类HIK_VideoCapture()
的Close_Video()
停止取流,关闭设备并销毁设备句柄。
2.4.2 编译为Python
可用的链接共享库
使用setup.py
文件将C++
库文件、头文件和Cython
封装的.pyx
文件编译成Python
可用的链接共享库。具体内容较为简单,都有固定模板,需要注意的是在setup.py
文件指定源码、头文件、库文件以及链接库名部分需要特别注意,否则会编译失败。
编译方法:在HIK_TEF_Driver_module
目录下键入
sudo python3 setup.py build_ext --inplace
终端输出绿色字样Setup has been completed!
即表示编译成功。
编译成功后在项目目录下的python脚本中,可以以下语句引入相机驱动库。
from HIK_TEF_Driver_module import HIK_TEF_Driver
2.5 驱动例程
在我的github仓库HIK_Camera_TEF_Driver中有具体介绍示例程序的使用方法,示例会连续无间断拍摄约几百帧(可调)图片,简单测试相机帧率,并保存第一张图片与最后一张图片以确定图像的实时性,经测试,在锁定5ms
的曝光时间下,图像尺寸为640x540
,视频流帧率可以达到约99 fps
,误差来源于相机内部的图像整合计算以及前后两帧的读取间隔。
2.6 极限帧率测试
在HIK_Camera_TEF_Driver的基础下,我们可以测试相机的极限帧率,保持图像的分辨率在640x540
,在MVS
上位机中将相机的曝光时间调整到最低值15us
,这样的曝光时间拍摄到的画面几乎是全黑的,但我们主要以测试为目的,不在意画面。在通信协议的限制下,图像传输带宽约764兆
左右,图像帧率可以达到276fps
左右。
设置完成后将设定保存,使用HIK_Camera_TEF_Driver的test_HIK.py
再次在RDK X5
测试视频帧率,为了保证测试值稳定性,我们连续拍摄1000张图片。
在RDK X5
中的测试帧率略低于在PC机MVS
上位机中的帧率,但从数值上来看只是板端的计算耗时导致前后两帧图像获取稍有间隔导致的,RDK X5
与PC机的USB 3.0
图像传输速度是一致的,而在640x540
的图像帧率下已知极限帧率为276fps
时,可以将曝光时间提高到约3.6ms
以在保持帧率的同时提高画面亮度与质量。
三、总结
RDK X5
的各个功能模块是十分多元的,这里我暂时只能针对工业相机这一块做相对比较具体的测评开发。
在RDK X5
中驱动海康工业相机的性能参数基本和PC机中一致,在USB 3.0 Vision
的通信速率下,如果视频分辨率要求不高,帧率几乎可以达到以百为单位,足以解决当前工业相机的大部分应用场景。
后续我也会继续完善HIK_Camera_TEF_Driver的其他功能,例如利用SDK调整相机参数以省去上位机调试这一步骤,也会及时更新到地瓜机器人Nodehub中,敬请期待。