#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include "ros/ros.h"
#include <iostream>
#include <message_filters/sync_policies/approximate_time.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/Image.h>
using namespace sensor_msgs;
using namespace message_filters;
void callback(const ImageConstPtr& image, const PointCloud2ConstPtr& pc_info) //回调中包含多个消息
{
//std::cout<<image->header<<pc_info->header<<std::endl;
std::cout<<1;
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "pc_image_tongbu");
ros::NodeHandle rs_lidar;
message_filters::Subscriber<Image> image_sub(rs_lidar,"/zed/zed_node/left/image_rect_color",10);
message_filters::Subscriber<PointCloud2> lidar_sub(rs_lidar,"/rslidar_points",10);
TimeSynchronizer<Image, PointCloud2> sync(image_sub, lidar_sub, 10); // 同步
sync.registerCallback(boost::bind(&callback, _1, _2));
ros::spin();
return 0;
}
参考:https://blog.csdn.net/ttomchy/article/details/82431320
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include "ros/ros.h"
#include <iostream>
#include <message_filters/sync_policies/approximate_time.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/Image.h>
using namespace sensor_msgs;
using namespace message_filters;
typedef message_filters::sync_policies::ApproximateTime<Image,PointCloud2> sync_policy_classification;
void callback(const ImageConstPtr& image, const PointCloud2ConstPtr& pc_info) //回调中包含多个消息
{
std::cout<<image->header<<pc_info->header<<std::endl;
// std::cout<<1;
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "pc_image_tongbu");
ros::NodeHandle rs_lidar;
message_filters::Subscriber<Image> image_sub(rs_lidar,"/zed/zed_node/left/image_rect_color",10);
message_filters::Subscriber<PointCloud2> lidar_sub(rs_lidar,"/rslidar_points",10);
message_filters::Synchronizer<sync_policy_classification> sync(sync_policy_classification(10), image_sub, lidar_sub);
sync.registerCallback(boost::bind(&callback, _1, _2));
ros::spin();
return 0;
}
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include "ros/ros.h"
#include <iostream>
#include <message_filters/sync_policies/approximate_time.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/Image.h>
#include <rosbag/bag.h>
using namespace sensor_msgs;
using namespace message_filters;
rosbag::Bag bag_record;
std::string img_topic="/zed/zed_node/left/image_rect_color";
std::string pc_topic="/rslidar_points";
typedef message_filters::sync_policies::ApproximateTime<Image,PointCloud2> sync_policy_classification;
void callback(const ImageConstPtr& image, const PointCloud2ConstPtr& pc_info) //回调中包含多个消息
{
std::cout<<"time gap is : "<<image->header.stamp.now() - pc_info->header.stamp.now() <<std::endl;
bag_record.write(img_topic,image->header.stamp.now(), image);
bag_record.write(pc_topic, pc_info->header.stamp.now(), pc_info);
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "pc_image_tongbu");
ros::NodeHandle rs_lidar;
bag_record.open("TEST.bag", rosbag::bagmode::Write);
message_filters::Subscriber<Image> image_sub(rs_lidar,img_topic,10);
message_filters::Subscriber<PointCloud2> lidar_sub(rs_lidar,pc_topic,10);
message_filters::Synchronizer<sync_policy_classification> sync(sync_policy_classification(10), image_sub, lidar_sub);
sync.registerCallback(boost::bind(&callback, _1, _2));
ros::spin();
return 0;
}
CMAKELISTS
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
image_transport
rosbag
)
还有一个参考博客如下 :https://blog.csdn.net/qq_36396941/article/details/105404232