ros 下面同步相机和IMU 两个topic

// This file is used for collecting data fromm imu and camera at the same time.
// One camera and one imu


#include <ros/ros.h>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/CameraInfo.h>
#include <geometry_msgs/PoseStamped.h>
#include <iostream>

#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 <sensor_msgs/Imu.h>

#include <rosbag/bag.h>


using namespace std;
using namespace sensor_msgs;
using namespace message_filters;
using namespace geometry_msgs;

// global variable
char command;
rosbag::Bag bag_record;

int  img_num=0;
char szName1[200] = {'\0'};
char szName2[200] = {'\0'};
double pose_array[7]={10,11,12,13,14,15,16};

typedef message_filters::sync_policies::ApproximateTime<Image,Imu> sync_policy_classification;
string img_topic = "/camera/image_mono";
string imu_topic = "/mu_data";


void callback(const ImageConstPtr& image,  const sensor_msgs::ImuConstPtr& imu_msg)
{
    std::cout<<"time gap is : "<<image->header.stamp.now() - imu_msg->header.stamp.now() <<endl;
    bag_record.write(img_topic,image->header.stamp.now(), image);
    bag_record.write(imu_topic, imu_msg->header.stamp.now(), imu_msg);

}



int main(int argc, char** argv)
{
    ros::init(argc, argv, "msg_filter_xuqw");

    ros::NodeHandle nh;
    bag_record.open("test.bag", rosbag::bagmode::Write);
    message_filters::Subscriber<Image> info_sub(nh, img_topic, 1);
    message_filters::Subscriber<Imu> imu_sub(nh, imu_topic, 1);

    message_filters::Synchronizer<sync_policy_classification> sync(sync_policy_classification(10), info_sub, imu_sub);
    sync.registerCallback(boost::bind(&callback, _1, _2));
    ros::spin();
    ros::shutdown();

    return 0;
}

 

  • 2
    点赞
  • 25
    收藏
    觉得还不错? 一键收藏
  • 5
    评论
评论 5
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值