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. | |
PointCloudConcatenateFieldsSynchronizer (int queue_size) | |
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. |
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 57 of file concatenate_fields.h.
typedef sensor_msgs::PointCloud2 pcl_ros::PointCloudConcatenateFieldsSynchronizer::PointCloud |
Definition at line 60 of file concatenate_fields.h.
typedef PointCloud::ConstPtr pcl_ros::PointCloudConcatenateFieldsSynchronizer::PointCloudConstPtr |
Definition at line 62 of file concatenate_fields.h.
typedef PointCloud::Ptr pcl_ros::PointCloudConcatenateFieldsSynchronizer::PointCloudPtr |
Definition at line 61 of file concatenate_fields.h.
pcl_ros::PointCloudConcatenateFieldsSynchronizer::PointCloudConcatenateFieldsSynchronizer | ( | ) | [inline] |
Empty constructor.
Definition at line 65 of file concatenate_fields.h.
pcl_ros::PointCloudConcatenateFieldsSynchronizer::PointCloudConcatenateFieldsSynchronizer | ( | int | queue_size | ) | [inline] |
Empty constructor.
queue_size | the maximum queue size |
Definition at line 70 of file concatenate_fields.h.
virtual pcl_ros::PointCloudConcatenateFieldsSynchronizer::~PointCloudConcatenateFieldsSynchronizer | ( | ) | [inline, virtual] |
Empty destructor.
Definition at line 73 of file concatenate_fields.h.
void pcl_ros::PointCloudConcatenateFieldsSynchronizer::input_callback | ( | const PointCloudConstPtr & | cloud | ) |
Definition at line 71 of file concatenate_fields.cpp.
void pcl_ros::PointCloudConcatenateFieldsSynchronizer::onInit | ( | ) | [virtual] |
Implements nodelet::Nodelet.
Definition at line 48 of file concatenate_fields.cpp.
The number of input messages that we expect on the input topic.
Definition at line 89 of file concatenate_fields.h.
The maximum number of messages that we can store in the queue.
Definition at line 92 of file concatenate_fields.h.
double pcl_ros::PointCloudConcatenateFieldsSynchronizer::maximum_seconds_ [private] |
The maximum number of seconds to wait until we drop the synchronization.
Definition at line 95 of file concatenate_fields.h.
ROS local node handle.
Reimplemented from nodelet::Nodelet.
Definition at line 80 of file concatenate_fields.h.
The output PointCloud publisher.
Definition at line 86 of file concatenate_fields.h.
std::map<ros::Time, std::vector<PointCloudConstPtr> > pcl_ros::PointCloudConcatenateFieldsSynchronizer::queue_ [private] |
A queue for messages.
Definition at line 98 of file concatenate_fields.h.
The input PointCloud subscriber.
Definition at line 83 of file concatenate_fields.h.