opencv之图像格式与效率
前言
本文主要讨论在原始图像和压缩图像两种格式
- 对于本地图片,
png
格式为压缩图片,jpeg
格式为原始图片. - 对于ros消息,
sensor_msg::CompressedImage
为压缩图像,sensor_msg::Image
为原始图像.
测试代码
- 加载本地图片
#include<iostream>
#include <chrono>
#include <opencv2/opencv.hpp>
int main()
{
std::string image_path = "/home/liuzhiyang/Desktop";
cv::Mat png_image, jpeg_image;
for (size_t i = 0; i < 10; ++i)
{
auto png_start_time = std::chrono::system_clock::now();
std::string png_image_name = image_path + "/image_png/" + std::to_string(i) + ".png";
png_image = cv::imread(png_image_name);
auto png_end_time = std::chrono::system_clock::now();
auto png_duration = std::chrono::duration_cast<std::chrono::milliseconds>(png_end_time - png_start_time).count();
auto jpeg_start_time = std::chrono::system_clock::now();
std::string jpeg_image_name = image_path + "/image_jpeg/" + std::to_string(i) + ".jpeg";
jpeg_image = cv::imread(jpeg_image_name);
auto jpeg_end_time = std::chrono::system_clock::now();
auto jpeg_duration = std::chrono::duration_cast<std::chrono::milliseconds>(jpeg_end_time - jpeg_start_time).count();
std::cout << "load png image time cost: " << png_duration << " ms" << std::endl;
std::cout << "load jpeg image time cost: " << jpeg_duration << " ms" << std::endl;
}
return -1;
}
结果
load png image time cost: 91 ms
load jpeg image time cost: 16 ms
load png image time cost: 53 ms
load jpeg image time cost: 17 ms
load png image time cost: 53 ms
load jpeg image time cost: 16 ms
load png image time cost: 50 ms
load jpeg image time cost: 16 ms
load png image time cost: 50 ms
load jpeg image time cost: 15 ms
load png image time cost: 53 ms
load jpeg image time cost: 16 ms
load png image time cost: 50 ms
load jpeg image time cost: 15 ms
load png image time cost: 52 ms
load jpeg image time cost: 15 ms
load png image time cost: 50 ms
load jpeg image time cost: 15 ms
load png image time cost: 50 ms
load jpeg image time cost: 15 ms
对于本地图片, 原始图片加载时间是压缩图片的将近3~5倍, 同时存储量也为压缩图片的5倍左右, 因此推荐保存和读取压缩格式的图片.
- 读取ros消息图像
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <opencv2/opencv.hpp>
#include <chrono>
ros::Publisher g_image_ros_pub;
image_transport::Publisher g_image_transport_pub;
void imageCallbackCompressed(const sensor_msgs::CompressedImageConstPtr &input_msg)
{
std::cout << "compressed image callback function! " << std::endl;
auto start_1 = std::chrono::system_clock::now();
// Image to cv::Mat
cv::Mat image;
try
{
image = cv::imdecode(cv::Mat(input_msg->data),1);
}
catch (cv_bridge::Exception& e)
{
ROS_ERROR("Could not convert to image!");
return;
}
auto end_1 = std::chrono::system_clock::now();
auto duration_1 = std::chrono::duration_cast<std::chrono::milliseconds>(end_1 - start_1).count();
// pub image
auto start_2 = std::chrono::system_clock::now();
sensor_msgs::ImagePtr msg = cv_bridge::CvImage(input_msg->header, "bgr8", image).toImageMsg();
g_image_transport_pub.publish(msg);
auto end_2 = std::chrono::system_clock::now();
auto duration_2 = std::chrono::duration_cast<std::chrono::milliseconds>(end_2 - start_2).count();
std::cout << "compressed image sub cost: " << duration_1 << std::endl;
std::cout << "image transport pub cost : " << duration_2 << std::endl;
}
void imageCallback(const sensor_msgs::ImageConstPtr &input_msg)
{
std::cout << "raw image callback function!" << std::endl;
auto start_1 = std::chrono::system_clock::now();
// Image to cv::Mat
cv::Mat image;
try
{
image = cv_bridge::toCvShare(input_msg, "bgr8")->image;
}
catch (cv_bridge::Exception& e)
{
ROS_ERROR("Could not convert to image!");
return;
}
auto end_1 = std::chrono::system_clock::now();
auto duration_1 = std::chrono::duration_cast<std::chrono::milliseconds>(end_1 - start_1).count();
// pub image
auto start_2 = std::chrono::system_clock::now();
sensor_msgs::ImagePtr msg = cv_bridge::CvImage(input_msg->header, "bgr8", image).toImageMsg();
g_image_ros_pub.publish(msg);
auto end_2 = std::chrono::system_clock::now();
auto duration_2 = std::chrono::duration_cast<std::chrono::milliseconds>(end_2 - start_2).count();
std::cout << "raw image sub cost: " << duration_1 << std::endl;
std::cout << "ros publisher cost: " << duration_2 << std::endl;
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "image_listener");
ros::NodeHandle nh;
ros::NodeHandle priv_nh("~");
image_transport::ImageTransport it(nh);
std::string input_raw_image_topic = "/cam_0/hik_image";
std::string input_compressed_image_topic = "/cam_0/hik_image/compressed";
ros::Subscriber raw_sub = nh.subscribe(input_raw_image_topic, 1, imageCallback);
g_image_ros_pub = nh.advertise<sensor_msgs::Image>("image_ros_pub", 1);
ros::Subscriber compressed_sub = nh.subscribe(input_compressed_image_topic, 1, imageCallbackCompressed);
g_image_transport_pub = it.advertise("image_transport_pub", 1);
ros::spin();
return 0;
}
结果
raw image callback function!
raw image sub cost: 0
ros publisher cost: 5
raw image callback function!
raw image sub cost: 0
ros publisher cost: 5
compressed image callback function!
compressed image sub cost: 15
image transport pub cost : 21
compressed image callback function!
compressed image sub cost: 15
image transport pub cost : 21
raw image callback function!
raw image sub cost: 0
ros publisher cost: 2
compressed image callback function!
compressed image sub cost: 15
image transport pub cost : 21
compressed image callback function!
compressed image sub cost: 15
image transport pub cost : 21
- 对于原始格式的图像,
sensor_msg::Image
->cv::Mat
几乎不耗时, 但是对于压缩格式的图像,sensor_msg::CompressedImage
->cv::Mat
需要对图像解压缩, 耗时需要一定时间. - 使用
ros::Publisher
发布图像, 在被订阅的情况下, 耗时较少. 但是使用image_transport::Publisher
发布图像, 如果有定法订阅了发布的compressed图像, 那么在发布是需要对图像进行压缩, 耗时需要一定的时间.
总结
对于图像格式, 如果需要存储的话, 保存到本地或者录bag包, 那么推荐压缩格式. 如果是进行通信的话, 需要考虑压缩和解压缩的时间, 对于单个相机还是考虑压缩格式, 如果是多个相机的话, 推荐使用原始格式的图像消息传输.
chrislzy: 如有疑惑,错误或者建议,请在评论区留下您宝贵的文字; 转载请注明作者和出处,未经允许请勿用于商业用途!