organized_statistical_outlier_removal.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2021, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 
37 #ifndef JSK_PCL_ROS_ORGANIZED_STATISTICAL_OUTLIER_REMOVAL_H_
38 #define JSK_PCL_ROS_ORGANIZED_STATISTICAL_OUTLIER_REMOVAL_H_
39 
40 #include <pcl/pcl_base.h>
41 #include <pcl_ros/pcl_nodelet.h>
42 #include <jsk_topic_tools/diagnostic_nodelet.h>
43 #include <jsk_topic_tools/counter.h>
44 #include <dynamic_reconfigure/server.h>
48 
49 #include "sensor_msgs/PointCloud2.h"
50 #include "jsk_recognition_msgs/ClusterPointIndices.h"
51 
52 #include "jsk_pcl_ros/OrganizedStatisticalOutlierRemovalConfig.h"
53 
54 namespace jsk_pcl_ros
55 {
56  class OrganizedStatisticalOutlierRemoval: public jsk_topic_tools::DiagnosticNodelet
57  {
58  public:
59  typedef jsk_pcl_ros::OrganizedStatisticalOutlierRemovalConfig Config;
61  sensor_msgs::PointCloud2,
62  jsk_recognition_msgs::ClusterPointIndices > SyncPolicy;
64  sensor_msgs::PointCloud2,
65  jsk_recognition_msgs::ClusterPointIndices > ApproximateSyncPolicy;
67  protected:
69  // methods
71  virtual void onInit();
72 
73  virtual void subscribe();
74 
75  virtual void unsubscribe();
76 
77  virtual void configCallback (Config &config, uint32_t level);
78 
79  void filter(const pcl::PCLPointCloud2::Ptr pcl_cloud,
80  pcl::PointIndices::Ptr pcl_indices_filtered);
81  void filter(const pcl::PCLPointCloud2::Ptr pcl_cloud,
82  const pcl::PointIndices::Ptr pcl_indices,
83  pcl::PointIndices::Ptr pcl_indices_filtered);
84  std::vector<int> getFilteredIndices(const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
85  void filterCloud(const sensor_msgs::PointCloud2::ConstPtr& msg);
87  const sensor_msgs::PointCloud2::ConstPtr& msg,
88  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& cpi_msg);
89 
90 
92 
94  // ROS variables
101 
105 
107  // Diagnostics variables
109 
111  // Parameters
113  bool use_cpi_;
114  bool use_async_;
115  int queue_size_;
116  bool keep_organized_;
117  bool negative_;
118  double std_mul_;
119  int mean_k_;
120  private:
121 
122  };
123 }
124 
125 #endif
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::mutex_
boost::mutex mutex_
Definition: organized_statistical_outlier_removal.h:168
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::queue_size_
int queue_size_
Definition: organized_statistical_outlier_removal.h:179
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::filterCloudWithClusterPointIndices
void filterCloudWithClusterPointIndices(const sensor_msgs::PointCloud2::ConstPtr &msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &cpi_msg)
Definition: organized_statistical_outlier_removal_nodelet.cpp:317
ros::Publisher
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::unsubscribe
virtual void unsubscribe()
Definition: organized_statistical_outlier_removal_nodelet.cpp:128
boost::shared_ptr
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::subscribe
virtual void subscribe()
Definition: organized_statistical_outlier_removal_nodelet.cpp:99
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::ApproximateSyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > ApproximateSyncPolicy
Definition: organized_statistical_outlier_removal.h:129
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::onInit
virtual void onInit()
Definition: organized_statistical_outlier_removal_nodelet.cpp:83
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::use_cpi_
bool use_cpi_
Definition: organized_statistical_outlier_removal.h:177
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::sub_cpi_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_cpi_
Definition: organized_statistical_outlier_removal.h:162
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::keep_organized_
bool keep_organized_
Definition: organized_statistical_outlier_removal.h:180
time_synchronizer.h
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > SyncPolicy
Definition: organized_statistical_outlier_removal.h:126
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::pub_
ros::Publisher pub_
Definition: organized_statistical_outlier_removal.h:166
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::mean_k_
int mean_k_
Definition: organized_statistical_outlier_removal.h:183
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::std_mul_
double std_mul_
Definition: organized_statistical_outlier_removal.h:182
message_filters::Subscriber< sensor_msgs::PointCloud2 >
pcl_nodelet.h
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::updateDiagnostic
void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: organized_statistical_outlier_removal_nodelet.cpp:372
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: organized_statistical_outlier_removal_nodelet.cpp:141
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: organized_statistical_outlier_removal.h:163
subscriber.h
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::filterCloud
void filterCloud(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: organized_statistical_outlier_removal_nodelet.cpp:275
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::Config
jsk_pcl_ros::OrganizedStatisticalOutlierRemovalConfig Config
Definition: organized_statistical_outlier_removal.h:123
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::sub_
ros::Subscriber sub_
Definition: organized_statistical_outlier_removal.h:160
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::use_async_
bool use_async_
Definition: organized_statistical_outlier_removal.h:178
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: organized_statistical_outlier_removal.h:167
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::filter
void filter(const pcl::PCLPointCloud2::Ptr pcl_cloud, pcl::PointIndices::Ptr pcl_indices_filtered)
Definition: organized_statistical_outlier_removal_nodelet.cpp:155
synchronizer.h
diagnostic_updater::DiagnosticStatusWrapper
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::sub_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
Definition: organized_statistical_outlier_removal.h:161
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::negative_
bool negative_
Definition: organized_statistical_outlier_removal.h:181
message_filters::sync_policies::ExactTime
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::async_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
Definition: organized_statistical_outlier_removal.h:164
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::getFilteredIndices
std::vector< int > getFilteredIndices(const pcl::PointCloud< pcl::PointXYZ >::Ptr cloud)
Definition: organized_statistical_outlier_removal_nodelet.cpp:189
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
jsk_pcl_ros::OrganizedStatisticalOutlierRemoval::OrganizedStatisticalOutlierRemoval
OrganizedStatisticalOutlierRemoval()
Definition: organized_statistical_outlier_removal_nodelet.cpp:77
ros::Subscriber


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