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. | |
PointCloudConcatenateDataSynchronizer (int queue_size) | |
Empty constructor. | |
virtual | ~PointCloudConcatenateDataSynchronizer () |
Empty destructor. | |
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. | |
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. | |
Private Attributes | |
bool | approximate_sync_ |
True if we use an approximate time synchronizer versus an exact one (false by default). | |
std::vector< boost::shared_ptr < message_filters::Subscriber < PointCloud2 > > > | filters_ |
A vector of message filters. | |
int | maximum_queue_size_ |
The maximum number of messages that we can store in the queue. | |
message_filters::PassThrough < PointCloud2 > | nf_ |
Null passthrough filter, used for pushing empty elements in the synchronizer. | |
std::string | output_frame_ |
Output TF frame the concatenated points should be transformed to. | |
ros::NodeHandle | private_nh_ |
ROS local node handle. | |
ros::Publisher | pub_output_ |
The output PointCloud publisher. | |
tf::TransformListener | tf_ |
TF listener object. | |
boost::shared_ptr < message_filters::Synchronizer < sync_policies::ApproximateTime < PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2 > > > | ts_a_ |
Synchronizer. | |
boost::shared_ptr < message_filters::Synchronizer < sync_policies::ExactTime < PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2 > > > | ts_e_ |
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.
Empty constructor.
Definition at line 68 of file concatenate_data.h.
pcl_ros::PointCloudConcatenateDataSynchronizer::PointCloudConcatenateDataSynchronizer | ( | int | queue_size | ) | [inline] |
Empty constructor.
queue_size | the maximum queue size |
Definition at line 73 of file concatenate_data.h.
virtual pcl_ros::PointCloudConcatenateDataSynchronizer::~PointCloudConcatenateDataSynchronizer | ( | ) | [inline, virtual] |
Empty destructor.
Definition at line 76 of file concatenate_data.h.
void pcl_ros::PointCloudConcatenateDataSynchronizer::combineClouds | ( | const PointCloud2 & | in1, |
const PointCloud2 & | in2, | ||
PointCloud2 & | out | ||
) | [private] |
Definition at line 199 of file concatenate_data.cpp.
void pcl_ros::PointCloudConcatenateDataSynchronizer::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 | ||
) | [private] |
Input callback for 8 synchronized topics.
Definition at line 223 of file concatenate_data.cpp.
void pcl_ros::PointCloudConcatenateDataSynchronizer::input_callback | ( | const PointCloud2ConstPtr & | input | ) | [inline, private] |
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 117 of file concatenate_data.h.
void pcl_ros::PointCloudConcatenateDataSynchronizer::onInit | ( | ) | [virtual] |
Implements nodelet::Nodelet.
Definition at line 47 of file concatenate_data.cpp.
True if we use an approximate time synchronizer versus an exact one (false by default).
Definition at line 91 of file concatenate_data.h.
std::vector<boost::shared_ptr<message_filters::Subscriber<PointCloud2> > > pcl_ros::PointCloudConcatenateDataSynchronizer::filters_ [private] |
A vector of message filters.
Definition at line 94 of file concatenate_data.h.
The maximum number of messages that we can store in the queue.
Definition at line 88 of file concatenate_data.h.
message_filters::PassThrough<PointCloud2> pcl_ros::PointCloudConcatenateDataSynchronizer::nf_ [private] |
Null passthrough filter, used for pushing empty elements in the synchronizer.
Definition at line 104 of file concatenate_data.h.
std::string pcl_ros::PointCloudConcatenateDataSynchronizer::output_frame_ [private] |
Output TF frame the concatenated points should be transformed to.
Definition at line 97 of file concatenate_data.h.
ROS local node handle.
Reimplemented from nodelet::Nodelet.
Definition at line 82 of file concatenate_data.h.
The output PointCloud publisher.
Definition at line 85 of file concatenate_data.h.
TF listener object.
Definition at line 100 of file concatenate_data.h.
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2> > > pcl_ros::PointCloudConcatenateDataSynchronizer::ts_a_ [private] |
Synchronizer.
Definition at line 109 of file concatenate_data.h.
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2> > > pcl_ros::PointCloudConcatenateDataSynchronizer::ts_e_ [private] |
Definition at line 110 of file concatenate_data.h.