Go to the documentation of this file.
   38 #ifndef PCL_IO_CONCATENATE_DATA_H_ 
   39 #define PCL_IO_CONCATENATE_DATA_H_ 
   93       std::vector<boost::shared_ptr<message_filters::Subscriber<PointCloud2> > > 
filters_;
 
  122         cloud.header.stamp = 
input->header.stamp;
 
  123         nf_.
add (boost::make_shared<PointCloud2> (cloud));
 
  127       void input (
const PointCloud2::ConstPtr &in1, 
const PointCloud2::ConstPtr &in2, 
 
  128                   const PointCloud2::ConstPtr &in3, 
const PointCloud2::ConstPtr &in4, 
 
  129                   const PointCloud2::ConstPtr &in5, 
const PointCloud2::ConstPtr &in6, 
 
  130                   const PointCloud2::ConstPtr &in7, 
const PointCloud2::ConstPtr &in8);
 
  136 #endif  //#ifndef PCL_ROS_IO_CONCATENATE_H_ 
  
PointCloudConcatenateDataSynchronizer(int queue_size)
Empty constructor.
int maximum_queue_size_
The maximum number of messages that we can store in the queue.
std::string output_frame_
Output TF frame the concatenated points should be transformed to.
XmlRpc::XmlRpcValue input_topics_
Input point cloud topics.
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2 > > > ts_a_
Synchronizer.
bool approximate_sync_
True if we use an approximate time synchronizer versus an exact one (false by default).
void input_callback(const PointCloud2ConstPtr &input)
Input point cloud callback. Because we want to use the same synchronizer object, we push back empty e...
sensor_msgs::PointCloud2 PointCloud2
message_filters::PassThrough< PointCloud2 > nf_
Null passthrough filter, used for pushing empty elements in the synchronizer.
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.
PointCloudConcatenateDataSynchronizer()
Empty constructor.
void combineClouds(const PointCloud2 &in1, const PointCloud2 &in2, PointCloud2 &out)
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2 > > > ts_e_
void add(const EventType &evt)
PointCloudConcatenateFieldsSynchronizer is a special form of data synchronizer: it listens for a set ...
ros::Publisher pub_output_
The output PointCloud publisher.
tf::TransformListener tf_
TF listener object.
virtual ~PointCloudConcatenateDataSynchronizer()
Empty destructor.
PointCloud2::Ptr PointCloud2Ptr
std::vector< boost::shared_ptr< message_filters::Subscriber< PointCloud2 > > > filters_
A vector of message filters.
PointCloud2::ConstPtr PointCloud2ConstPtr
pcl_ros
Author(s): Open Perception, Julius Kammerl 
, William Woodall 
autogenerated on Fri Jul 12 2024 02:54:40