【ROS工具学习】之message_filters:消息同步

2023-05-16

最近实验室老师在做一个多传感器数据采集实验,涉及到了消息同步。所以就学习了ROS官网下的消息同步工具message_filters。
http://wiki.ros.org/message_filters
消息同步有两种方式,暂且称之为松同步与紧同步,紧同步是精确的同步,松同步是粗略的同步。我使用的是C++下的松同步我的代码如下:

#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/LaserScan.h>
#include "image_transport/image_transport.h"
#include "sensor_msgs/CompressedImage.h"
#include "ros/ros.h"
#include "sensor_msgs/Imu.h"
#include "nav_msgs/Odometry.h"
#include "sensor_msgs/CameraInfo.h"
#include "rosbag/bag.h"
#include "ctime"
#include "time.h"
/*
ros::Publisher Velodyne_pub;
ros::Publisher Hokuyo_pub;
ros::Publisher Ominivision_pub;
ros::Publisher Kinect2color_pub;
ros::Publisher Kinect2depth_pub;
ros::Publisher Imu_pub;
ros::Publisher Odom_pub;
ros::Publisher Kinect2camera_info_pub;*/
rosbag::Bag bag_record;
using namespace std;
string int2string(int value)
{
    stringstream ss;
    ss<<value;
    return ss.str();
}

void callback(const sensor_msgs:: PointCloud2ConstPtr& point_cloud2,
              const sensor_msgs::LaserScan::ConstPtr& laser_scan,
              const sensor_msgs::CompressedImageConstPtr& ominivision_msg,
              const sensor_msgs::CompressedImageConstPtr& kinect2color_msg,
              const sensor_msgs::CompressedImageConstPtr&kinect2depth_msg,
              const sensor_msgs::ImuConstPtr& imu_msg,
              const nav_msgs::OdometryConstPtr& odom_msg)
{
    ROS_INFO("Enter Publish");

    bag_record.write("message_filter/velodyne_points",point_cloud2->header.stamp.now(),*point_cloud2);
    bag_record.write("message_filter/scan",laser_scan->header.stamp.now(),*laser_scan);
    bag_record.write("message_filter/camera/compressed",ominivision_msg->header.stamp.now(),*ominivision_msg);
    bag_record.write("message_filter/kinect2/qhd/image_color_rect/compressed",laser_scan->header.stamp.now(),*kinect2color_msg);
    bag_record.write("message_filter/kinect2/qhd/image_depth_rect/compressed",laser_scan->header.stamp.now(),*kinect2depth_msg);
    bag_record.write("message_filter/imu/data",imu_msg->header.stamp.now(),*imu_msg);
    bag_record.write("message_filter/odom",odom_msg->header.stamp.now(),*odom_msg);

}
int main(int argc, char** argv)
{
  ros::init(argc, argv, "message_filter_node");
  ros::Time::init();
  ros::NodeHandle nh;
  ROS_INFO("start message filter");
  time_t t=std::time(0);
  struct tm * now = std::localtime( & t );
  string file_name;
  //the name of bag file is better to be determined by the system time
  file_name=int2string(now->tm_year + 1900)+
          '-'+int2string(now->tm_mon + 1)+
          '-'+int2string(now->tm_mday)+
          '-'+int2string(now->tm_hour)+
          '-'+int2string(now->tm_min)+
          '-'+int2string(now->tm_sec)+
            ".bag";
  bag_record.open(file_name,rosbag::bagmode::Write);
  message_filters::Subscriber<sensor_msgs::PointCloud2> Velodyne_sub(nh, "/velodyne_points", 1);//订阅16线激光雷达Topic
  message_filters::Subscriber<sensor_msgs::LaserScan> Hokuyo_sub(nh,"/scan" , 1);//订阅平面激光雷达Topic
  message_filters::Subscriber<sensor_msgs::CompressedImage> ominivision_sub(nh,"/camera/image_raw/compressed" , 1);//订阅全向视觉Topic
  message_filters::Subscriber<sensor_msgs::CompressedImage> kinect2color_sub(nh,"/kinect2/qhd/image_color_rect/compressed" , 1);//订阅Kinect的Topic
  message_filters::Subscriber<sensor_msgs::CompressedImage> kinect2depth_sub(nh,"/kinect2/qhd/image_depth_rect/compressed" , 1);//订阅Kinect的Topic
  message_filters::Subscriber<sensor_msgs::Imu> imu_sub(nh,"/imu/data" , 1);//订阅imu的Topic
  message_filters::Subscriber<nav_msgs::Odometry> odom_sub(nh,"/odom" , 1);//订阅里程计的Topic

  typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2,
          sensor_msgs::LaserScan,
          sensor_msgs::CompressedImage,
          sensor_msgs::CompressedImage,
          sensor_msgs::CompressedImage,
          sensor_msgs::Imu,
          nav_msgs::Odometry> MySyncPolicy;
  // ApproximateTime takes a queue size as its constructor argument, hence MySyncPolicy(10)
  message_filters::Synchronizer<MySyncPolicy> sync(MySyncPolicy(20),
                                                   Velodyne_sub,
                                                   Hokuyo_sub,
                                                   ominivision_sub,
                                                   kinect2color_sub,
                                                   kinect2depth_sub,
                                                   imu_sub,
                                                   odom_sub);
  sync.registerCallback(boost::bind(&callback, _1, _2, _3, _4, _5, _6, _7));
  ros::spin();
  bag_record.close();
  return 0;
}

这个框架直接拿出来就能用,同步过后的message会自动进入callback函数,之前把它封装成类结果一直跑不通,因为其中有些句柄当作了局部变量,这一点需要注意。

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

【ROS工具学习】之message_filters:消息同步 的相关文章

随机推荐

  • 《JAVA并发编程实践JavaConcurrencyinPractice-中文-高清-带书签-完整版(Doug Lea)》

    免责声明 xff1a 全部内容都属于是段友分享 xff0c 我只是属于整理 写在前边 xff0c 个人觉得 弄一个积分下载 xff0c 就是在自掘坟墓 表面上看起来是可以为个人赚积分 xff0c 实际砍掉分享交流的一个途径 对我就是没有积分
  • 《Java核心技术 卷1 基础知识 原书第10版》

    免责声明 xff1a 全部内容都属于是段友分享 xff0c 我只是属于整理 写在前边 xff0c 个人觉得 弄一个积分下载 xff0c 就是在自掘坟墓 表面上看起来是可以为个人赚积分 xff0c 实际砍掉分享交流的一个途径 对我就是没有积分
  • 《高性能mysql第三版》

    免责声明 xff1a 全部内容都属于是段友分享 xff0c 我只是属于整理 写在前边 xff0c 个人觉得 弄一个积分下载 xff0c 就是在自掘坟墓 表面上看起来是可以为个人赚积分 xff0c 实际砍掉分享交流的一个途径 对我就是没有积分
  • idea中maven报错Cannot reconnect

    问题所在 xff1a Maven工程 错误处在pom文件 xff1a 最重要的是学会了怎样在Idea出现错误时 xff0c 发现导致错误的具体原因 xff0c 通过 Helper gt Show Log in Explorer xff0c
  • 用一份JAVA工程师的求职简历来说说求职简历怎么写

    这是一篇我比较想看到的简历指导的文章 但是我比较反对简历造假 我觉得会什么写什么把 可以先看看我的这篇文章 xff1a 刚实习结束 xff0c 就要做面试官 xff0c 谈谈我的想法 自己做过面试官以后 xff0c 自己也总结了一下 xff
  • LiveGBS/LiveNVR等实现安防监控视频Web无插件直播时如何叠加水印文字

    H5直播点播播放器 下载集成入口 xff1a https www liveqing com docs download LivePlayer html 使用说明 xff1a https www liveqing com docs manua
  • OpenMV4开发笔记3-串口通信

    OpenMV4引出了串口3和串口1 xff0c 首先以串口3的收发为例 span class token keyword import span time span class token keyword from span pyb spa
  • FreeRTOS与UCOSIII任务状态对比

    FreeRTOS任务状态 1 运行态 正在运行的任务 xff0c 正在使用处理器的任务 单核处理器中任何时候都有且只有一个任务处于运行态 2 就绪态 已经准备就绪 xff08 非阻塞或挂起 xff09 xff0c 可以立即运行但还没有运行的
  • 白话TCP/IP协议栈

    前言 最近在复习总结计算机基础知识 xff0c 包括操作系统 数据结构 计算机网络等程序员必备的知识 xff0c 这属于程序员的内功 把内功修炼好了 xff0c 外功只是一种形式 xff0c 如果你内功深厚 xff0c 那么无论是用龙抓手还
  • 飞机绕地球问题

    每个飞机只有一个油箱 xff0c 飞机之间可以相互加油 xff08 注意是相互 xff0c 没有加油机 xff09 xff0c 一箱油可以供一架飞机绕地球飞半圈 问 xff1a 为了使至少一架飞机绕地球一圈回到起飞 时候的飞机场 xff0c
  • 【ROS】Gazebo仿真平台安装及问题解决

    Gazebo安装 这里的ROS版本是Melodic xff0c 如果是其他版本的ROS可以修改下面命令的melodic为指定版本 sudo apt get install ros melodic gazebo ros pkgs ros me
  • 激光slam经典开源算法及论文整理

    开源算法 loamLeGO LOAMlio mappingLIO SAMCartographergmappinghector slam 考虑到有些朋友们的网络下载论文可能有问题 xff0c 把论文整理到百度网盘 xff0c 可自行下载 xf
  • Body系下空间平面如何转到World系下

    Body系下空间平面如何转到World系下 题目解法 题目 已知 传感器坐标系 xff08 Body系 xff09 下有一平面P方程为Ax 43 By 43 Cz 43 D 61 0 xff0c 简写为 n
  • cmake: symbol lookup error: cmake: undefined symbol: archive_write_add_filter_zstd 两种解决方法

    centOS8 x86 64 或 aarch64 系统下 yum或dnf 默认安装的 cmake 3 18 2 11 el8版本 xff0c 安装后无法使用 xff0c 出现 xff1a cmake symbol lookup error
  • ROS学习--轻松使用tf

    tf是ROS中建立坐标系 xff0c 并且使用各个坐标间转换关系的一个很好的工具 xff0c 对于非导航专业的同学 xff0c 常常苦恼与各种旋转矩阵的变换 xff0c 自己经常被搞的头大 xff0c 最近由于课题实验的需要 xff0c 尝
  • ROS 下navigation/robot_pose_ekf编译报错

    想要使用navigation下的robot pose ekf做IMU与视觉的融合于是找到了这个包 xff1a https github com ros planning navigation tree indigo devel 但是编译报错
  • 【学习日记】ROS下IMU使用困惑

    最近准备在机器人上测试使用IMU代替机器人的里程计 xff0c 以提高底层的控制周期 由于底层通信的原因 xff0c 使用里程计的话最多能到50HZ xff0c 因为我们的机器人对运动性能要求较高 xff0c 所以无法满足我们的要求 xff
  • ROS学习--如何结合launch文件使用参数服务器

    ROS xff08 Robot Operating System xff09 接触了将近两年了 xff0c 最常用的也就是发布话题与订阅话题 xff0c 前一段时间刚刚把Rviz与 tf搞明白一些 xff0c 都能够多掌握一些东西 xff0
  • 【ROS工具学习】之topic_tools/throttle,改变节点发布频率

    最近老师想做一个实验 xff0c 机器人上搭在Hokuyo单线激光雷达 xff0c Velodyne16线激光雷达 xff0c Kinect2 xff0c Bumblebee xb3等传感器 xff0c 这些传感器做一些实验 xff0c 因
  • 【ROS工具学习】之message_filters:消息同步

    最近实验室老师在做一个多传感器数据采集实验 xff0c 涉及到了消息同步 所以就学习了ROS官网下的消息同步工具message filters http wiki ros org message filters 消息同步有两种方式 xff0