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 jsk_pcl_ros::OrganizedStatisticalOutlierRemovalConfig Config
 
typedef pcl::PointXYZRGB PointT
 

Public Member Functions

 OrganizedStatisticalOutlierRemoval ()
 

Protected Member Functions

virtual void configCallback (Config &config, uint32_t level)
 
virtual void filter (const sensor_msgs::PointCloud2::ConstPtr &msg)
 
virtual void onInit ()
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 
virtual void updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)
 

Protected Attributes

bool keep_organized_
 
int mean_k_
 
boost::mutex mutex_
 
bool negative_
 
ros::Publisher pub_
 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
double std_mul_
 
ros::Subscriber sub_
 

Detailed Description

Definition at line 81 of file organized_statistical_outlier_removal.h.

Member Typedef Documentation

◆ Config

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

Definition at line 116 of file organized_statistical_outlier_removal.h.

◆ PointT

Definition at line 117 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()

void jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::filter ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
protectedvirtual

◆ 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)
protectedvirtual

Member Data Documentation

◆ keep_organized_

bool jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::keep_organized_
protected

Definition at line 151 of file organized_statistical_outlier_removal.h.

◆ mean_k_

int jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::mean_k_
protected

Definition at line 154 of file organized_statistical_outlier_removal.h.

◆ mutex_

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

Definition at line 142 of file organized_statistical_outlier_removal.h.

◆ negative_

bool jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::negative_
protected

Definition at line 152 of file organized_statistical_outlier_removal.h.

◆ pub_

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

Definition at line 140 of file organized_statistical_outlier_removal.h.

◆ srv_

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

Definition at line 141 of file organized_statistical_outlier_removal.h.

◆ std_mul_

double jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::std_mul_
protected

Definition at line 153 of file organized_statistical_outlier_removal.h.

◆ sub_

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

Definition at line 139 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 Tue Jan 7 2025 04:05:46