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

#include <organized_statistical_outlier_removal.h>

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

Public Types

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > ApproximateSyncPolicy
 
typedef jsk_pcl_ros::OrganizedStatisticalOutlierRemovalConfig Config
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > SyncPolicy
 

Public Member Functions

 OrganizedStatisticalOutlierRemoval ()
 

Protected Member Functions

virtual void configCallback (Config &config, uint32_t level)
 
void filter (const pcl::PCLPointCloud2::Ptr pcl_cloud, const pcl::PointIndices::Ptr pcl_indices, pcl::PointIndices::Ptr pcl_indices_filtered)
 
void filter (const pcl::PCLPointCloud2::Ptr pcl_cloud, pcl::PointIndices::Ptr pcl_indices_filtered)
 
void filterCloud (const sensor_msgs::PointCloud2::ConstPtr &msg)
 
void filterCloudWithClusterPointIndices (const sensor_msgs::PointCloud2::ConstPtr &msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &cpi_msg)
 
std::vector< int > getFilteredIndices (const pcl::PointCloud< pcl::PointXYZ >::Ptr cloud)
 
virtual void onInit ()
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 
void updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)
 

Protected Attributes

boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
 
bool keep_organized_
 
int mean_k_
 
boost::mutex mutex_
 
bool negative_
 
ros::Publisher pub_
 
int queue_size_
 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
double std_mul_
 
ros::Subscriber sub_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
 
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_cpi_
 
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
 
bool use_async_
 
bool use_cpi_
 

Detailed Description

Definition at line 88 of file organized_statistical_outlier_removal.h.

Member Typedef Documentation

◆ ApproximateSyncPolicy

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::ApproximateSyncPolicy

Definition at line 129 of file organized_statistical_outlier_removal.h.

◆ Config

typedef jsk_pcl_ros::OrganizedStatisticalOutlierRemovalConfig jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::Config

Definition at line 123 of file organized_statistical_outlier_removal.h.

◆ SyncPolicy

typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::SyncPolicy

Definition at line 126 of file organized_statistical_outlier_removal.h.

Constructor & Destructor Documentation

◆ OrganizedStatisticalOutlierRemoval()

jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::OrganizedStatisticalOutlierRemoval ( )

Member Function Documentation

◆ configCallback()

void jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

◆ filter() [1/2]

void jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::filter ( const pcl::PCLPointCloud2::Ptr  pcl_cloud,
const pcl::PointIndices::Ptr  pcl_indices,
pcl::PointIndices::Ptr  pcl_indices_filtered 
)
protected

◆ filter() [2/2]

void jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::filter ( const pcl::PCLPointCloud2::Ptr  pcl_cloud,
pcl::PointIndices::Ptr  pcl_indices_filtered 
)
protected

◆ filterCloud()

void jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::filterCloud ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
protected

◆ filterCloudWithClusterPointIndices()

void jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::filterCloudWithClusterPointIndices ( const sensor_msgs::PointCloud2::ConstPtr &  msg,
const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &  cpi_msg 
)
protected

◆ getFilteredIndices()

std::vector< int > jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::getFilteredIndices ( const pcl::PointCloud< pcl::PointXYZ >::Ptr  cloud)
protected

◆ onInit()

void jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::onInit ( )
protectedvirtual

◆ subscribe()

void jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::subscribe ( )
protectedvirtual

◆ unsubscribe()

void jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::unsubscribe ( )
protectedvirtual

◆ updateDiagnostic()

void jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::updateDiagnostic ( diagnostic_updater::DiagnosticStatusWrapper stat)
protected

Member Data Documentation

◆ async_

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

Definition at line 164 of file organized_statistical_outlier_removal.h.

◆ keep_organized_

bool jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::keep_organized_
protected

Definition at line 180 of file organized_statistical_outlier_removal.h.

◆ mean_k_

int jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::mean_k_
protected

Definition at line 183 of file organized_statistical_outlier_removal.h.

◆ mutex_

boost::mutex jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::mutex_
protected

Definition at line 168 of file organized_statistical_outlier_removal.h.

◆ negative_

bool jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::negative_
protected

Definition at line 181 of file organized_statistical_outlier_removal.h.

◆ pub_

ros::Publisher jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::pub_
protected

Definition at line 166 of file organized_statistical_outlier_removal.h.

◆ queue_size_

int jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::queue_size_
protected

Definition at line 179 of file organized_statistical_outlier_removal.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::srv_
protected

Definition at line 167 of file organized_statistical_outlier_removal.h.

◆ std_mul_

double jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::std_mul_
protected

Definition at line 182 of file organized_statistical_outlier_removal.h.

◆ sub_

ros::Subscriber jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::sub_
protected

Definition at line 160 of file organized_statistical_outlier_removal.h.

◆ sub_cloud_

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

Definition at line 161 of file organized_statistical_outlier_removal.h.

◆ sub_cpi_

message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::sub_cpi_
protected

Definition at line 162 of file organized_statistical_outlier_removal.h.

◆ sync_

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

Definition at line 163 of file organized_statistical_outlier_removal.h.

◆ use_async_

bool jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::use_async_
protected

Definition at line 178 of file organized_statistical_outlier_removal.h.

◆ use_cpi_

bool jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::use_cpi_
protected

Definition at line 177 of file organized_statistical_outlier_removal.h.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:12:13