Skip to content

Commit

Permalink
[upgrade] configurable tf_duration
Browse files Browse the repository at this point in the history
  • Loading branch information
HuaYuXiao committed Dec 24, 2024
1 parent 1b371bd commit 8dc5ad3
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 3 deletions.
2 changes: 2 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -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坐标系下
Expand Down
1 change: 1 addition & 0 deletions config/merge_pcl.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
9 changes: 6 additions & 3 deletions include/merge_pcl/merge_pcl.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<message_filters::Subscriber<sensor_msgs::PointCloud2>> 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;
};

Expand Down

0 comments on commit 8dc5ad3

Please sign in to comment.