1. image_transport
image_transport是一个用于实现图像传输的工具包,它提供了一种灵活的方式来订阅和发布图像数据,但它并不直接操作消息类型。
使用 image_transport 将发送的图像转发为压缩图像
如果不想写程序对图像进行处理,可以使用 image_transport 包的命令行工具来将 Image 消息转发为 CompressedImage 消息
rosrun image_transport republish raw in:=/image compressed out:=/image
该节点会自动订阅/image话题下的Image消息,并将CompressedImage格式的消息发送到/image/compressed话题下
2.sensor_msgs/Image 和 sensor_msgs/CompressedImage
(1)两者的关系
sensor_msgs/Image 和 sensor_msgs/CompressedImage 是 ROS 中用于传输图像数据的两种不同消息类型,它们有一些显著的区别:
数据格式:
sensor_msgs/Image:原始的未经压缩的图像消息,通常用于传输原始图像数据,例如 RGB、灰度或深度图像。
sensor_msgs/CompressedImage:经过压缩的图像消息,以减少数据量。压缩格式通常是 JPEG 或 PNG。
数据量:
sensor_msgs/Image 包含原始图像数据,因此它可能会占用较多的带宽和存储空间。
sensor_msgs/CompressedImage 则通过压缩算法减少了数据量,因此在传输和存储时需要的带宽和空间更少。
传输效率:
由于 sensor_msgs/CompressedImage 的数据量较小,因此在网络传输中具有更高的效率,尤其是在带宽受限的情况下。
sensor_msgs/Image 虽然保留了图像的所有信息,但在传输过程中可能需要更多的带宽和资源。
(2)sensor_msgs/Image
sensor_msgs/Image 是ROS(机器人操作系统)中定义的一种消息类型,用于在ROS系统中传输图像数据。该消息类型通常用于机器人视觉、图像处理和计算机视觉应用中。
sensor_msgs/Image 消息格式通常包含以下字段:
- header: 用于存储消息的元数据,如时间戳、坐标系等信息。
- height: 图像的高度(以像素为单位)。
- width: 图像的宽度(以像素为单位)。
- encoding: 图像数据的编码格式,常见的编码格式包括 "rgb8"、"bgr8"、"mono8" 等。
- is_bigendian: 表示图像数据是否采用大端字节顺序。
- step: 表示每一行图像数据所占用的字节数。
- data: 存储图像数据的字节数组。
以下是一个 sensor_msgs/Image 消息的示例:
header:
seq: 0
stamp:
secs: 1622525477
nsecs: 123456789
frame_id: "camera_frame"
height: 480
width: 640
encoding: "rgb8"
is_bigendian: 0
step: 1920
data: [255, 0, 0, 255, 255, ...]
(3)sensor_msgs/CompressedImage
sensor_msgs/CompressedImage是ROS(机器人操作系统)中用于传输压缩图像数据的消息类型之一。它允许在ROS系统中传输图像数据,同时减少带宽占用和传输延迟。
该消息类型包含以下字段:
header:用于存储消息头信息,如时间戳和帧ID。
format:字符串,表示图像编码格式,例如“jpeg”、“png”等。
data:字节数组,存储压缩后的图像数据。
以下是一个 sensor_msgs/CompressedImage 消息的示例:
header:
seq: 0
stamp:
secs: 1622525477
nsecs: 123456789
frame_id: "camera_frame"
format: "jpeg"
data: [255, 216, 255, 224, 0, ...]
3. 发布压缩图像
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <opencv2/highgui/highgui.hpp>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/CompressedImage.h>
int main(int argc, char** argv)
{ros::init(argc, argv, "image_publisher");
ros::NodeHandle nh;
ros::Publisher pub = nh.advertise<sensor_msgs::CompressedImage>("compressed_image", 1);
ros::Publisher pubO = nh.advertise<sensor_msgs::Image>("image_raw", 1);
cv::Mat image = cv::imread("./0000.jpg", CV_LOAD_IMAGE_COLOR);
sensor_msgs::CompressedImage compressed_msg;
std::vector<int> compression_params;
compression_params.push_back(cv::IMWRITE_JPEG_QUALITY);
compression_params.push_back(95);
compressed_msg.header.stamp = ros::Time::now();
compressed_msg.format = "jpeg";
cv::imencode(".jpg", image, compressed_msg.data, compression_params);
sensor_msgs::ImagePtr raw_msg=cv_bridge::CvImage(std_msgs::Header(), "bgr8", image).toImageMsg();
ros::Rate loop_rate(5);
while (nh.ok()) {
pub.publish(compressed_msg);
pubO.publish(raw_msg);//发布图像消息
ros::spinOnce();
loop_rate.sleep();
}
return 0;
}
4. 接收压缩图像
#include <ros/ros.h>
#include <sensor_msgs/CompressedImage.h>
#include <opencv2/opencv.hpp>
#include <cv_bridge/cv_bridge.h>
// 回调函数,处理接收到的压缩图像数据
void imageCallback(const sensor_msgs::CompressedImage::ConstPtr& msg)
{
cv_bridge::CvImagePtr cv_ptr;
try
{
// Convert compressed image message to OpenCV image
cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
}
catch (cv_bridge::Exception& e)
{
ROS_ERROR("cv_bridge exception: %s", e.what());
return;
}
// Access the image using cv::Mat
cv::Mat image = cv_ptr->image;
// 在这里可以对图像进行进一步处理,例如显示、保存等操作
cv::imshow("Received Image", image);
cv::waitKey(1);
}
int main(int argc, char** argv)
{
// 初始化ROS节点
ros::init(argc, argv, "image_subscriber");
// 创建节点句柄
ros::NodeHandle nh;
// 创建一个订阅者,订阅名为"/compressed_image"的话题,回调函数为imageCallback
ros::Subscriber sub = nh.subscribe("/compressed_image", 1, imageCallback);
// 初始化OpenCV窗口
// cv::namedWindow("Received Image", cv::WINDOW_AUTOSIZE);
// 循环等待回调函数
ros::spin();
return 0;
}
5. CMakeLists.txt
cmake_minimum_required(VERSION 2.8.3)
project(msg2image)
## Compile as C++11, supported in ROS Kinetic and newer
add_compile_options(-std=c++11)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
cv_bridge
image_transport
roscpp
rospy
sensor_msgs
std_msgs
)
find_package(PCL REQUIRED)
find_package(OpenCV REQUIRED)
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES msg2image
# CATKIN_DEPENDS cv_bridge image_transport roscpp rospy sensor_msgs std_mags
# DEPENDS system_lib
)
include_directories(
include ${catkin_INCLUDE_DIRS}
${PROJECT_NAME}
${OpenCV_INCLUDE_DIRS}
)
add_executable(ImageCompressedpub src/ImageCompressedpub.cpp)
add_dependencies(ImageCompressedpub ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(ImageCompressedpub ${catkin_LIBRARIES} ${OpenCV_LIBS})
add_executable(Imdecodesub src/Imdecodesub.cpp)
add_dependencies(Imdecodesub ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(Imdecodesub ${catkin_LIBRARIES} ${OpenCV_LIBS})
6.发布原始图像
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <sensor_msgs/image_encodings.h>
#include <opencv2/opencv.hpp>
#include <cv_bridge/cv_bridge.h>
int main(int argc, char** argv) {
ros::init(argc, argv, "image_publisher");
ros::NodeHandle nh;
image_transport::ImageTransport it(nh);
image_transport::Publisher pub = it.advertise("compressed_image_topic", 1);
// 打开图像文件或者从摄像头捕获图像
cv::Mat image = cv::imread("./0000.jpg", cv::IMREAD_COLOR);
ros::Rate loop_rate(10); // 发布频率,这里设定为10Hz
while (nh.ok()) {
sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image).toImageMsg();
pub.publish(msg);
ros::spinOnce();
loop_rate.sleep();
}
return 0;
}
7.接收原始图像
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/image_encodings.h>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>
#include<iostream>
#include <sensor_msgs/Image.h>
#include <ros/time.h>
using namespace std;
using namespace cv;
long int count_ =0000;//不能命名成count
int n=0;
void imageCallback(const sensor_msgs::ImageConstPtr& msg)
{
cv_bridge::CvImagePtr cv_ptr;
try //对错误异常进行捕获,检查数据的有效性
{
cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
char base_name[256];
if(n%7==0)
{
sprintf(base_name,"./120H/%04ld.jpg",count_++);
//std::sprintf(base_name,"./image/%ld.jpg", msg->header.stamp.toNSec());//获取ROS时间戳
cv::imwrite(base_name, cv_ptr->image);
ROS_INFO_STREAM("Saved image to " << base_name);
}
n++;
std::cout<<"n= "<<n<<std::endl;
}
catch(cv_bridge::Exception& e) //异常处理
{
ROS_ERROR("cv_bridge exception: %s", e.what());
return;
}
// // 获取ROS时间戳并生成文件名
// std::string filename =std::to_string(msg->header.stamp.toNSec()) + ".jpg";
// // 保存图像到文件
// cv::imwrite(filename, cv_ptr->image);
// ROS_INFO_STREAM("Saved image to " << filename);
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "msg2img2");
ros::NodeHandle nh_;
ros::Subscriber image_sub_ = nh_.subscribe("/tztek/camera0",1, imageCallback);///middle/pylon_camera_node/image_raw/compressed
ros::spin();
return 0;
}