ROS进行bag包图片信息提取和图片发布以及订阅时,cmake文件内容。
cmake_minimum_required(VERSION 3.0.2)
project(bag_images)
find_package(catkin REQUIRED COMPONENTS
cv_bridge
roscpp
rospy
sensor_msgs
std_msgs
image_transport
)
find_package(OpenCV REQUIRED)
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES bag_images
# CATKIN_DEPENDS roscpp rospy std_msgs
# DEPENDS system_lib
)
include_directories(
include
${catkin_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
)
add_executable( ima_sub_node src/ima_sub.cpp)
add_executable( ima_pub_node src/ima_pub.cpp)
target_link_libraries(ima_sub_node
${catkin_LIBRARIES} ${OpenCV_LIBRARIES}
)
target_link_libraries(ima_pub_node
${catkin_LIBRARIES} ${OpenCV_LIBRARIES}
)
bag包的信息提取出图片
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
#include <opencv2/highgui/highgui.hpp>
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include "ros/time.h"
//接收bag包发布的信息,提取图片
static const char WINDOW[] = "Image window";
char base_name[256];
ros::Time time1;
double time2;
void imageCallback(const sensor_msgs::Image::ConstPtr &msg)
{
ROS_INFO_STREAM("Get Msg");
time1 = msg->header.stamp;
time2 = time1.toSec();
try {
sprintf(base_name,"/home/h/图像数据包/图像提取2/frame%f.jpg",time2);
cv::imwrite(base_name, cv_bridge::toCvShare(msg, "bgr8")->image);
cv::imshow(WINDOW, cv_bridge::toCvShare(msg, "bgr8")->image);
}
catch (cv_bridge::Exception &e) {
ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str());
}
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "ima_sub");
ros::NodeHandle nh;
cv::namedWindow(WINDOW);
// 在调用cv::startWindowThread();后,即使没有调用waitKey()函数,图片也依然实时刷新。大家知道,opencv的imshow()函数调用以后,并不立即刷新显示图片,
// 而是等到waitKey()后才会刷新图片显示,所以我猜测cv::startWindowThread();是新开一个线程实时刷新图片显示。
cv::startWindowThread();
image_transport::ImageTransport it(nh);
image_transport::Subscriber sub = it.subscribe("cam_raw_data1", 10, imageCallback);
ros::spin();
cv::destroyWindow(WINDOW);
}
图片的发布
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <ros/ros.h>
#include "std_msgs/String.h"
#include <sstream>
#include <sensor_msgs/image_encodings.h>
std::stringstream ss;
std_msgs::String msg;
int count = 1;
int main(int argc, char **argv)
{
ros::init(argc, argv, "image_pub");
// Convert OpenCV image to ROS message
ros::NodeHandle node;
image_transport::ImageTransport transport(node);
image_transport::Publisher image_pub;
image_pub = transport.advertise("cam_raw_data", 1000);
ros::Time time = ros::Time::now();
ros::Rate rate(10.0); //10HZ 一秒发布十次
while (ros::ok())
{
ss << "/home/h/图像数据包/图像提取1/frame" << count++ << ".jpg";
msg.data = ss.str();
// stringstream.str(std::string())的作用是清空stringstream内部的字符串内容,
// stringstream.clear()的作用是将该流中所有的状态位复位,将流的状态设置为有效。
ss.str(std::string());
ss.clear();
// Reading an image from the file
cv::Mat cv_image = cv::imread(msg.data.c_str());
if (cv_image.empty())
{
ROS_INFO("发送的消息:%s", msg.data.c_str());
ROS_FATAL("Read the picture failed!");
return -1;
}
else
{
ROS_INFO("发送的消息:%s", msg.data.c_str());
ROS_INFO_STREAM("Read the picture successful!");
}
cv_bridge::CvImage cvi;
cvi.header.stamp = time;
cvi.header.frame_id = "test_image";
cvi.encoding = "bgr8";
cvi.image = cv_image;
sensor_msgs::Image im;
cvi.toImageMsg(im);
ROS_INFO_STREAM("publish");
image_pub.publish(im);
rate.sleep();
}
return 0;
}
图片的订阅
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
#include <opencv2/highgui/highgui.hpp>
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include "ros/time.h"
//接收bag包发布的信息,提取图片
static const char WINDOW[] = "Image window";
char base_name[256];
ros::Time time1;
double time2;
int count=0;
void imageCallback(const sensor_msgs::Image::ConstPtr &msg)
{
ROS_INFO_STREAM("Get Msg");
time1 = msg->header.stamp;
time2 = time1.toSec();
try
{
sprintf(base_name, "/home/h/图像数据包/图像提取3/frame%d.jpg", ++count);
cv::imshow(WINDOW, cv_bridge::toCvShare(msg, "bgr8")->image);
cv::imwrite(base_name, cv_bridge::toCvShare(msg, "bgr8")->image);
}
catch (cv_bridge::Exception &e)
{
ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str());
}
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "image_sub");
ros::NodeHandle nh;
cv::namedWindow(WINDOW);
// 在调用cv::startWindowThread();后,即使没有调用waitKey()函数,图片也依然实时刷新。大家知道,opencv的imshow()函数调用以后,并不立即刷新显示图片,
// 而是等到waitKey()后才会刷新图片显示,所以我猜测cv::startWindowThread();是新开一个线程实时刷新图片显示。
cv::startWindowThread();
image_transport::ImageTransport it(nh);
image_transport::Subscriber sub = it.subscribe("cam_raw_data", 1000, imageCallback);
ros::spin();
cv::destroyWindow(WINDOW);
}