Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros::ExtractIndices Class Reference

#include <extract_indices.h>

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

Public Types

typedef message_filters::sync_policies::ApproximateTime< PCLIndicesMsg, sensor_msgs::PointCloud2 > ApproximateSyncPolicy
 
typedef message_filters::sync_policies::ExactTime< PCLIndicesMsg, sensor_msgs::PointCloud2 > SyncPolicy
 

Public Member Functions

 ExtractIndices ()
 
virtual ~ExtractIndices ()
 

Protected Member Functions

virtual void convert (const PCLIndicesMsg::ConstPtr &indices_msg, const sensor_msgs::PointCloud2::ConstPtr &msg)
 
virtual void onInit ()
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 

Protected Attributes

bool approximate_sync_
 
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
 
bool keep_organized_
 
int max_queue_size_
 
bool negative_
 
ros::Publisher pub_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
 
message_filters::Subscriber< PCLIndicesMsgsub_indices_
 
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
 

Detailed Description

Definition at line 82 of file extract_indices.h.

Member Typedef Documentation

◆ ApproximateSyncPolicy

typedef message_filters::sync_policies::ApproximateTime< PCLIndicesMsg, sensor_msgs::PointCloud2 > jsk_pcl_ros::ExtractIndices::ApproximateSyncPolicy

Definition at line 122 of file extract_indices.h.

◆ SyncPolicy

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

Definition at line 119 of file extract_indices.h.

Constructor & Destructor Documentation

◆ ExtractIndices()

jsk_pcl_ros::ExtractIndices::ExtractIndices ( )
inline

Definition at line 124 of file extract_indices.h.

◆ ~ExtractIndices()

jsk_pcl_ros::ExtractIndices::~ExtractIndices ( )
virtual

Definition at line 61 of file extract_indices_nodelet.cpp.

Member Function Documentation

◆ convert()

void jsk_pcl_ros::ExtractIndices::convert ( const PCLIndicesMsg::ConstPtr &  indices_msg,
const sensor_msgs::PointCloud2::ConstPtr &  msg 
)
protectedvirtual

Definition at line 97 of file extract_indices_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros::ExtractIndices::onInit ( )
protectedvirtual

Definition at line 50 of file extract_indices_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros::ExtractIndices::subscribe ( )
protectedvirtual

Definition at line 73 of file extract_indices_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros::ExtractIndices::unsubscribe ( )
protectedvirtual

Definition at line 91 of file extract_indices_nodelet.cpp.

Member Data Documentation

◆ approximate_sync_

bool jsk_pcl_ros::ExtractIndices::approximate_sync_
protected

Definition at line 137 of file extract_indices.h.

◆ async_

boost::shared_ptr<message_filters::Synchronizer<ApproximateSyncPolicy> > jsk_pcl_ros::ExtractIndices::async_
protected

Definition at line 139 of file extract_indices.h.

◆ keep_organized_

bool jsk_pcl_ros::ExtractIndices::keep_organized_
protected

Definition at line 134 of file extract_indices.h.

◆ max_queue_size_

int jsk_pcl_ros::ExtractIndices::max_queue_size_
protected

Definition at line 136 of file extract_indices.h.

◆ negative_

bool jsk_pcl_ros::ExtractIndices::negative_
protected

Definition at line 135 of file extract_indices.h.

◆ pub_

ros::Publisher jsk_pcl_ros::ExtractIndices::pub_
protected

Definition at line 140 of file extract_indices.h.

◆ sub_cloud_

message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::ExtractIndices::sub_cloud_
protected

Definition at line 141 of file extract_indices.h.

◆ sub_indices_

message_filters::Subscriber<PCLIndicesMsg> jsk_pcl_ros::ExtractIndices::sub_indices_
protected

Definition at line 142 of file extract_indices.h.

◆ sync_

boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::ExtractIndices::sync_
protected

Definition at line 138 of file extract_indices.h.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:46