CV图像加速处理
OpenCV是一个著名的机器视觉处理库,相信大家都有听过,这个库中有很多图像处理的基础算法,比如灰度变化、图像滤波等,不过这个库为了保证较好的通用性,主要通过软件实现各种算法,TogetherROS对此作了大量优化,我们一起来看看。
TogetherROS视觉加速
TogetherROS中集成了地平线Hobot CV视觉加速库,通过底层芯片中的硬件引擎,软硬件协同,可以提升常用CV算子的性能,降低系统资源的消耗,例如高斯滤波、图像缩放、畸变校正等常用的视觉处理方法。
而且在接口风格上兼容OpenCV,可以做到与OpenCV混合编程,便于视觉应用的开发。
具体测试CV加速库的效率,与OpenCV中软件实现的效率进行对比,我们分别对比图像缩放的帧率,图像旋转的帧率,高斯滤波的帧率,通过Hobot CV视觉加速库运行的帧率可以做到OpenCV的2到3倍,甚至更多倍。
效果这么好,具体该如何使用呢?
高斯滤波
我们先来看下图像处理中常用的高斯滤波算法,OpenCV和hobotcv,正面PK一下,我们也看看在程序中如何使用hobotcv的图像处理加速算法。
运行示例程序
$ source /opt/tros/setup.bash
$ cp -r /opt/tros/lib/hobot_cv/config/ .
$ ros2 launch hobot_cv hobot_cv_gaussian_blur.launch.py
代码解析
代码地址:https://c-gitlab.horizon.ai/HHP/box/hobot_cv/-/blob/develop/test/test_gaussian_blur.cpp
// Copyright (c) 2021 Horizon Robotics.All Rights Reserved.
//
// The material in this file is confidential and contains trade secrets
// of Horizon Robotics Inc. This is proprietary information owned by
// Horizon Robotics Inc. No part of this work may be disclosed,
// reproduced, copied, transmitted, or used in any way for any purpose,
// without the express written permission of Horizon Robotics Inc.
#include <algorithm>
#include <chrono>
#include <fstream>
#include <iomanip>
#include <iostream>
#include <iterator>
#include <map>
#include <queue>
#include <utility>
#include "hobotcv_gaussian_blur.h"
#include "opencv2/core/mat.hpp"
#include "opencv2/imgcodecs.hpp"
#include "opencv2/imgproc.hpp"
void analyse_result(cv::Mat &out_filter, cv::Mat &cls_filter,
std::string flag_name) {
auto start_time = std::chrono::steady_clock::now();
std::cout << "" << std::endl;
std::cout << "analyse_result start " << std::endl;
std::cout << "---------" << flag_name << std::endl;
std::cout << "out_filter type:" << out_filter.type()
<< ",cols:" << out_filter.cols << ",rows:" << out_filter.rows
<< ",channel:" << out_filter.channels() << std::endl;
std::cout << "cls_filter type:" << cls_filter.type()
<< ",cols:" << cls_filter.cols << ",rows:" << cls_filter.rows
<< ",channel:" << cls_filter.channels() << std::endl;
double minvalue, maxvalue;
cv::Point mixIdx, maxIdx;
cv::minMaxLoc(out_filter, &minvalue, &maxvalue, &mixIdx, &maxIdx);
std::cout << "out_filter minvalue:" << minvalue << ",max:" << maxvalue
<< std::endl;
std::cout << "out_filter min,x:" << mixIdx.x << ",y:" << mixIdx.y
<< std::endl;
std::cout << "out_filter max,x:" << maxIdx.x << ",y:" << maxIdx.y
<< std::endl;
cv::minMaxLoc(cls_filter, &minvalue, &maxvalue, &mixIdx, &maxIdx);
std::cout << "cls_filter minvalue:" << minvalue << ",max:" << maxvalue
<< std::endl;
std::cout << "cls_filter min,x:" << mixIdx.x << ",y:" << mixIdx.y
<< std::endl;
std::cout << "cls_filter max,x:" << maxIdx.x << ",y:" << maxIdx.y
<< std::endl;
cv::Mat mat_diff = cv::abs(out_filter - cls_filter);
cv::Scalar sum_error = cv::sum(mat_diff >= 1);
cv::Scalar mean_error = cv::sum(mat_diff) / (mat_diff.rows * mat_diff.cols);
cv::minMaxLoc(mat_diff, &minvalue, &maxvalue, &mixIdx, &maxIdx);
std::cout << "" << std::endl;
std::cout << "diff diff diff" << std::endl;
std::cout << "mat_diff minvalue:" << minvalue << ",max:" << maxvalue
<< std::endl;
std::cout << "mat_diff min,x:" << mixIdx.x << ",y:" << mixIdx.y << std::endl;
std::cout << "mat_diff max,x:" << maxIdx.x << ",y:" << maxIdx.y << std::endl;
std::cout << "" << std::endl;
std::cout << "error sum:" << sum_error[0] << ",max:" << maxvalue
<< ",mean_error:" << mean_error[0] << std::endl;
int time_used_ms_end = std::chrono::duration_cast<std::chrono::milliseconds>(
std::chrono::steady_clock::now() - start_time)
.count();
std::cout << "analyse_result,time_used_ms_end:" << time_used_ms_end
<< std::endl;
std::cout << "analyse_result end " << std::endl;
std::cout << "" << std::endl;
}
int main() {
int32_t ret = -1;
HobotGaussianBlurParam blur_param;
HOBOTCV_INITIALIZE_GAUSSIAN_BLUR_PARAM(&blur_param);
HobotCVGaussianBlurHandle handle;
ret = HobotCVGaussianBlurCreate(blur_param, &handle);
if (ret < 0) {
printf("HobotCVGaussianBlurCreate failed, error msg:%d\n", ret);
return -1;
}
for (int i = 0; i < 5; i++) {
std::string m_tof_file_s = "images/frame1_" + std::to_string(i) + ".jpg";
std::cout << "===================" << std::endl;
std::cout << "image name :" << m_tof_file_s << std::endl;
cv::Mat src = cv::imread(m_tof_file_s, CV_16UC1);
cv::Mat dst;
cv::medianBlur(src, src, 3);
auto start_time_infe = std::chrono::steady_clock::now();
ret = HobotCVGaussianBlurProcess(handle, &src, &dst);
if (ret < 0) {
printf("HobotCVGaussianBlurProcess failed, error msg:%d\n", ret);
return -1;
}
int infe_time = std::chrono::duration_cast<std::chrono::microseconds>(
std::chrono::steady_clock::now() - start_time_infe).count();
std::cout << "infe cost time:" << infe_time << std::endl;
auto start_time_gauss = std::chrono::steady_clock::now();
cv::Mat gaussian_tof;
cv::GaussianBlur(src, gaussian_tof, cv::Size(3, 3), 0, 0,
cv::BORDER_REPLICATE);
int guss_time = std::chrono::duration_cast<
std::chrono::microseconds>(
std::chrono::steady_clock::now() - start_time_gauss).count();
std::cout << "guss_time cost time:" << guss_time << std::endl;
float save_rate = float((guss_time * 1.0 - infe_time * 1.0) / guss_time);
std::cout << "hobotcv save rate:" << save_rate << std::endl;
analyse_result(dst, gaussian_tof, "GaussianBlur");
std::cout << "-------------------------" << std::endl;
std::cout << "" << std::endl;
}
ret = HobotCVGaussianBlurDestroy(handle);
if (ret < 0) {
printf("HobotCVGaussianBlurDestroy failed, error msg:%d\n", ret);
return -1;
}
return 0;
}
图像裁剪与缩放
再来看另外一个案例,图像的裁剪与缩放,比如这样一幅图片,我们尝试剪裁左上角的一小块图像出来,或者对裁剪的某一块图像放大来看看。
运行示例程序
# 配置TogetherROS环境
source /opt/tros/setup.bash
# 从TogetherROS的安装路径中拷贝出运行示例需要的模型和配置文件。
cp -r /opt/tros/lib/hobot_cv/config/ .
# 启动launch文件
ros2 launch hobot_cv hobot_cv_crop_resize.launch.py
代码解析
代码地址:https://c-gitlab.horizon.ai/HHP/box/hobot_cv/-/blob/develop/src/test.cpp
// Copyright (c) 2021 Horizon Robotics.All Rights Reserved.
//
// The material in this file is confidential and contains trade secrets
// of Horizon Robotics Inc. This is proprietary information owned by
// Horizon Robotics Inc. No part of this work may be disclosed,
// reproduced, copied, transmitted, or used in any way for any purpose,
// without the express written permission of Horizon Robotics Inc.
#include "include/hobotcv_imgproc.h"
#include "include/utils.h"
#include "opencv2/core/mat.hpp"
#include "opencv2/core/types.hpp"
#include "opencv2/imgcodecs.hpp"
#include "opencv2/opencv.hpp"
#include <fstream>
#include <string>
#include <chrono>
#include <iostream>
void writeImg(cv::Mat &mat, std::string imgfile)
{
cv::Mat img_bgr;
cv::cvtColor(mat, img_bgr, cv::COLOR_YUV2BGR_NV12);
cv::imwrite(imgfile, img_bgr);
}
int main()
{
std::string image_file = "config/test.jpg";
cv::Mat bgr_mat = cv::imread(image_file, cv::IMREAD_COLOR);
auto src_height = bgr_mat.rows;
auto src_width = bgr_mat.cols;
cv::Mat srcmat_nv12;
BGRToNv12(bgr_mat, srcmat_nv12);
auto dst_height = src_height / 2;
auto dst_width = src_width / 2;
cv::Mat dstmat_nv12(dst_height * 3 / 2, dst_width, CV_8UC1);
auto before_resize = std::chrono::system_clock::now();
auto ret = hobot_cv::hobotcv_resize(srcmat_nv12, src_height, src_width, dstmat_nv12, dst_height, dst_width);
auto after_resize = std::chrono::system_clock::now();
auto interval = std::chrono::duration_cast<std::chrono::milliseconds>(
after_resize - before_resize).count();
if(0 == ret) {
std::cout << "resize finish, time: " << interval << "ms" << std::endl;
}
writeImg(dstmat_nv12, "./resize.jpg");
auto before_crop = std::chrono::system_clock::now();
auto cropmat =
hobot_cv::hobotcv_crop(
srcmat_nv12, src_height, src_width, 200, 200, cv::Range(0, 200), cv::Range(0, 200));
auto after_crop = std::chrono::system_clock::now();
interval = std::chrono::duration_cast<std::chrono::milliseconds>(
after_crop - before_crop).count();
std::cout << "crop finish, time: " << interval << "ms" << std::endl;
writeImg(cropmat, "./crop.jpg");
auto before_cropResize = std::chrono::system_clock::now();
auto cropResizemat =
hobot_cv::hobotcv_crop(
srcmat_nv12, src_height, src_width, src_height, src_width, cv::Range(200, 400), cv::Range(200, 400));
auto after_cropResize = std::chrono::system_clock::now();
interval = std::chrono::duration_cast<std::chrono::milliseconds>(
after_cropResize - before_cropResize).count();
std::cout << "cropResize finish, time: " << interval << "ms" << std::endl;
writeImg(cropResizemat, "./cropResize.jpg");
return 0;
}