当前位置:网站首页>ROS 之订阅多个topic时间同步问题
ROS 之订阅多个topic时间同步问题
2022-07-31 05:16:00 【xp_fangfei】
message_filters的介绍:
message_filters是一个用于roscpp和rospy的实用程序库。 它集合了许多的常用的消息“过滤”算法。消息过滤器message_filters类似一个消息缓存,当消息到达消息过滤器的时候,可能并不会立即输出,而是在稍后的时间点里满足一定条件下输出。
举个例子,比如时间同步器,它接收来自多个源的不同类型的消息,并且仅当它们在具有相同时间戳的每个源上接收到消息时才输出它们,也就是起到了一个消息同步输出的效果。
Time Synchronizer 时间同步器:
C++ message_filters::TimeSynchronizer API docs
Python message_filters.TimeSynchronizer
TimeSynchronizer过滤器通过包含在其头中的时间戳来同步输入通道,并以单个回调的形式输出它们需要相同数量的通道。 C ++实现可以同步最多9个通道。
例子(C++):
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/CameraInfo.h>
using namespace sensor_msgs;
using namespace message_filters;
void callback(const ImageConstPtr& image, const CameraInfoConstPtr& cam_info)
{
// Solve all of perception here...
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "vision_node");
ros::NodeHandle nh;
message_filters::Subscriber<Image> image_sub(nh, "image", 1);
message_filters::Subscriber<CameraInfo> info_sub(nh, "camera_info", 1);
TimeSynchronizer<Image, CameraInfo> sync(image_sub, info_sub, 10);
sync.registerCallback(boost::bind(&callback, _1, _2));
ros::spin();
return 0;
}
Policy-Based Synchronizer 基于策略的同步器 :
Synchronizer filter同步过滤器通过包含在其头中的时间戳来同步输入通道,并以单个回调的形式输出它们需要相同数量的通道。 C ++实现可以同步最多9个通道。
Synchronizer过滤器在确定如何同步通道的策略上进行模板化。 目前有两个策略:ExactTime和ApproximateTime。
C++ Header: message_filters/synchronizer.h
例1(ExactTime):
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/exact_time.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/CameraInfo.h>
using namespace sensor_msgs;
using namespace message_filters;
void callback(const ImageConstPtr& image, const CameraInfoConstPtr& cam_info)
{
// Solve all of perception here...
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "vision_node");
ros::NodeHandle nh;
message_filters::Subscriber<Image> image_sub(nh, "image", 1);
message_filters::Subscriber<CameraInfo> info_sub(nh, "camera_info", 1);
typedef sync_policies::ExactTime<Image, CameraInfo> MySyncPolicy;
// ExactTime takes a queue size as its constructor argument, hence MySyncPolicy(10)
Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), image_sub, info_sub);
sync.registerCallback(boost::bind(&callback, _1, _2));
ros::spin();
return 0;
}
例2(ApproximateTime):
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <sensor_msgs/Image.h>
using namespace sensor_msgs;
using namespace message_filters;
void callback(const ImageConstPtr& image1, const ImageConstPtr& image2)
{
// Solve all of perception here...
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "vision_node");
ros::NodeHandle nh;
message_filters::Subscriber<Image> image1_sub(nh, "image1", 1);
message_filters::Subscriber<Image> image2_sub(nh, "image2", 1);
typedef sync_policies::ApproximateTime<Image, Image> MySyncPolicy;
// ApproximateTime takes a queue size as its constructor argument, hence MySyncPolicy(10)
Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), image1_sub, image2_sub);
sync.registerCallback(boost::bind(&callback, _1, _2));
ros::spin();
return 0;
}
注意:实现以上三种时间同步的前提是消息体中有包含时间戳的头:
std_msg/Header
uint32 seq //存储原始数据类型uint32
time stamp //存储ROS中的时间戳信息
string frame_id //用于表示和此数据关联的帧,在坐标系变化中可以理解为数据所在的坐标系名称
边栏推荐
- understand js operators
- 场效应管 | N-mos内部结构详解
- Access database query
- sql add default constraint
- RuntimeError: CUDA error: no kernel image is available for execution on the device问题记录
- QT VS中双击ui文件无法打开的问题
- 深度学习知识点杂谈
- quick-3.5 ActionTimeline的setLastFrameCallFunc调用会崩溃问题
- cocos2d-x-3.2图片灰化效果
- cocos2d-x implements cross-platform directory traversal
猜你喜欢
VS2017 connects to MYSQL
npm WARN config global `--global`, `--local` are deprecated. Use `--location solution
How MySQL - depots table?A look at will understand
pytorch学习笔记10——卷积神经网络详解及mnist数据集多分类任务应用
[Cloud native] Simple introduction and use of microservice Nacos
Notes on creating a new virtual machine in Hyper-V
MySql to create data tables
JS写一段代码,判断一个字符串中出现次数最多的字符串,并统计出现的次数JS
计算图像数据集均值和方差
人脸识别AdaFace学习笔记
随机推荐
如何修改数据库密码
[Cloud native] Simple introduction and use of microservice Nacos
C语言 | 获取字符串里逗号间隔的内容
The server time zone value ‘й‘ is unrecognized or represents more than one time zone
cv2.resize()是反的
活体检测CDCN学习笔记
自定dialog 布局没有居中解决方案
js中的全局作用域与函数作用域
Access database query
sql add default constraint
禅道安装及使用教程
对js的数组的理解
Numpy常用函数
VS connects to MYSQL through ODBC (1)
OpenCV中的图像数据格式CV_8U定义
configure:error no SDL library found
Why does read in bash need to cooperate with while to read the contents of /dev/stdin
CNN的一点理解
计算图像数据集均值和方差
SSH automatic reconnection script