$search

pcl_ros::PointCloudConcatenateFieldsSynchronizer Class Reference

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>

Inheritance diagram for pcl_ros::PointCloudConcatenateFieldsSynchronizer:
Inheritance graph
[legend]

List of all members.

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 (int queue_size)
 Empty constructor.
 PointCloudConcatenateFieldsSynchronizer ()
 Empty constructor.
virtual ~PointCloudConcatenateFieldsSynchronizer ()
 Empty destructor.

Private Attributes

int input_messages_
 The number of input messages that we expect on the input topic.
int maximum_queue_size_
 The maximum number of messages that we can store in the queue.
double maximum_seconds_
 The maximum number of seconds to wait until we drop the synchronization.
ros::NodeHandle private_nh_
 ROS local node handle.
ros::Publisher pub_output_
 The output PointCloud publisher.
std::map< ros::Time,
std::vector
< PointCloudConstPtr > > 
queue_
 A queue for messages.
ros::Subscriber sub_input_
 The input PointCloud subscriber.

Detailed Description

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.

Author:
Radu Bogdan Rusu

Definition at line 55 of file concatenate_fields.h.


Member Typedef Documentation

Definition at line 58 of file concatenate_fields.h.

Definition at line 60 of file concatenate_fields.h.

Definition at line 59 of file concatenate_fields.h.


Constructor & Destructor Documentation

pcl_ros::PointCloudConcatenateFieldsSynchronizer::PointCloudConcatenateFieldsSynchronizer (  )  [inline]

Empty constructor.

Definition at line 63 of file concatenate_fields.h.

pcl_ros::PointCloudConcatenateFieldsSynchronizer::PointCloudConcatenateFieldsSynchronizer ( int  queue_size  )  [inline]

Empty constructor.

Parameters:
queue_size the maximum queue size

Definition at line 68 of file concatenate_fields.h.

virtual pcl_ros::PointCloudConcatenateFieldsSynchronizer::~PointCloudConcatenateFieldsSynchronizer (  )  [inline, virtual]

Empty destructor.

Definition at line 71 of file concatenate_fields.h.


Member Function Documentation

void pcl_ros::PointCloudConcatenateFieldsSynchronizer::input_callback ( const PointCloudConstPtr cloud  ) 

Definition at line 69 of file concatenate_fields.cpp.

void pcl_ros::PointCloudConcatenateFieldsSynchronizer::onInit (  )  [virtual]
Author:
Radu Bogdan Rusu

Implements nodelet::Nodelet.

Definition at line 46 of file concatenate_fields.cpp.


Member Data Documentation

The number of input messages that we expect on the input topic.

Definition at line 87 of file concatenate_fields.h.

The maximum number of messages that we can store in the queue.

Definition at line 90 of file concatenate_fields.h.

The maximum number of seconds to wait until we drop the synchronization.

Definition at line 93 of file concatenate_fields.h.

ROS local node handle.

Reimplemented from nodelet::Nodelet.

Definition at line 78 of file concatenate_fields.h.

The output PointCloud publisher.

Definition at line 84 of file concatenate_fields.h.

A queue for messages.

Definition at line 96 of file concatenate_fields.h.

The input PointCloud subscriber.

Definition at line 81 of file concatenate_fields.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


pcl_ros
Author(s): Maintained by Radu Bogdan Rusu
autogenerated on Fri Mar 1 16:26:36 2013