Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
pcl_ros::PointCloudConcatenateDataSynchronizer 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_data.h>

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

Public Types

typedef sensor_msgs::PointCloud2 PointCloud2
 
typedef PointCloud2::ConstPtr PointCloud2ConstPtr
 
typedef PointCloud2::Ptr PointCloud2Ptr
 

Public Member Functions

void onInit ()
 
 PointCloudConcatenateDataSynchronizer ()
 Empty constructor. More...
 
 PointCloudConcatenateDataSynchronizer (int queue_size)
 Empty constructor. More...
 
void subscribe ()
 
void unsubscribe ()
 
virtual ~PointCloudConcatenateDataSynchronizer ()
 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 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. More...
 
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. More...
 

Private Attributes

bool approximate_sync_
 True if we use an approximate time synchronizer versus an exact one (false by default). More...
 
std::vector< boost::shared_ptr< message_filters::Subscriber< PointCloud2 > > > filters_
 A vector of message filters. More...
 
XmlRpc::XmlRpcValue input_topics_
 Input point cloud topics. More...
 
int maximum_queue_size_
 The maximum number of messages that we can store in the queue. More...
 
message_filters::PassThrough< PointCloud2nf_
 Null passthrough filter, used for pushing empty elements in the synchronizer. More...
 
std::string output_frame_
 Output TF frame the concatenated points should be transformed to. More...
 
ros::Publisher pub_output_
 The output PointCloud publisher. More...
 
tf::TransformListener tf_
 TF listener object. More...
 
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2 > > > ts_a_
 Synchronizer. More...
 
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2 > > > ts_e_
 

Additional Inherited Members

- Protected Member Functions inherited from nodelet_topic_tools::NodeletLazy
ros::Publisher advertise (ros::NodeHandle &nh, std::string topic, int queue_size, bool latch=false)
 
virtual void connectionCallback (const ros::SingleSubscriberPublisher &pub)
 
virtual void onInitPostProcess ()
 
virtual void warnNeverSubscribedCallback (const ros::WallTimerEvent &event)
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 
- Protected Attributes inherited from nodelet_topic_tools::NodeletLazy
boost::mutex connection_mutex_
 
ConnectionStatus connection_status_
 
bool ever_subscribed_
 
bool lazy_
 
boost::shared_ptr< ros::NodeHandlenh_
 
boost::shared_ptr< ros::NodeHandlepnh_
 
std::vector< ros::Publisherpublishers_
 
ros::WallTimer timer_ever_subscribed_
 
bool verbose_connection_
 

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 60 of file concatenate_data.h.

Member Typedef Documentation

Definition at line 63 of file concatenate_data.h.

Definition at line 65 of file concatenate_data.h.

Definition at line 64 of file concatenate_data.h.

Constructor & Destructor Documentation

pcl_ros::PointCloudConcatenateDataSynchronizer::PointCloudConcatenateDataSynchronizer ( )
inline

Empty constructor.

Definition at line 68 of file concatenate_data.h.

pcl_ros::PointCloudConcatenateDataSynchronizer::PointCloudConcatenateDataSynchronizer ( int  queue_size)
inline

Empty constructor.

Parameters
queue_sizethe maximum queue size

Definition at line 73 of file concatenate_data.h.

virtual pcl_ros::PointCloudConcatenateDataSynchronizer::~PointCloudConcatenateDataSynchronizer ( )
inlinevirtual

Empty destructor.

Definition at line 76 of file concatenate_data.h.

Member Function Documentation

void pcl_ros::PointCloudConcatenateDataSynchronizer::combineClouds ( const PointCloud2 in1,
const PointCloud2 in2,
PointCloud2 out 
)
private

Definition at line 207 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 232 of file concatenate_data.cpp.

void pcl_ros::PointCloudConcatenateDataSynchronizer::input_callback ( const PointCloud2ConstPtr input)
inlineprivate

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 119 of file concatenate_data.h.

void pcl_ros::PointCloudConcatenateDataSynchronizer::onInit ( )
virtual

Reimplemented from nodelet_topic_tools::NodeletLazy.

Definition at line 47 of file concatenate_data.cpp.

void pcl_ros::PointCloudConcatenateDataSynchronizer::subscribe ( )
virtual

Implements nodelet_topic_tools::NodeletLazy.

Definition at line 93 of file concatenate_data.cpp.

void pcl_ros::PointCloudConcatenateDataSynchronizer::unsubscribe ( )
virtual

Implements nodelet_topic_tools::NodeletLazy.

Definition at line 197 of file concatenate_data.cpp.

Member Data Documentation

bool pcl_ros::PointCloudConcatenateDataSynchronizer::approximate_sync_
private

True if we use an approximate time synchronizer versus an exact one (false by default).

Definition at line 90 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 93 of file concatenate_data.h.

XmlRpc::XmlRpcValue pcl_ros::PointCloudConcatenateDataSynchronizer::input_topics_
private

Input point cloud topics.

Definition at line 99 of file concatenate_data.h.

int pcl_ros::PointCloudConcatenateDataSynchronizer::maximum_queue_size_
private

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

Definition at line 87 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 106 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 96 of file concatenate_data.h.

ros::Publisher pcl_ros::PointCloudConcatenateDataSynchronizer::pub_output_
private

The output PointCloud publisher.

Definition at line 84 of file concatenate_data.h.

tf::TransformListener pcl_ros::PointCloudConcatenateDataSynchronizer::tf_
private

TF listener object.

Definition at line 102 of file concatenate_data.h.

Synchronizer.

Note
This will most likely be rewritten soon using the DynamicTimeSynchronizer.

Definition at line 111 of file concatenate_data.h.

Definition at line 112 of file concatenate_data.h.


The documentation for this class was generated from the following files:


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Mon Jun 10 2019 14:19:19