From 8dc5ad30fdc6e3ea65361e0db1c110f7fc4771ad Mon Sep 17 00:00:00 2001 From: HuaYuXiao Date: Tue, 24 Dec 2024 11:34:28 +0800 Subject: [PATCH] [upgrade] configurable `tf_duration` --- CHANGELOG.md | 2 ++ config/merge_pcl.yaml | 1 + include/merge_pcl/merge_pcl.h | 9 ++++++--- 3 files changed, 9 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index a33a0d6..ace39f8 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -7,6 +7,8 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0 ## v2.1.4 - 2024-12-24 - [upgrade] set `queue_size` of `Subscriber` to `boost::thread::hardware_concurrency()` +- [upgrade] check if both `frame_id`s are the same +- [upgrade] configurable `tf_duration` ## v2.1.3: 2024-08-23 - [new feature] 转发lidar_frame坐标系下的点云到world坐标系下 diff --git a/config/merge_pcl.yaml b/config/merge_pcl.yaml index d5972b0..ef62cd2 100644 --- a/config/merge_pcl.yaml +++ b/config/merge_pcl.yaml @@ -3,6 +3,7 @@ pcl2_topic_0: /livox/lidar pcl2_frame_0: laser_livox pcl2_topic_1: /realsense/depth_camera/depth/points pcl2_frame_0: realsense_camera_frame +tf_duration: 0.1 pcl2_topic_out: /sensor/pcl2_out pcl2_frame_out: base_link timeout: 0.1 diff --git a/include/merge_pcl/merge_pcl.h b/include/merge_pcl/merge_pcl.h index e61cef0..b218d54 100644 --- a/include/merge_pcl/merge_pcl.h +++ b/include/merge_pcl/merge_pcl.h @@ -39,13 +39,16 @@ class PointCloudMerger { ros::NodeHandle nh; int pcl2_source_num; - std::string pcl2_topic_0, pcl2_topic_1, pcl2_topic_out; - std::string pcl2_frame_0, pcl2_frame_1, pcl2_frame_out; - + std::string pcl2_topic_0, pcl2_frame_0; + std::string pcl2_topic_1, pcl2_frame_1; shared_ptr> pcl2_sub_0, pcl2_sub_1; int queue_size; Synchronizer synchronizer_; + tf::TransformListener listener0, listener1; + double tf_duration; + + std::string pcl2_topic_out, pcl2_frame_out; ros::Publisher pcl2_pub; };