cloud_filter.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement  (BSD License)
00003  *
00004  *  Point Cloud Library  (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2012-, Open Perception, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of the copyright holder(s) nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES  (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  */
00037 
00038 #ifndef PCL_APPS_OPTRONIC_VIEWER_CLOUD_FILTER_H_
00039 #define PCL_APPS_OPTRONIC_VIEWER_CLOUD_FILTER_H_
00040 
00041 #include <pcl/apps/optronic_viewer/qt.h>
00042 #include <boost/shared_ptr.hpp>
00043 #include <pcl/io/openni_grabber.h>
00044 
00045 #include <pcl/visualization/pcl_visualizer.h>
00046 
00047 #include <fz_api.h>
00048 
00049 #include <string>
00050 #include <vector>
00051 
00052 namespace pcl
00053 {
00054   namespace apps
00055   {
00056     namespace optronic_viewer
00057     {
00058       
00060 
00063       class CloudFilter
00064       {
00065       public:
00066         virtual ~CloudFilter () {}
00067 
00071         virtual void
00072         filter (
00073           pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud_in,
00074           pcl::PointCloud<pcl::PointXYZRGBA>::Ptr &cloud_out) = 0;
00075 
00077         virtual std::string
00078         getName ()
00079         {
00080           return name_;
00081         }
00082 
00084         virtual void
00085         setName (std::string & name)
00086         {
00087           name_ = name;
00088         }
00089 
00091         virtual QWizardPage *
00092         getParameterPage () = 0;
00093 
00094       protected:
00096         std::string name_;
00097       };
00098 
00100 
00101       class CloudFilterFactory
00102       {
00103       public:
00104         virtual ~CloudFilterFactory () {}
00105 
00107         virtual std::string
00108         getName ()
00109         {
00110           return filter_type_name_;
00111         }
00112 
00114         virtual CloudFilter*
00115         create () = 0;
00116 
00117       protected:
00119         CloudFilterFactory (std::string name)
00120           : filter_type_name_ (name)
00121         {}
00122 
00123       protected:
00125         std::string filter_type_name_;
00126       };
00127 
00129 
00140       template <class T, char const *name>
00141       class CloudFilterFactory2
00142         : public CloudFilterFactory
00143       {
00144       public:
00148         CloudFilterFactory2 () : CloudFilterFactory (name) {}
00149         virtual ~CloudFilterFactory2 () {}
00150 
00152         virtual CloudFilter*
00153         create ()
00154         {
00155           return (new T ());
00156         }
00157       };
00158 
00160 
00163       class VoxelGridCF
00164         : public CloudFilter
00165       {
00166       public:
00167         VoxelGridCF ();
00168         virtual ~VoxelGridCF ();
00169 
00170         virtual void
00171         filter (
00172           pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud_in,
00173           pcl::PointCloud<pcl::PointXYZRGBA>::Ptr &cloud_out);
00174 
00175         virtual QWizardPage *
00176         getParameterPage ()
00177         {
00178           return (filter_selection_page_);
00179         }
00180 
00181       protected:
00182         // filter parameters
00183         float voxel_grid_size_x_;
00184         float voxel_grid_size_y_;
00185         float voxel_grid_size_z_;
00186 
00187         QLabel * voxel_grid_size_x_label_;
00188         QLabel * voxel_grid_size_y_label_;
00189         QLabel * voxel_grid_size_z_label_;
00190         QLineEdit * voxel_grid_size_x_line_edit_;
00191         QLineEdit * voxel_grid_size_y_line_edit_;
00192         QLineEdit * voxel_grid_size_z_line_edit_;
00193         QVBoxLayout * main_layout_;
00194         QWizardPage * filter_selection_page_;
00195       };
00196 
00198 
00202       class PassThroughCF
00203         : public CloudFilter
00204       {
00205       public:
00206         PassThroughCF ();
00207         virtual ~PassThroughCF ();
00208 
00209         virtual void
00210         filter (
00211           pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud_in,
00212           pcl::PointCloud<pcl::PointXYZRGBA>::Ptr &cloud_out);
00213         
00214         virtual QWizardPage *
00215         getParameterPage ()
00216         {
00217           return (filter_selection_page_);
00218         }
00219 
00220       protected:
00221         std::string filter_field_name_;
00222         float filter_limits_min_;
00223         float filter_limits_max_;
00224 
00225         QLabel * filter_field_name_label_;
00226         QLabel * filter_limits_min_label_;
00227         QLabel * filter_limits_max_label_;
00228         QLineEdit * filter_field_name_line_edit_;
00229         QLineEdit * filter_limits_min_line_edit_;
00230         QLineEdit * filter_limits_max_line_edit_;
00231         QVBoxLayout * main_layout_;
00232         QWizardPage * filter_selection_page_;
00233       };
00234 
00236 
00240       class RadiusOutlierCF
00241         : public CloudFilter
00242       {
00243       public:
00244         RadiusOutlierCF ();
00245         virtual ~RadiusOutlierCF ();
00246 
00247         virtual void
00248         filter (
00249           pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud_in,
00250           pcl::PointCloud<pcl::PointXYZRGBA>::Ptr &cloud_out);
00251         
00252         virtual QWizardPage *
00253         getParameterPage ()
00254         {
00255           return (filter_selection_page_);
00256         }
00257 
00258       protected:
00259         float search_radius_;
00260         int min_neighbors_in_radius_;
00261 
00262         QLabel * search_radius_label_;
00263         QLabel * min_neighbors_in_radius_label_;
00264         QLineEdit * search_radius_line_edit_;
00265         QLineEdit * min_neighbors_in_radius_line_edit_;
00266         QVBoxLayout * main_layout_;
00267         QWizardPage * filter_selection_page_;
00268       };
00269 
00271 
00274       class FastBilateralCF
00275         : public CloudFilter
00276       {
00277       public:
00278         FastBilateralCF ();
00279         virtual ~FastBilateralCF ();
00280 
00281         virtual void
00282         filter (
00283           pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud_in,
00284           pcl::PointCloud<pcl::PointXYZRGBA>::Ptr &cloud_out);
00285         
00286         virtual QWizardPage *
00287         getParameterPage ()
00288         {
00289           return (filter_selection_page_);
00290         }
00291 
00292       protected:
00293         float sigma_s_;
00294         float sigma_r_;
00295 
00296         QLabel * sigma_s_label_;
00297         QLabel * sigma_r_label_;
00298         QLineEdit * sigma_s_line_edit_;
00299         QLineEdit * sigma_r_line_edit_;
00300         QVBoxLayout * main_layout_;
00301         QWizardPage * filter_selection_page_;
00302       };
00303 
00305 
00308       class MedianCF
00309         : public CloudFilter
00310       {
00311       public:
00312         MedianCF ();
00313         virtual ~MedianCF ();
00314 
00315         virtual void
00316         filter (
00317           pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud_in,
00318           pcl::PointCloud<pcl::PointXYZRGBA>::Ptr &cloud_out);
00319         
00320         virtual QWizardPage *
00321         getParameterPage ()
00322         {
00323           return (filter_selection_page_);
00324         }
00325 
00326       protected:
00327         float max_allowed_movement_;
00328         int window_size_;
00329 
00330         QLabel * max_allowed_movement_label_;
00331         QLabel * window_size_label_;
00332         QLineEdit * max_allowed_movement_line_edit_;
00333         QLineEdit * window_size_line_edit_;
00334         QVBoxLayout * main_layout_;
00335         QWizardPage * filter_selection_page_;
00336       };
00337 
00339 
00342       class RandomSampleCF
00343         : public CloudFilter
00344       {
00345       public:
00346         RandomSampleCF ();
00347         virtual ~RandomSampleCF ();
00348 
00349         virtual void
00350         filter (
00351           pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud_in,
00352           pcl::PointCloud<pcl::PointXYZRGBA>::Ptr &cloud_out);
00353         
00354         virtual QWizardPage *
00355         getParameterPage ()
00356         {
00357           return (filter_selection_page_);
00358         }
00359 
00360       protected:
00361         int seed_;
00362         int sample_;
00363 
00364         QLabel * seed_label_;
00365         QLabel * sample_label_;
00366         QLineEdit * seed_line_edit_;
00367         QLineEdit * sample_line_edit_;
00368         QVBoxLayout * main_layout_;
00369         QWizardPage * filter_selection_page_;
00370       };
00371 
00373 
00376       class PlaneCF
00377         : public CloudFilter
00378       {
00379       public:
00380         PlaneCF ();
00381         virtual ~PlaneCF ();
00382 
00383         virtual void
00384         filter (
00385           pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud_in,
00386           pcl::PointCloud<pcl::PointXYZRGBA>::Ptr &cloud_out);
00387         
00388         virtual QWizardPage *
00389         getParameterPage ()
00390         {
00391           return (filter_selection_page_);
00392         }
00393 
00394       protected:
00395         double threshold_;
00396         int max_iterations_;
00397 
00398         double refinement_sigma_;
00399         int max_refinement_iterations_;
00400 
00401         bool return_negative_;
00402 
00403         double cluster_tolerance_;
00404         int min_cluster_size_;
00405 
00406         QLabel * threshold_label_;
00407         QLabel * max_iterations_label_;
00408         QLabel * refinement_sigma_label_;
00409         QLabel * max_refinement_iterations_label_;
00410         QLabel * return_negative_label_;
00411         QLabel * cluster_tolerance_label_;
00412         QLabel * min_cluster_size_label_;
00413 
00414         QLineEdit * threshold_line_edit_;
00415         QLineEdit * max_iterations_line_edit_;
00416         QLineEdit * refinement_sigma_line_edit_;
00417         QLineEdit * max_refinement_iterations_line_edit_;
00418         QCheckBox * return_negative_check_box_;
00419         QLineEdit * cluster_tolerance_line_edit_;
00420         QLineEdit * min_cluster_size_line_edit_;
00421 
00422         QVBoxLayout * main_layout_;
00423         QWizardPage * filter_selection_page_;
00424       };
00425 
00426 
00428       char g_voxel_grid_cf_name[];
00429       char g_passthrough_cf_name[];
00430       char g_radius_outlier_cf_name[];
00431       char g_fast_bilateral_cf_name[];
00432       char g_median_cf_name[];
00433       char g_random_sample_cf_name[];
00434       char g_plane_cf_name[];
00435 
00437       typedef CloudFilterFactory2< VoxelGridCF,      g_voxel_grid_cf_name>      VoxelGridCFF2;
00438       typedef CloudFilterFactory2< PassThroughCF,    g_passthrough_cf_name>     PassThroughCFF2;
00439       typedef CloudFilterFactory2< RadiusOutlierCF,  g_radius_outlier_cf_name>  RadiusOutlierCFF2;
00440       typedef CloudFilterFactory2< FastBilateralCF,  g_fast_bilateral_cf_name>  FastBilateralCFF2;
00441       typedef CloudFilterFactory2< MedianCF,         g_median_cf_name>          MedianCFF2;
00442       typedef CloudFilterFactory2< RandomSampleCF,   g_random_sample_cf_name>   RandomSampleCFF2;
00443       typedef CloudFilterFactory2< PlaneCF,          g_plane_cf_name>           PlaneCFF2;
00444 
00445     }
00446   }
00447 }
00448 
00449 #endif // PCL_APPS_OPTRONIC_VIEWER_CLOUD_FILTER_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:22:41