PointCloudConcatenateFieldsSynchronizer is a special form of data synchronizer: it listens for a set of input PointCloud messages on the same topic, checks their timestamps, and concatenates their fields together into a single PointCloud output message. More...
#include <concatenate_data.h>

| Public Types | |
| typedef sensor_msgs::PointCloud2 | PointCloud2 | 
| typedef PointCloud2::ConstPtr | PointCloud2ConstPtr | 
| typedef PointCloud2::Ptr | PointCloud2Ptr | 
| Public Member Functions | |
| void | onInit () | 
| PointCloudConcatenateDataSynchronizer () | |
| Empty constructor.  More... | |
| PointCloudConcatenateDataSynchronizer (int queue_size) | |
| Empty constructor.  More... | |
| void | subscribe () | 
| void | unsubscribe () | 
| virtual | ~PointCloudConcatenateDataSynchronizer () | 
| Empty destructor.  More... | |
|  Public Member Functions inherited from nodelet_topic_tools::NodeletLazy | |
| NodeletLazy () | |
|  Public Member Functions inherited from nodelet::Nodelet | |
| void | init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL) | 
| Nodelet () | |
| virtual | ~Nodelet () | 
| Private Member Functions | |
| void | combineClouds (const PointCloud2 &in1, const PointCloud2 &in2, PointCloud2 &out) | 
| void | input (const PointCloud2::ConstPtr &in1, const PointCloud2::ConstPtr &in2, const PointCloud2::ConstPtr &in3, const PointCloud2::ConstPtr &in4, const PointCloud2::ConstPtr &in5, const PointCloud2::ConstPtr &in6, const PointCloud2::ConstPtr &in7, const PointCloud2::ConstPtr &in8) | 
| Input callback for 8 synchronized topics.  More... | |
| void | input_callback (const PointCloud2ConstPtr &input) | 
| Input point cloud callback. Because we want to use the same synchronizer object, we push back empty elements with the same timestamp.  More... | |
PointCloudConcatenateFieldsSynchronizer is a special form of data synchronizer: it listens for a set of input PointCloud messages on the same topic, checks their timestamps, and concatenates their fields together into a single PointCloud output message.
Definition at line 60 of file concatenate_data.h.
| typedef sensor_msgs::PointCloud2 pcl_ros::PointCloudConcatenateDataSynchronizer::PointCloud2 | 
Definition at line 63 of file concatenate_data.h.
| typedef PointCloud2::ConstPtr pcl_ros::PointCloudConcatenateDataSynchronizer::PointCloud2ConstPtr | 
Definition at line 65 of file concatenate_data.h.
| typedef PointCloud2::Ptr pcl_ros::PointCloudConcatenateDataSynchronizer::PointCloud2Ptr | 
Definition at line 64 of file concatenate_data.h.
| 
 | inline | 
Empty constructor.
Definition at line 68 of file concatenate_data.h.
| 
 | inline | 
Empty constructor.
| queue_size | the maximum queue size | 
Definition at line 73 of file concatenate_data.h.
| 
 | inlinevirtual | 
Empty destructor.
Definition at line 76 of file concatenate_data.h.
| 
 | private | 
Definition at line 206 of file concatenate_data.cpp.
| 
 | private | 
Input callback for 8 synchronized topics.
Definition at line 247 of file concatenate_data.cpp.
| 
 | inlineprivate | 
Input point cloud callback. Because we want to use the same synchronizer object, we push back empty elements with the same timestamp.
Definition at line 119 of file concatenate_data.h.
| 
 | virtual | 
Reimplemented from nodelet_topic_tools::NodeletLazy.
Definition at line 46 of file concatenate_data.cpp.
| 
 | virtual | 
Implements nodelet_topic_tools::NodeletLazy.
Definition at line 92 of file concatenate_data.cpp.
| 
 | virtual | 
Implements nodelet_topic_tools::NodeletLazy.
Definition at line 196 of file concatenate_data.cpp.
| 
 | private | 
True if we use an approximate time synchronizer versus an exact one (false by default).
Definition at line 90 of file concatenate_data.h.
| 
 | private | 
A vector of message filters.
Definition at line 93 of file concatenate_data.h.
| 
 | private | 
Input point cloud topics.
Definition at line 99 of file concatenate_data.h.
| 
 | private | 
The maximum number of messages that we can store in the queue.
Definition at line 87 of file concatenate_data.h.
| 
 | private | 
Null passthrough filter, used for pushing empty elements in the synchronizer.
Definition at line 106 of file concatenate_data.h.
| 
 | private | 
Output TF frame the concatenated points should be transformed to.
Definition at line 96 of file concatenate_data.h.
| 
 | private | 
The output PointCloud publisher.
Definition at line 84 of file concatenate_data.h.
| 
 | private | 
TF listener object.
Definition at line 102 of file concatenate_data.h.
| 
 | private | 
Synchronizer.
Definition at line 111 of file concatenate_data.h.
| 
 | private | 
Definition at line 112 of file concatenate_data.h.