Skip to content

Commit

Permalink
[upgrade] store pointclouds with std::deque
Browse files Browse the repository at this point in the history
  • Loading branch information
HuaYuXiao committed Dec 24, 2024
1 parent 3b10f35 commit 6d726be
Showing 1 changed file with 3 additions and 2 deletions.
5 changes: 3 additions & 2 deletions include/merge_pcl/merge_pcl.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ class PointCloudMerger {

int pcl2_source_num;
size_t queue_size;
double timeout;

std::string pcl2_topic_0, pcl2_frame_0;
ros::Subscriber pcl2_sub_0;
Expand All @@ -46,8 +47,8 @@ class PointCloudMerger {
void pcl2Callback1(const sensor_msgs::PointCloud2ConstPtr& pcl2);

// Buffers to store point clouds
std::deque<sensor_msgs::PointCloud2ConstPtr> buffer_0;
std::deque<sensor_msgs::PointCloud2ConstPtr> buffer_1;
std::deque<pcl::PointCloud<pcl::PointXYZ>::Ptr> buffer_0;
std::deque<pcl::PointCloud<pcl::PointXYZ>::Ptr> buffer_1;
std::mutex buffer_mutex;

// Transform listeners
Expand Down

0 comments on commit 6d726be

Please sign in to comment.