ros 同步两个消息

由于最近经常用到 相机和激光雷达来采集数据,因此在这里就需要对两个不同的消息进行同步处理。

由于是之前录好的包,因此需要在播放的时候  ,需要进行 设置一个参数。

 

rosparam set use_sim_time true

 

降低播放速度:

 

 rosbag play -r 0.1  stereo_camera.bag --clock  --pause 

 

 

 

此外由于我们读取的图像时 经过压缩的 ,如果直接接收 compressed 的数据的话,会出现一些问题。假设我们录包里面的消息是

 

 

 

 

/camera_17023549/pg_17023549/image_raw/compressed

 

 

 

 

 

可以先进行数据的TOPIC 转发一下

 

rosrun image_transport republish compressed in:=/camera_17023549/pg_17023549/image_raw raw out:=/camera_17023549/pg_17023549/image_raw


这样的话我们只需要在 cpp 里面接收消息:

 

 

/camera_17023549/pg_17023549/image_raw

 

 


就可以了,其次的话还有另外一种方法,在 ros wiki 上面进行介绍的

rosparam set /compressed_listener/image_transport compressed

 

rosrun beginner_tutorials compress __name:=compressed 

 

 

 

此外还有小的技巧比如怎么看一个消息的 fixframe

 

 rostopic echo /horizontal_hokuyo/scan | grep frame_id


当你录得包里面含有很多消息,你只想拿出来其中的一部分时可以这么做

 

 

rosbag filter sensor_data.bag only-tf.bag "topic == '/camera_17023549/pg_17023549/image_raw/compressed' or topic == '/left_velodyne/velodyne_points'"

在这里只保留俩消息。
 

 

 

/camera_17023549/pg_17023549/image_raw/compressed 和 /left_velodyne/velodyne_points

 

 

 

 

 

好了言归正传 我们在这里开始进行同步两个消息

 

 

 

 

 

#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 <beginner_tutorials/myNum.h>

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

// global variable

typedef message_filters::sync_policies::ApproximateTime<Image, Image> sync_policy_classification;

void callback(const ImageConstPtr& cam_info, const ImageConstPtr& pos)
{

    cout << "I should record the pose: " << endl;
}



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

    ros::NodeHandle nh;

    message_filters::Subscriber<Image> info_sub(nh, "/camera_17082012/pg_17082012/image_raw", 1);
    message_filters::Subscriber<Image> pose_sub(nh, "/camera_17082034/pg_17082034/image_raw", 1);
    message_filters::Synchronizer<sync_policy_classification> sync(sync_policy_classification(100), info_sub, pose_sub);
    //TimeSynchronizer<CameraInfo, PoseStamped> sync(info_sub, pose_sub, 10);
    sync.registerCallback(boost::bind(&callback, _1, _2));

    ros::spin();

    return 0;
}

 

 

 

 

 

  • 0
    点赞
  • 6
    收藏
    觉得还不错? 一键收藏
  • 4
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 4
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值