smoothing_filter.h
Go to the documentation of this file.
00001 /****************************************************************
00002  *
00003  * Copyright (c) 2011
00004  *
00005  * Fraunhofer Institute for Manufacturing Engineering
00006  * and Automation (IPA)
00007  *
00008  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00009  *
00010  * Project name: care-o-bot
00011  * ROS stack name: cob_environment_perception_intern
00012  * ROS package name: cob_3d_mapping_filters
00013  * Description:
00014  *
00015  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00016  *
00017  * Author: Waqas Tanveer, email:waqas.informatik@googlemail.com
00018  * Supervised by: Georg Arbeiter, email:georg.arbeiter@ipa.fhg.de
00019  *
00020  * Date of creation: 05/2011
00021 
00022  * Redistribution and use in source and binary forms, with or without
00023  * modification, are permitted provided that the following conditions are met:
00024  *
00025  *     * Redistributions of source code must retain the above copyright
00026  *       notice, this list of conditions and the following disclaimer.
00027  *     * Redistributions in binary form must reproduce the above copyright
00028  *       notice, this list of conditions and the following disclaimer in the
00029  *       documentation and/or other materials provided with the distribution.
00030  *     * Neither the name of the Fraunhofer Institute for Manufacturing
00031  *       Engineering and Automation (IPA) nor the names of its
00032  *       contributors may be used to endorse or promote products derived from
00033  *       this software without specific prior written permission.
00034  *
00035  * This program is free software: you can redistribute it and/or modify
00036  * it under the terms of the GNU Lesser General Public License LGPL as
00037  * published by the Free Software Foundation, either version 3 of the
00038  * License, or (at your option) any later version.
00039  *
00040  * This program is distributed in the hope that it will be useful,
00041  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00042  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00043  * GNU Lesser General Public License LGPL for more details.
00044  *
00045  * You should have received a copy of the GNU Lesser General Public
00046  * License LGPL along with this program.
00047  * If not, see <http://www.gnu.org/licenses/>.
00048  *
00049  ****************************************************************/
00050 
00051 #ifndef INTENSITY_FILTER_H_
00052 #define INTENSITY_FILTER_H_
00053 
00054 //##################
00055 //#### includes ####
00056 
00057 // PCL includes
00058 #include "pcl/pcl_base.h"
00059 #include <pcl/point_types.h>
00060 #include <pcl/filters/filter.h>
00061 
00062 namespace cob_3d_mapping_filters
00063 {
00067   template<typename PointT>
00068     class SmoothingFilter : public pcl::Filter<PointT>
00069     {
00070       using pcl::Filter<PointT>::input_;
00071 
00072     public:
00073       typedef typename pcl::Filter<PointT>::PointCloud PointCloud;
00074       typedef typename PointCloud::Ptr PointCloudPtr;
00075       typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00076 
00078       SmoothingFilter () :
00079           edge_threshold_ (0.05), smoothing_factor_ (0.25), integral_factor_ (0.25)
00080       {
00081       }
00082       ;
00083 
00084       //virtual ~IntensityFilter();
00085 
00087       inline void
00088       setFilterLimits (double edge_threshold, double smoothing_factor, double integral_factor)
00089       {
00090         edge_threshold_ = edge_threshold;
00091         smoothing_factor_ = smoothing_factor;
00092         integral_factor_ = integral_factor;
00093       }
00094 
00096       inline double
00097       getEdgeThr ()
00098       {
00099         return edge_threshold_;
00100       }
00101 
00103       inline double
00104       getSmoothingFactor ()
00105       {
00106         return smoothing_factor_;
00107       }
00108 
00110       inline double
00111       getIntegralFactor ()
00112       {
00113         return integral_factor_;
00114       }
00115 
00116     private:
00117 
00118       PointCloud last_pc_;
00119 
00120     public:
00121 
00125       void
00126       applyFilter (PointCloud &output);
00127 
00129       float edge_threshold_;
00130       float smoothing_factor_;
00131       float integral_factor_;
00132 
00133     };
00134 
00135 } // end namespace cob_3d_mapping_filters
00136 
00137 #endif /* INTENSITY_FILTER_H_ */


cob_3d_mapping_filters
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:02:54