Jafar
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
filters.hpp
00001 #ifndef VELODYNEUTILS_FILTERS_HPP
00002 #define VELODYNEUTILS_FILTERS_HPP
00003 
00004 #include <sys/types.h> // Necessary for libregionMap.h
00005 
00006 #include <libregionMap.h>
00007 
00008 #include <boost/shared_ptr.hpp>
00009 #include <Eigen/Geometry>
00010 #include <pcl/pcl_base.h>
00011 #include <pcl/point_cloud.h>
00012 
00013 #include "points.hpp"
00014 
00015 extern "C" {
00016 typedef struct data_im3d DATA_IM3D;
00017 typedef struct REGION_MAP REGION_MAP;
00018 }
00019 
00020 namespace jafar {
00021 namespace velodyneutils {
00022 
00026 template<typename PointT>
00027 class FrameTransformer : public pcl::PCLBase<PointT> {
00028 public:
00029     typedef pcl::PCLBase<PointT> BaseClass;
00030     typedef pcl::PointCloud<PointT> PointCloud;
00031     typedef boost::shared_ptr<const Eigen::Affine3f> AffineConstPtr;
00032     typedef boost::shared_ptr<FrameTransformer<PointT> > Ptr;
00033     typedef boost::shared_ptr<const FrameTransformer<PointT> > ConstPtr;
00034 
00035     FrameTransformer();
00036     ~FrameTransformer();
00037 
00038     int setInputAffine(const AffineConstPtr& affine);
00039     int compute(PointCloud& output);
00040 
00041 private:
00042     AffineConstPtr affine;
00043 
00044     bool initCompute();
00045 };
00046 
00050 template<typename PointInT>
00051 class ToHDL : public pcl::PCLBase<PointInT> {
00052 public:
00053     typedef pcl::PCLBase<PointInT> BaseClass;
00054     typedef typename BaseClass::PointCloud PointCloudIn;
00055     typedef pcl::PointCloud<PointHDL> PointCloudOut;
00056     typedef boost::shared_ptr<ToHDL<PointInT> > Ptr;
00057     typedef boost::shared_ptr<const ToHDL<PointInT> > ConstPtr;
00058 
00059     ToHDL();
00060     ~ToHDL();
00061 
00062     void compute(PointCloudOut& output);
00063 
00064 private:
00065     bool initCompute();
00066 };
00067 
00071 template<typename PointInT, typename PointOutT>
00072 class NormalEstimatorImages3D : public pcl::PCLBase<PointInT> {
00073 public:
00074     typedef pcl::PCLBase<PointInT> BaseClass;
00075     typedef pcl::PointCloud<PointOutT> PointCloudOut;
00076     typedef boost::shared_ptr<NormalEstimatorImages3D<PointInT, PointOutT> >
00077             Ptr;
00078     typedef boost::shared_ptr<const NormalEstimatorImages3D<PointInT, PointOutT> >
00079             ConstPtr;
00080 
00081     NormalEstimatorImages3D();
00082     ~NormalEstimatorImages3D();
00083 
00084     void init();
00085     void compute(PointCloudOut& output);
00086 
00087 private:
00088     DATA_IM3D* im3D;
00089     pcl::PointCloud<NormalPure> normals;
00090 
00091     bool initCompute();
00092 };
00093 
00097 template<typename PointInT>
00098 class RegionMapEstimator : public pcl::PCLBase<PointInT> {
00099 public:
00100     typedef pcl::PCLBase<PointInT> BaseClass;
00101     typedef pcl::PointCloud<PointRegionMap> PointCloudOut;
00102     typedef boost::shared_ptr<RegionMapEstimator<PointInT> > Ptr;
00103     typedef boost::shared_ptr<const RegionMapEstimator<PointInT> > ConstPtr;
00104 
00105     RegionMapEstimator();
00106     ~RegionMapEstimator();
00107 
00108     void init();
00109     void compute(PointCloudOut& output);
00110 
00111 private:
00112     REGION_MAP* regionMap;
00113     DATA_IM3D* im3D;
00114 
00115     bool initCompute();
00116 };
00117 
00121 template<typename PointT>
00122 class PointCloudMapper {
00123 public:
00124     typedef typename pcl::PointCloud<PointT> PointCloud;
00125     typedef typename PointCloud::Ptr PointCloudPtr;
00126     typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00127     typedef boost::shared_ptr<PointCloudMapper<PointT> > Ptr;
00128     typedef boost::shared_ptr<const PointCloudMapper<PointT> > ConstPtr;
00129 
00130     PointCloudMapper();
00131     ~PointCloudMapper();
00132 
00133     int setCloudIn(const PointCloudConstPtr& cloud);
00134     int setCloudOut(const PointCloudPtr& cloud);
00135     int compute();
00136 
00137 private:
00138     PointCloudConstPtr mCloudIn;
00139     PointCloudPtr mCloudInDense;
00140     PointCloudPtr mCloudOut;
00141     int numClouds;
00142 
00143     bool initCompute();
00144 };
00145 
00149 template<typename PointT>
00150 class PointCloudClassifier {
00151 public:
00152     typedef typename pcl::PointCloud<PointT> PointCloudIn;
00153     typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00154     typedef typename boost::shared_ptr<const REGION_MAP> RegionMapConstPtr;
00155     typedef typename pcl::PointCloud<PointRegionMap> PointCloudOut;
00156     typedef typename PointCloudOut::Ptr PointCloudOutPtr;
00157     typedef boost::shared_ptr<PointCloudClassifier<PointT> > Ptr;
00158     typedef boost::shared_ptr<const PointCloudClassifier<PointT> > ConstPtr;
00159 
00160     PointCloudClassifier();
00161     ~PointCloudClassifier();
00162 
00163     int setCloudIn(const PointCloudInConstPtr& cloud);
00164     int setRegionMap(const RegionMapConstPtr& regionMap);
00165     int setCloudOut(const PointCloudOutPtr& cloud);
00166     int compute();
00167 
00168 private:
00169     PointCloudInConstPtr mCloudIn;
00170     RegionMapConstPtr mRegionMap;
00171     PointCloudOutPtr mCloudOut;
00172 
00173     bool initCompute();
00174 };
00175 
00176 } // namespace velodyneutils
00177 } // namespace jafar
00178 
00179 #endif // VELODYNEUTILS_FILTERS_HPP
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines

Generated on Wed Oct 15 2014 00:37:29 for Jafar by doxygen 1.7.6.1
LAAS-CNRS