#include <organized_statistical_outlier_removal.h>
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_ |
Definition at line 88 of file organized_statistical_outlier_removal.h.
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.
typedef jsk_pcl_ros::OrganizedStatisticalOutlierRemovalConfig jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::Config |
Definition at line 123 of file organized_statistical_outlier_removal.h.
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.
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::OrganizedStatisticalOutlierRemoval | ( | ) |
Definition at line 77 of file organized_statistical_outlier_removal_nodelet.cpp.
|
protectedvirtual |
Definition at line 141 of file organized_statistical_outlier_removal_nodelet.cpp.
|
protected |
Definition at line 164 of file organized_statistical_outlier_removal_nodelet.cpp.
|
protected |
Definition at line 155 of file organized_statistical_outlier_removal_nodelet.cpp.
|
protected |
Definition at line 275 of file organized_statistical_outlier_removal_nodelet.cpp.
|
protected |
Definition at line 317 of file organized_statistical_outlier_removal_nodelet.cpp.
|
protected |
Definition at line 189 of file organized_statistical_outlier_removal_nodelet.cpp.
|
protectedvirtual |
Definition at line 83 of file organized_statistical_outlier_removal_nodelet.cpp.
|
protectedvirtual |
Definition at line 99 of file organized_statistical_outlier_removal_nodelet.cpp.
|
protectedvirtual |
Definition at line 128 of file organized_statistical_outlier_removal_nodelet.cpp.
|
protected |
Definition at line 372 of file organized_statistical_outlier_removal_nodelet.cpp.
|
protected |
Definition at line 164 of file organized_statistical_outlier_removal.h.
|
protected |
Definition at line 180 of file organized_statistical_outlier_removal.h.
|
protected |
Definition at line 183 of file organized_statistical_outlier_removal.h.
|
protected |
Definition at line 168 of file organized_statistical_outlier_removal.h.
|
protected |
Definition at line 181 of file organized_statistical_outlier_removal.h.
|
protected |
Definition at line 166 of file organized_statistical_outlier_removal.h.
|
protected |
Definition at line 179 of file organized_statistical_outlier_removal.h.
|
protected |
Definition at line 167 of file organized_statistical_outlier_removal.h.
|
protected |
Definition at line 182 of file organized_statistical_outlier_removal.h.
|
protected |
Definition at line 160 of file organized_statistical_outlier_removal.h.
|
protected |
Definition at line 161 of file organized_statistical_outlier_removal.h.
|
protected |
Definition at line 162 of file organized_statistical_outlier_removal.h.
|
protected |
Definition at line 163 of file organized_statistical_outlier_removal.h.
|
protected |
Definition at line 178 of file organized_statistical_outlier_removal.h.
|
protected |
Definition at line 177 of file organized_statistical_outlier_removal.h.