概要
想要实现读取视频或者图片,然后发布到ros中,用rivz显示。
需要借助几个库,如下
catkin_create_pkg test roscpp rosmsg cv_bridge image_transport sensor_msgs std_msgs
实现方式
方式一 ros::Publisher
#include <cv_bridge/cv_bridge.h>
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <chrono>
#include <opencv2/opencv.hpp>
double GetTimeCostms(const std::chrono::time_point<std::chrono::high_resolution_clock>& start) {
auto end = std::chrono::high_resolution_clock::now();
double milliseconds = std::chrono::duration_cast<std::chrono::duration<double>>(end - start).count() * 1000;
// ROS_INFO_STREAM("handle cost ms:" << milliseconds);
return milliseconds;
}
int main(int argc, char** argv) {
// 初始化ROS节点
ros::init(argc, argv, "image_publisher");
// 创建一个ROS节点句柄
ros::NodeHandle nh;
// 创建一个图像发布者
ros::Publisher image_pub = nh.advertise<sensor_msgs::Image>("image_topic", 10);
// 读取本地图片
cv::Mat image = cv::imread("./picture/0.jpg");
// 发布图像消息
ros::Rate rate(25); // 设置发布频率为10Hz
while (ros::ok()) {
auto start = std::chrono::high_resolution_clock::now();
auto start1 = start;
// 创建一个CvBridge对象
cv_bridge::CvImage cv_image;
// 将OpenCV图像转换为ROS图像消息
cv::Mat imageResize;
// cv::resize(image, imageResize, cv::Size(), 0.5, 0.5);
// cv_image.image = imageResize;
cv_image.image = image;
cv_image.encoding = "bgr8";
cv_image.header.stamp = ros::Time::now();
auto msg = cv_image.toImageMsg();
ROS_INFO_STREAM("1cost ms:" << GetTimeCostms(start));
start = std::chrono::high_resolution_clock::now();
image_pub.publish(msg);
ROS_INFO_STREAM("2cost ms:" << GetTimeCostms(start));
ROS_INFO_STREAM("3cost ms:" << GetTimeCostms(start1));
ros::spinOnce();
rate.sleep();
}
return 0;
}

方式二 image_transport::Publisher
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <chrono>
#include <opencv2/opencv.hpp>
double GetTimeCostms(const std::chrono::time_point<std::chrono::high_resolution_clock>& start) {
auto end = std::chrono::high_resolution_clock::now();
double milliseconds = std::chrono::duration_cast<std::chrono::duration<double>>(end - start).count() * 1000;
// ROS_INFO_STREAM("handle cost ms:" << milliseconds);
return milliseconds;
}
int main(int argc, char** argv) {
// 初始化ROS节点
ros::init(argc, argv, "image_publisher");
// 创建一个ROS节点句柄
ros::NodeHandle nh;
// 创建一个图像发布者
image_transport::ImageTransport it_(nh);
image_transport::Publisher image_pub = it_.advertise("image_topic", 10);
// 读取本地图片
cv::Mat image = cv::imread("./picture/0.jpg");
// 发布图像消息
ros::Rate rate(25); // 设置发布频率为10Hz
while (ros::ok()) {
auto start = std::chrono::high_resolution_clock::now();
auto start1 = start;
// 创建一个CvBridge对象
cv_bridge::CvImage cv_image;
// 将OpenCV图像转换为ROS图像消息
cv::Mat imageResize;
// cv::resize(image, imageResize, cv::Size(), 0.5, 0.5);
// cv_image.image = imageResize;
cv_image.image = image;
cv_image.encoding = "bgr8";
// cv_image.header.stamp = ros::Time::now();
auto msg = cv_image.toImageMsg();
ROS_INFO_STREAM("1cost ms:" << GetTimeCostms(start));
start = std::chrono::high_resolution_clock::now();
image_pub.publish(msg);
ROS_INFO_STREAM("2cost ms:" << GetTimeCostms(start));
ROS_INFO_STREAM("3cost ms:" << GetTimeCostms(start1));
ros::spinOnce();
rate.sleep();
}
return 0;
}
-> % rostopic list
/clicked_point
/image_topic
/image_topic/compressed
/image_topic/compressed/parameter_descriptions
/image_topic/compressed/parameter_updates
/image_topic/compressedDepth
/image_topic/compressedDepth/parameter_descriptions
/image_topic/compressedDepth/parameter_updates
/image_topic/theora
/image_topic/theora/parameter_descriptions
/image_topic/theora/parameter_updates
/initialpose
/move_base_simple/goal
/rosout
/rosout_agg
/rviz_1707222063696618079/compressed/parameter_descriptions
/rviz_1707222063696618079/compressed/parameter_updates
/tf
/tf_static
ros topic 对比
使用方式二多了很多个topic。
-
raw

-
compressed

-
compressedDepth


-
theora

性能对比

总结
需要跨终端传输,用image_transport::Publisher,会压缩,方便传输,接收放也需要解压。
不需要时,直接ros::Publisher,节省性能。
本文介绍了在ROS中使用cv_bridge和image_transport两种方式实现读取并发布视频或图片,比较了它们在性能上的差异,特别强调了image_transport的压缩功能对传输效率的影响。
396

被折叠的 条评论
为什么被折叠?



