#include <normal_concatenater.h>
Public Types | |
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | ASyncPolicy |
typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | SyncPolicy |
Public Member Functions | |
virtual | ~NormalConcatenater () |
Protected Member Functions | |
virtual void | concatenate (const sensor_msgs::PointCloud2::ConstPtr &xyz, const sensor_msgs::PointCloud2::ConstPtr &normal) |
virtual void | subscribe () |
virtual void | unsubscribe () |
Protected Attributes | |
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > | async_ |
int | maximum_queue_size_ |
ros::Publisher | pub_ |
message_filters::Subscriber< sensor_msgs::PointCloud2 > | sub_normal_ |
message_filters::Subscriber< sensor_msgs::PointCloud2 > | sub_xyz_ |
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > | sync_ |
bool | use_async_ |
Private Member Functions | |
virtual void | onInit () |
Definition at line 87 of file normal_concatenater.h.
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> jsk_pcl_ros_utils::NormalConcatenater::ASyncPolicy |
Definition at line 123 of file normal_concatenater.h.
typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> jsk_pcl_ros_utils::NormalConcatenater::SyncPolicy |
Definition at line 122 of file normal_concatenater.h.
|
virtual |
Definition at line 123 of file normal_concatenater_nodelet.cpp.
|
protectedvirtual |
Definition at line 73 of file normal_concatenater_nodelet.cpp.
|
privatevirtual |
Definition at line 111 of file normal_concatenater_nodelet.cpp.
|
protectedvirtual |
Definition at line 135 of file normal_concatenater_nodelet.cpp.
|
protectedvirtual |
Definition at line 151 of file normal_concatenater_nodelet.cpp.
|
protected |
Definition at line 129 of file normal_concatenater.h.
|
protected |
Definition at line 127 of file normal_concatenater.h.
|
protected |
Definition at line 126 of file normal_concatenater.h.
|
protected |
Definition at line 131 of file normal_concatenater.h.
|
protected |
Definition at line 130 of file normal_concatenater.h.
|
protected |
Definition at line 128 of file normal_concatenater.h.
|
protected |
Definition at line 135 of file normal_concatenater.h.