利用message_filters进行同步操作,然后在一个回调函数中显示和处理两种图像.
对齐传感信息时间戳有两种方式,一种是时间戳完全对齐 ExactTime Policy ,另一种是时间戳相近 ApproximateTime Policy ,前者更为严格.
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include<opencv2/core/core.hpp>
#include<opencv2/highgui/highgui.hpp>
#include<opencv2/imgproc/imgproc.hpp>
#include "sensor_msgs/image_encodings.h"
#include <cv_bridge/cv_bridge.h>
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/exact_time.h>
#include <message_filters/sync_policies/approximate_time.h>//相近对齐
#include <message_filters/time_synchronizer.h>
#include"std_msgs/UInt16MultiArray.h"
#include <iostream>
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
using namespace cv;
using namespace std;
using namespace sensor_msgs;
using namespace message_filters;
class mySynchronizer{
public:
mySynchronizer();
~mySynchronizer(){
};
void callback(const sensor_msgs::ImageConstPtr &RGB_image, const sensor_msgs::ImageConstPtr &depth_image);
};
void mySynchronizer::callback(const sensor_msgs::ImageConstPtr &RGB_image,const sensor_msgs::ImageConstPtr &depth_image){
try
{
cv_bridge::CvImagePtr image_ptr = cv_bridge::toCvCopy(RGB_image, sensor_msgs::image_encodings::BGR8);
cv::Mat RGB_image= image_ptr->image;
cv_bridge::CvImagePtr image_ptr1 = cv_bridge::toCvCopy(depth_image, sensor_msgs::image_encodings::BGR8);
cv::Mat depth_image= image_ptr1->image;
cv::imshow("rgb_camera",RGB_image);
cv::imshow("depth_camera",depth_image);
cv::waitKey(10);
}
catch(cv_bridge::Exception &e)
{
ROS_ERROR("cv_bridge Exception %s",e.what());
}
}
mySynchronizer::mySynchronizer()
{
ros::NodeHandle nh;
message_filters::Subscriber<sensor_msgs::Image> image_sub(nh, "/stereo_camera/RGB", 1);
message_filters::Subscriber<sensor_msgs::Image> render_sub(nh, "/stereo_camera/render", 1);
typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, sensor_msgs::Image> MySyncPolicy;
message_filters::Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), image_sub, render_sub);
sync.registerCallback(boost::bind(&mySynchronizer::callback, this, _1, _2));
ros::spin();
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "msg_synchronizer");
mySynchronizer wode;
return 0;
}