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_fields.h>

| Public Types | |
| typedef sensor_msgs::PointCloud2 | PointCloud | 
| typedef PointCloud::ConstPtr | PointCloudConstPtr | 
| typedef PointCloud::Ptr | PointCloudPtr | 
| Public Member Functions | |
| void | input_callback (const PointCloudConstPtr &cloud) | 
| void | onInit () | 
| PointCloudConcatenateFieldsSynchronizer () | |
| Empty constructor.  More... | |
| PointCloudConcatenateFieldsSynchronizer (int queue_size) | |
| Empty constructor.  More... | |
| void | subscribe () | 
| void | unsubscribe () | 
| virtual | ~PointCloudConcatenateFieldsSynchronizer () | 
| 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 Attributes | |
| int | input_messages_ | 
| The number of input messages that we expect on the input topic.  More... | |
| int | maximum_queue_size_ | 
| The maximum number of messages that we can store in the queue.  More... | |
| double | maximum_seconds_ | 
| The maximum number of seconds to wait until we drop the synchronization.  More... | |
| ros::Publisher | pub_output_ | 
| The output PointCloud publisher.  More... | |
| std::map< ros::Time, std::vector< PointCloudConstPtr > > | queue_ | 
| A queue for messages.  More... | |
| ros::Subscriber | sub_input_ | 
| The input PointCloud subscriber.  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 53 of file concatenate_fields.h.
| typedef sensor_msgs::PointCloud2 pcl_ros::PointCloudConcatenateFieldsSynchronizer::PointCloud | 
Definition at line 56 of file concatenate_fields.h.
| typedef PointCloud::ConstPtr pcl_ros::PointCloudConcatenateFieldsSynchronizer::PointCloudConstPtr | 
Definition at line 58 of file concatenate_fields.h.
| typedef PointCloud::Ptr pcl_ros::PointCloudConcatenateFieldsSynchronizer::PointCloudPtr | 
Definition at line 57 of file concatenate_fields.h.
| 
 | inline | 
Empty constructor.
Definition at line 61 of file concatenate_fields.h.
| 
 | inline | 
Empty constructor.
| queue_size | the maximum queue size | 
Definition at line 66 of file concatenate_fields.h.
| 
 | inlinevirtual | 
Empty destructor.
Definition at line 69 of file concatenate_fields.h.
| void pcl_ros::PointCloudConcatenateFieldsSynchronizer::input_callback | ( | const PointCloudConstPtr & | cloud | ) | 
Definition at line 86 of file concatenate_fields.cpp.
| 
 | virtual | 
Reimplemented from nodelet_topic_tools::NodeletLazy.
Definition at line 47 of file concatenate_fields.cpp.
| 
 | virtual | 
Implements nodelet_topic_tools::NodeletLazy.
Definition at line 72 of file concatenate_fields.cpp.
| 
 | virtual | 
Implements nodelet_topic_tools::NodeletLazy.
Definition at line 79 of file concatenate_fields.cpp.
| 
 | private | 
The number of input messages that we expect on the input topic.
Definition at line 84 of file concatenate_fields.h.
| 
 | private | 
The maximum number of messages that we can store in the queue.
Definition at line 87 of file concatenate_fields.h.
| 
 | private | 
The maximum number of seconds to wait until we drop the synchronization.
Definition at line 90 of file concatenate_fields.h.
| 
 | private | 
The output PointCloud publisher.
Definition at line 81 of file concatenate_fields.h.
| 
 | private | 
A queue for messages.
Definition at line 93 of file concatenate_fields.h.
| 
 | private | 
The input PointCloud subscriber.
Definition at line 78 of file concatenate_fields.h.