Public Types | Protected Member Functions | Protected Attributes | Private Member Functions
jsk_pcl_ros::NormalConcatenater Class Reference

#include <normal_concatenater.h>

Inheritance diagram for jsk_pcl_ros::NormalConcatenater:
Inheritance graph
[legend]

List of all members.

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

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 ()

Detailed Description

Definition at line 55 of file normal_concatenater.h.


Member Typedef Documentation

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> jsk_pcl_ros::NormalConcatenater::ASyncPolicy

Definition at line 59 of file normal_concatenater.h.

typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> jsk_pcl_ros::NormalConcatenater::SyncPolicy

Definition at line 58 of file normal_concatenater.h.


Member Function Documentation

void jsk_pcl_ros::NormalConcatenater::concatenate ( const sensor_msgs::PointCloud2::ConstPtr &  xyz,
const sensor_msgs::PointCloud2::ConstPtr &  normal 
) [protected, virtual]

Definition at line 41 of file normal_concatenater_nodelet.cpp.

void jsk_pcl_ros::NormalConcatenater::onInit ( void  ) [private, virtual]

Reimplemented from jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 79 of file normal_concatenater_nodelet.cpp.

void jsk_pcl_ros::NormalConcatenater::subscribe ( ) [protected, virtual]
void jsk_pcl_ros::NormalConcatenater::unsubscribe ( ) [protected, virtual]

Member Data Documentation

Definition at line 64 of file normal_concatenater.h.

Definition at line 62 of file normal_concatenater.h.

Definition at line 61 of file normal_concatenater.h.

Definition at line 66 of file normal_concatenater.h.

Definition at line 65 of file normal_concatenater.h.

Definition at line 63 of file normal_concatenater.h.

Definition at line 70 of file normal_concatenater.h.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:49