5.2.4 图像处理加速
高斯滤波
功能介绍
实现高斯滤波功能,加速类型分为BPU加速和NEON加速,BPU加速暂时只支持int16格式,NEON加速暂时只支持int16和uint16格式。
代码仓库:https://github.com/D-Robotics/hobot_cv
支持平台
平台 | 运行方式 | 示例功能 |
---|---|---|
RDK X3, RDK X3 Module | Ubuntu 20.04 (Foxy), Ubuntu 22.04 (Humble) | 读取ToF图片,进行高斯滤波 |
准备工作
RDK平台
-
RDK已烧录好Ubuntu 20.04/Ubuntu 22.04系统镜像。
-
RDK已成功安装TogetheROS.Bot。
使用介绍
BPU加速
当前版本支持的参数范围如下:
-
滤波类型:高斯滤波
-
支持的数据类型:int16
-
支持的分辨率:320x240。
-
滤波核:高斯3x3
-
sigmax: 0
-
sigmay: 0
NEON加速
当前版本支持的参数范围如下:
-
滤波类型:高斯滤波
-
支持的数据类型:int16、uint16
-
滤波核:高斯3x3,5x5
-
sigmax: 0
-
sigmay: 0
package中提供了简单测试程序,输入为本地的ToF图片,调用hobot_cv中接口实现高斯滤波功能。具体接口说明可参考hobot_cv pakcage中的README.md进一步了解。
RDK平台
- Foxy
- Humble
# 配置tros.b环境
source /opt/tros/setup.bash
# 配置tros.b环境
source /opt/tros/humble/setup.bash
# 从tros.b的安装路径中拷贝出运行示例需要的模型和配置文件。
cp -r /opt/tros/${TROS_DISTRO}/lib/hobot_cv/config/ .
# 启动BPU加速测试程序pkg
ros2 launch hobot_cv hobot_cv_gaussian_blur.launch.py
# 启动NEON加速测试程序pkg
ros2 launch hobot_cv hobot_cv_neon_blur.launch.py
结果分析
BPU加速
输出结果:
===================
image name :images/frame1_4.png
infe cost time:1314
guss_time cost time:2685
hobotcv save rate:0.510615
analyse_result start
---------GaussianBlur
out_filter type:2,cols:320,rows:240,channel:1
cls_filter type:2,cols:320,rows:240,channel:1
out_filter minvalue:96,max:2363
out_filter min,x:319,y:115
out_filter max,x:147,y:239
cls_filter minvalue:96,max:2364
cls_filter min,x:319,y:115
cls_filter max,x:147,y:239
diff diff diff
mat_diff minvalue:0,max:2
mat_diff min,x:2,y:0
mat_diff max,x:110,y:14
error sum:8.46524e+06,max:2,mean_error:0.439232
analyse_result,time_used_ms_end:2
analyse_result end
-------------------------
其中:
infe cost time:1314 //表示hobotcv加速的高斯滤波耗时1314微秒。
guss_time cost time:2685 //表示opencv的高斯滤波耗时2685微秒。
hobotcv save rate = (guss_time cost time - infe cost time)/ guss_time cost time = 0.510615
从以上比较结果,经过hobot_cv加速后性能提升50%。
error sum:8.46524e+06,max:2,mean_error:0.439232 //单张图片总误差是:8.46524e+06,单个像素最大误差是:2,平均误差:0.439232
平均误差 = sum / (width height) = 8.46524e+06 / (320 240)
hobot_cv高斯滤波BPU加速与opencv高斯滤波性能对比结果如下:
接口类型 | 滤波核大小 | 耗时(ms) | 单核CPU占比(%) |
---|---|---|---|
Hobotcv gaussian | Size(3,3) | 1.10435 | 15.9 |
Opencv gaussian | Size(3,3) | 2.41861 | 49.7 |
NEON加速
输出结果:
[neon_example-1] ===================
[neon_example-1] image name :config/tof_images/frame1_4.png
[neon_example-1] hobotcv mean cost time:674
[neon_example-1] opencv mean cost time:1025
[neon_example-1] hobotcv mean save rate:0.342439
[neon_example-1]
[neon_example-1] analyse_result start
[neon_example-1] ---------Mean_Blur
[neon_example-1] error sum:8.43744e+06,max:1,mean_error:0.430833
[neon_example-1]
[neon_example-1] hobotcv gaussian cost time:603
[neon_example-1] opencv gaussian cost time:2545
[neon_example-1] hobotcv gaussian save rate:0.763065
[neon_example-1]
[neon_example-1] analyse_result start
[neon_example-1] ---------Gaussian_Blur
[neon_example-1] error sum:9.13206e+06,max:1,mean_error:0.466302
[neon_example-1]
[neon_example-1] -------------------------
hobotcv gaussian cost time:603 //hobotcv 高斯滤波neon加速接口耗时603微秒。 opencv gaussian cost time:2545 //表示opencv的高斯滤波耗时2545微秒。 hobotcv gaussian save rate = (opencv cost time - hobotcv cost time)/ opencv cost time = 0.763065 从以上比较结果,经过hobotcv加速后高斯滤波性能提升76%。
hobot_cv高斯滤波NEON加速与opencv高斯滤波性能对比结果如下:
接口类型 | 滤波核大小 | 耗时(ms) | 单核CPU占比(%) |
---|---|---|---|
Hobotcv gaussian | Size(3,3) | 0.430284 | 27.1 |
Opencv gaussian | Size(3,3) | 2.42225 | 47 |
Hobotcv gaussian | Size(5,5) | 0.854871 | 39.1 |
Opencv gaussian | Size(5,5) | 3.15647 | 99.8 |