联合标定三维雷达和IMU,第一步要先对齐两种传感信息的时间戳。

ros官网提供了message_filters用于对齐多种传感信息的时间戳。

http://wiki.ros.org/message_filters#Time_Synchronizer

注意,对齐传感信息时间戳有两种方式,一种是时间戳完全对齐 ExactTime Policy ,另一种是时间戳相近

ApproximateTime Policy ,前者更为严格。

msg_syn.h

#ifndef CLIMBING_ROBOT_GT_MAP_
#define CLIMBING_ROBOT_GT_MAP_ #include <string> #include <ros/ros.h>
#include <rosbag/bag.h>
#include <sensor_msgs/PointCloud2.h>
#include <geometry_msgs/PoseStamped.h> #include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h> namespace climbing_robot
{ class MsgSynchronizer{
public:
MsgSynchronizer(ros::NodeHandle node);
~MsgSynchronizer(){}; void callback(const sensor_msgs::PointCloud2::ConstPtr& ori_pointcloud, const geometry_msgs::PoseStamped::ConstPtr& ori_pose); inline void CloseBag()
{
msg_syn_bag.close();
} private:
// ros::Publisher pubVelodyne;
// ros::Publisher pubImu;
std::string syn_bag_path;
rosbag::Bag msg_syn_bag;
}; }//namespace climbing_robot #endif// CLIMBING_ROBOT_GT_MAP_

msg_syn.cpp

#include "msg_syn.h"

#include <iostream>

namespace climbing_robot
{ MsgSynchronizer::MsgSynchronizer(ros::NodeHandle node)
{
// pubVelodyne = nh.advertise<sensor_msgs::PointCloud2>("/Syn/imu/data", 1); message_filters::Subscriber<geometry_msgs::PoseStamped> pose_sub(node, "/vrpn_client_node/RigidBody/pose", );
message_filters::Subscriber<sensor_msgs::PointCloud2> velodyne_sub(node, "/velodyne_points", ); typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, geometry_msgs::PoseStamped> approximate_policy;
message_filters::Synchronizer<approximate_policy> sync(approximate_policy(), velodyne_sub, pose_sub);
sync.registerCallback(boost::bind(&MsgSynchronizer::callback, this, _1, _2)); node.getParam("msg_syn_bag_path", syn_bag_path);
msg_syn_bag.open(syn_bag_path, rosbag::bagmode::Write); ros::spin();
} void MsgSynchronizer::callback(const sensor_msgs::PointCloud2::ConstPtr& ori_pointcloud, const geometry_msgs::PoseStamped::ConstPtr& ori_pose)
{
ROS_INFO("pointcloud stamp value is: %f", ori_pointcloud->header.stamp.toSec());
ROS_INFO("pose stamp value is: %f", ori_pose->header.stamp.toSec()); // ros::Time timestamp = ori_pointcloud.header.stamp;
msg_syn_bag.write("/velodyne_points", ori_pointcloud->header.stamp, *ori_pointcloud);
msg_syn_bag.write("/vrpn_client_node/RigidBody/pose", ori_pointcloud->header.stamp, *ori_pose); // pubVelodyne.publish(syn_pointcloud);
} }//namespace climbing_robot

main.cpp

#include "msg_syn.h"

int main(int argc, char** argv)
{
ros::init(argc, argv, "msg_synchronizer");
ros::NodeHandle node("~");
ROS_INFO("\033[1;32m---->\033[0m Sync msgs node Started."); climbing_robot::MsgSynchronizer synchronizer(node); // ros::spin(); synchronizer.CloseBag(); return ;
}

非常注意2点:

A

sync.registerCallback(boost::bind(&mySynchronizer::callback, this, _1, _2));

由于callback函数是类内函数,所以要使用类内成员函数的写法;

加上this关键字;

参考:https://blog.csdn.net/Felaim/article/details/78212738#commentBox

B

ros::spin();  要放在订阅函数之后。如果放在主函数中,由于作用域的原因,会出现无法订阅/topic的错误。

参考:https://www.cnblogs.com/liu-fa/p/5925381.html

<ROS> message_filters 对齐多种传感器数据的时间戳的更多相关文章

  1. [ROS]一些传感器数据读取融合问题的思考

    思考问题: 1. 如何实现传感器数据的融合,或者说时间同步? 比如里程计读数和雷达数据融合? void SlamGMapping::startLiveSlam() { entropy_publishe ...

  2. 【AllJoyn专题】基于AllJoyn和Yeelink的传感器数据上传与指令下行的研究

    接触高通物联网框架AllJoyn不太久,但确是被深深地吸引了.在我看来,促进我深入学习的原因有三点:一.AllJoyn开源,对开源的软硬件总会有种莫名的喜爱,虽然或许不会都深入下去:二.顺应潮流,物联 ...

  3. python多种格式数据加载、处理与存储

    多种格式数据加载.处理与存储 实际的场景中,我们会在不同的地方遇到各种不同的数据格式(比如大家熟悉的csv与txt,比如网页HTML格式,比如XML格式),我们来一起看看python如何和这些格式的数 ...

  4. 基于uFUN开发板的心率计(一)DMA方式获取传感器数据

    前言 从3月8号收到板子,到今天算起来,uFUN到手也有两周的时间了,最近利用下班后的时间,做了个心率计,从单片机程序到上位机开发,到现在为止完成的差不多了,实现很简单,uFUN开发板外加一个Puls ...

  5. 云中树莓派(2):将传感器数据上传到 AWS IoT 并利用Kibana进行展示

    云中树莓派(1):环境准备 云中树莓派(2):将传感器数据上传到AWS IoT 并利用Kibana进行展示 1. 传感器安装及配置 1.1 DHT22 安装 DHT22 是一款温度与湿度传感器,它有3 ...

  6. C#关于时间(获取特定格式的时间及多种方式获取当前时间戳)以及10位和13位时间戳转为特定格式

    C#关于时间(获取特定格式的时间及多种方式获取当前时间戳)以及10位和13位时间戳转为特定格式 置顶 2018年03月06日 19:16:51 黎筱曦 阅读数:19098 标签: C#时间 更多 个人 ...

  7. STC15系列通用-STC15F2K60S2/STCW4K32S4读取DHT11温湿度传感器数据串口输出代码实例工程免费下载

    //为了方便大家调试,另附程序工程共大家下载,下载地址:https://www.90pan.com/b1908750 ​ //************************** //程序说明:stc ...

  8. [转]ROS中使用message_filters进行多传感器消息同步

    转:http://www.rosclub.cn/post-1030.html 最近实验室老师在做一个多传感器数据采集实验,涉及到了消息同步.所以就学习了ROS官网下的消息同步工具message_fil ...

  9. ros学习笔记 - 深度传感器转换成激光数据(hector_slam)

    前提条件:1,确保读者已经安装了kinect或者其他深度摄像头的驱动,如果未安装,可以直接在网盘下载:http://pan.baidu.com/s/1hqHB10w 提取密码:wrmn 利用深度相机仿 ...

随机推荐

  1. OpenGL中VA,VAO,VBO和EBO的区别

    1,顶点数组(Vertex Array) VA,顶点数组也是收集好所有的顶点,一次性发送给GPU.不过数据不是存储于GPU中的,绘制速度上没有显示列表快,优点是可以修改数据. 4.VBO(Vertex ...

  2. linux实时时钟相关函数

    time 功能:获取1970年1月1日00:00:00到现在的秒数 原型:time_t time(time_t *t); 参数: t:获取到的秒数 返回:获取到的秒数 说明:在time.h中定义了ti ...

  3. 如何优雅的关闭Golang Channel?

    Channel关闭原则 不要在消费端关闭channel,不要在有多个并行的生产者时对channel执行关闭操作. 也就是说应该只在[唯一的或者最后唯一剩下]的生产者协程中关闭channel,来通知消费 ...

  4. 测试工具安装(JMeter,Postman)

    Jmeter的安装依赖Java环境,所以必须安装JDK(1.8版本以上的),与JRE集成安装.记得配置环境变量.(5H) Postman,我安装的windows64的,直接在官网下载就好了.不需要在c ...

  5. vue中 左侧导航条 多个toggleClass

    <ul> <li v-for='item in items' @click="showToggle(item)"> <i :class="{ ...

  6. powerdesigner 使用心得 comment、name

    一.表字段设计页面设置 注意:name列填写的是中文,这样方便在视图中显示,本人忘了所以现在写下来. 二.设置PowerDesigner模型视图中数据表显示列 1.Tools-Display Pref ...

  7. Linux 环境下安装RabbitMQ的步骤

    #下载erlangcd /usr/local/devwget wget http://erlang.org/download/otp_src_17.5.tar.gz # 解压tar -xzvf otp ...

  8. python从零开始 -- 第1篇之环境搭建

    事实上,网络上有很多相应的教程,本文无意做成文章的粘贴展示板,附上我认为的简易的安装详解: 安装 Python 环境(编程小白的第一本 Python 入门书),包含了python以及相关的IDE,图文 ...

  9. centos7下部署node应用程序

    一.安装node 二.安装nginx 三.使用express写一个简单的demo,并且使用pm2部署 四.错误 invalid PID number "" in "/ru ...

  10. DataBase——Mysql的DataHelper

    源帖 https://www.cnblogs.com/youuuu/archive/2011/06/16/2082730.html 保护原帖,尊重技术,致敬工匠! using System; usin ...