当前位置:网站首页>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 //用于表示和此数据关联的帧,在坐标系变化中可以理解为数据所在的坐标系名称
边栏推荐
猜你喜欢

jenkins +miniprogram-ci 一键上传微信小程序

The feign call fails, JSON parse error Illegal character ((CTRL-CHAR, code 31)) only regular white space (r

活体检测FaceBagNet阅读笔记

小米手机短信定位服务激活失败

cv2.imread()

npm WARN config global `--global`, `--local` are deprecated. Use `--location solution

禅道安装及使用教程

【解决问题】RuntimeError: The size of tensor a (80) must match the size of tensor b (56) at non-singleton

qt:cannot open C:\Users\XX\AppData\Local\Temp\main.obj.15576.16.jom for write

softmax函数详解
随机推荐
Gradle sync failed: Uninitialized object exists on backward branch 142
powershell statistics folder size
禅道安装及使用教程
configure:error no SDL library found
Access database query
SSH自动重连脚本
为数学而歌之伯努利家族
自定dialog 布局没有居中解决方案
mysql common commands
腾讯云GPU桌面服务器驱动安装
podspec自动化升级脚本
Multi-Modal Face Anti-Spoofing Based on Central Difference Networks学习笔记
场效应管 | N-mos内部结构详解
对js的数组的理解
quick-3.6源码修改纪录
quick-3.5 ActionTimeline的setLastFrameCallFunc调用会崩溃问题
VS connects to MYSQL through ODBC (1)
Flutter mixed development module dependencies
cocos2d-x-3.2 create project method
cocos2d-x-3.x 修改和纪录