Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | List of all members
jsk_pcl_ros_utils::NormalConcatenater Class Reference

#include <normal_concatenater.h>

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

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

Detailed Description

Definition at line 87 of file normal_concatenater.h.

Member Typedef Documentation

◆ ASyncPolicy

Definition at line 123 of file normal_concatenater.h.

◆ SyncPolicy

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.

Constructor & Destructor Documentation

◆ ~NormalConcatenater()

jsk_pcl_ros_utils::NormalConcatenater::~NormalConcatenater ( )
virtual

Definition at line 123 of file normal_concatenater_nodelet.cpp.

Member Function Documentation

◆ concatenate()

void jsk_pcl_ros_utils::NormalConcatenater::concatenate ( const sensor_msgs::PointCloud2::ConstPtr &  xyz,
const sensor_msgs::PointCloud2::ConstPtr &  normal 
)
protectedvirtual

Definition at line 73 of file normal_concatenater_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros_utils::NormalConcatenater::onInit ( )
privatevirtual

Definition at line 111 of file normal_concatenater_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros_utils::NormalConcatenater::subscribe ( )
protectedvirtual

Definition at line 135 of file normal_concatenater_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros_utils::NormalConcatenater::unsubscribe ( )
protectedvirtual

Definition at line 151 of file normal_concatenater_nodelet.cpp.

Member Data Documentation

◆ async_

boost::shared_ptr<message_filters::Synchronizer<ASyncPolicy> > jsk_pcl_ros_utils::NormalConcatenater::async_
protected

Definition at line 129 of file normal_concatenater.h.

◆ maximum_queue_size_

int jsk_pcl_ros_utils::NormalConcatenater::maximum_queue_size_
protected

Definition at line 127 of file normal_concatenater.h.

◆ pub_

ros::Publisher jsk_pcl_ros_utils::NormalConcatenater::pub_
protected

Definition at line 126 of file normal_concatenater.h.

◆ sub_normal_

message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros_utils::NormalConcatenater::sub_normal_
protected

Definition at line 131 of file normal_concatenater.h.

◆ sub_xyz_

message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros_utils::NormalConcatenater::sub_xyz_
protected

Definition at line 130 of file normal_concatenater.h.

◆ sync_

boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros_utils::NormalConcatenater::sync_
protected

Definition at line 128 of file normal_concatenater.h.

◆ use_async_

bool jsk_pcl_ros_utils::NormalConcatenater::use_async_
protected

Definition at line 135 of file normal_concatenater.h.


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


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:44