00001 #ifndef VELODYNEUTILS_EXECUTIVES_HPP
00002 #define VELODYNEUTILS_EXECUTIVES_HPP
00003
00004 #include <sys/types.h>
00005
00006 #include <string>
00007
00008 #include <libregionMap.h>
00009
00010 #include <Eigen/Geometry>
00011 #include <pcl/filters/passthrough.h>
00012 #include <pcl/point_cloud.h>
00013 #include <pcl/point_types.h>
00014
00015 #include "data.hpp"
00016 #include "fileIO.hpp"
00017 #include "filters.hpp"
00018 #include "points.hpp"
00019 #include "visualizers.hpp"
00020
00021 namespace jafar {
00022 namespace velodyneutils {
00023
00024 class Executive {
00025 public:
00026 virtual void update() = 0;
00027 virtual bool isId(const std::string& id) const = 0;
00028 };
00029
00033 class ExecutiveReaderPosition : public Executive {
00034 public:
00035 typedef ReaderPosition Filter;
00036 typedef jafar::velodyneutils::Data<Eigen::Affine3f> Data;
00037
00038 ExecutiveReaderPosition(Filter* readerIn, Data* outputIn,
00039 const std::string& idIn);
00040 ~ExecutiveReaderPosition();
00041
00042 void setBaseFileName(const std::string& baseFileName);
00043 void setFileNumInput(void* fileNumInput);
00044 void setOutput(Data* output);
00045 virtual void update();
00046 virtual bool isId(const std::string& id) const;
00047
00048 private:
00049 Filter* reader;
00050 int* fileNumInput;
00051 Data* output;
00052 int time;
00053 bool updateNecessary;
00054 std::string id;
00055 };
00056
00060 class ExecutiveReaderVelodyneImage3D : public Executive {
00061 public:
00062 typedef ReaderVelodyneImage3D Filter;
00063 typedef jafar::velodyneutils::Data<pcl::PointCloud<pcl::PointXYZL> > Data;
00064
00065 ExecutiveReaderVelodyneImage3D(Filter* readerIn, Data* outputIn,
00066 const std::string& idIn);
00067 ~ExecutiveReaderVelodyneImage3D();
00068
00069 void setBaseFileName(const std::string& baseFileName);
00070 void setFileNumInput(void* fileNumInput);
00071 void setOutput(Data* output);
00072 virtual void update();
00073 virtual bool isId(const std::string& id) const;
00074
00075 private:
00076 Filter* reader;
00077 int* fileNumInput;
00078 Data* output;
00079 int time;
00080 bool updateNecessary;
00081 std::string id;
00082 };
00083
00087 class ExecutiveReader3DImage : public Executive {
00088 public:
00089 typedef Reader3DImage Filter;
00090 typedef jafar::velodyneutils::Data<pcl::PointCloud<PointXYZIL> > Data;
00091
00092 ExecutiveReader3DImage(Filter* readerIn, Data* outputIn,
00093 const std::string& idIn);
00094 ~ExecutiveReader3DImage();
00095
00096 void setBaseFileName(const std::string& baseFileName);
00097 void setFileNumInput(void* fileNumInput);
00098 void setOutput(Data* output);
00099 virtual void update();
00100 virtual bool isId(const std::string& id) const;
00101
00102 private:
00103 Filter* reader;
00104 int* fileNumInput;
00105 Data* output;
00106 int time;
00107 bool updateNecessary;
00108 std::string id;
00109 };
00110
00114 class ExecutiveReaderRegionMap : public Executive {
00115 public:
00116 typedef ReaderRegionMap Reader;
00117 typedef jafar::velodyneutils::Data<pcl::PointCloud<PointRegionMap> >
00118 DataCloud;
00119 typedef jafar::velodyneutils::Data<REGION_MAP> DataRegionMap;
00120
00121 ExecutiveReaderRegionMap(Reader* reader, DataCloud* output,
00122 const std::string& id);
00123 ExecutiveReaderRegionMap(Reader* reader, DataRegionMap* output,
00124 const std::string& id);
00125 ~ExecutiveReaderRegionMap();
00126
00127 void setBaseFileName(const std::string& baseFileName);
00128 void setFileNum(int fileNum);
00129 void setInputFileNum(void* inputFileNum);
00130 void setOutputCloud(DataCloud* output);
00131 void setOutputRegionMap(DataRegionMap* output);
00132 virtual void update();
00133 virtual bool isId(const std::string& id) const;
00134
00135 private:
00136 Reader* mReader;
00137 int* mInputFileNum;
00138 DataCloud* mOutputCloud;
00139 DataRegionMap* mOutputRegionMap;
00140 int time;
00141 bool updateNecessary;
00142 std::string mId;
00143 };
00144
00148 template<typename PointT>
00149 class ExecutiveWriterPCD : public Executive {
00150 public:
00151 typedef WriterPCD<PointT> Filter;
00152 typedef jafar::velodyneutils::Data<pcl::PointCloud<PointT> > Data;
00153
00154 ExecutiveWriterPCD(Filter* writerIn, Data* inputIn,
00155 const std::string& idIn);
00156 ~ExecutiveWriterPCD();
00157
00158 void setInput(Data* input);
00159 void setBinary(bool binary);
00160 void setBaseFileName(const std::string& baseFileName);
00161 void setFileNumInput(void* fileNumInput);
00162 virtual void update();
00163 virtual bool isId(const std::string& id) const;
00164
00165 private:
00166 Filter* writer;
00167 Data* input;
00168 int* fileNumInput;
00169 int time;
00170 bool updateNecessary;
00171 std::string id;
00172 };
00173
00177 template<typename PointT>
00178 class ExecutiveFrameTransformer : public Executive {
00179 public:
00180 typedef FrameTransformer<PointT> Filter;
00181 typedef jafar::velodyneutils::Data<pcl::PointCloud<PointT> > DataCloud;
00182 typedef jafar::velodyneutils::Data<Eigen::Affine3f> DataAffine;
00183
00184 ExecutiveFrameTransformer(Filter* filterIn, DataCloud* inputCloudIn,
00185 DataAffine* inputAffineIn, DataCloud* outputIn,
00186 const std::string& idIn);
00187 ~ExecutiveFrameTransformer();
00188
00189 void setInputCloud(DataCloud* input);
00190 void setInputAffine(DataAffine* input);
00191 void setOutput(DataCloud* output);
00192 virtual void update();
00193 virtual bool isId(const std::string& id) const;
00194
00195 private:
00196 Filter* filter;
00197 DataCloud* inputCloud;
00198 DataAffine* inputAffine;
00199 DataCloud* output;
00200 int timeCloud;
00201 int timeAffine;
00202 bool updateNecessary;
00203 std::string id;
00204 };
00205
00209 template<typename PointInT>
00210 class ExecutiveToHDL : public Executive {
00211 public:
00212 typedef ToHDL<PointInT> Filter;
00213 typedef jafar::velodyneutils::Data<pcl::PointCloud<PointInT> > DataIn;
00214 typedef jafar::velodyneutils::Data<pcl::PointCloud<PointHDL> > DataOut;
00215
00216 ExecutiveToHDL(Filter* filterIn, DataIn* inputIn, DataOut* outputIn,
00217 const std::string& idIn);
00218 ~ExecutiveToHDL();
00219
00220 void setInput(DataIn* input);
00221 void setOutput(DataOut* output);
00222 virtual void update();
00223 virtual bool isId(const std::string& id) const;
00224
00225 private:
00226 Filter* filter;
00227 DataIn* input;
00228 DataOut* output;
00229 int time;
00230 bool updateNecessary;
00231 std::string id;
00232 };
00233
00237 template<typename PointInT, typename PointOutT>
00238 class ExecutiveNormalEstimatorImages3D : public Executive {
00239 public:
00240 typedef NormalEstimatorImages3D<PointInT, PointOutT> Filter;
00241 typedef jafar::velodyneutils::Data<pcl::PointCloud<PointInT> > DataIn;
00242 typedef jafar::velodyneutils::Data<pcl::PointCloud<PointOutT> > DataOut;
00243
00244 ExecutiveNormalEstimatorImages3D(
00245 Filter* filterIn, DataIn* inputIn, DataOut* outputIn,
00246 const std::string& idIn);
00247 ~ExecutiveNormalEstimatorImages3D();
00248
00249 void setInput(DataIn* input);
00250 void setOutput(DataOut* output);
00251 virtual void update();
00252 virtual bool isId(const std::string& id) const;
00253
00254 private:
00255 Filter* filter;
00256 DataIn* input;
00257 DataOut* output;
00258 int time;
00259 bool updateNecessary;
00260 std::string id;
00261 };
00262
00266 template<typename PointInT>
00267 class ExecutiveRegionMapEstimator : public Executive {
00268 public:
00269 typedef RegionMapEstimator<PointInT> Filter;
00270 typedef jafar::velodyneutils::Data<pcl::PointCloud<PointInT> > DataIn;
00271 typedef jafar::velodyneutils::Data<pcl::PointCloud<PointRegionMap> >
00272 DataOut;
00273
00274 ExecutiveRegionMapEstimator(Filter* filterIn,
00275 DataIn* inputIn, DataOut* outputIn,
00276 const std::string& idIn);
00277 ~ExecutiveRegionMapEstimator();
00278
00279 void setInput(DataIn* input);
00280 void setOutput(DataOut* output);
00281 virtual void update();
00282 virtual bool isId(const std::string& id) const;
00283
00284 private:
00285 Filter* filter;
00286 DataIn* input;
00287 DataOut* output;
00288 int time;
00289 bool updateNecessary;
00290 std::string id;
00291 };
00292
00296 template<typename PointT>
00297 class ExecutivePassThrough : public Executive {
00298 public:
00299 typedef pcl::PassThrough<PointT> Filter;
00300 typedef jafar::velodyneutils::Data<pcl::PointCloud<PointT> > Data;
00301
00302 ExecutivePassThrough(Filter* filterIn, Data* inputIn, Data* outputIn,
00303 const std::string& idIn);
00304 ~ExecutivePassThrough();
00305
00306 void setInput(Data* input);
00307 void setFieldName(const std::string& fieldName);
00308 void setLimits(float limitMin, float limitMax);
00309 void setOutput(Data* output);
00310 virtual void update();
00311 virtual bool isId(const std::string& id) const;
00312
00313 private:
00314 Filter* filter;
00315 Data* input;
00316 Data* output;
00317 int time;
00318 bool updateNecessary;
00319 std::string id;
00320 };
00321
00325 template<typename PointT>
00326 class ExecutivePointCloudMapper : public Executive {
00327 public:
00328 typedef PointCloudMapper<PointT> Filter;
00329 typedef jafar::velodyneutils::Data<pcl::PointCloud<PointT> > Data;
00330
00331 ExecutivePointCloudMapper(Filter* filter, Data* input, Data* output,
00332 const std::string& id);
00333 ~ExecutivePointCloudMapper();
00334
00335 void setInput(Data* input);
00336 void setOutput(Data* output);
00337 virtual void update();
00338 virtual bool isId(const std::string& id) const;
00339
00340 private:
00341 Filter* mFilter;
00342 Data* mInput;
00343 Data* mOutput;
00344 int time;
00345 bool updateNecessary;
00346 std::string mId;
00347 };
00348
00352 template<typename PointT>
00353 class ExecutivePointCloudClassifier : public Executive {
00354 public:
00355 typedef PointCloudClassifier<PointT> Filter;
00356 typedef jafar::velodyneutils::Data<pcl::PointCloud<PointT> > DataInCloud;
00357 typedef jafar::velodyneutils::Data<REGION_MAP> DataInRegionMap;
00358 typedef jafar::velodyneutils::Data<pcl::PointCloud<PointRegionMap> >
00359 DataOut;
00360
00361 ExecutivePointCloudClassifier(
00362 Filter* filter,
00363 DataInCloud* inputCloud, DataInRegionMap* inputRegionMap,
00364 DataOut* output,
00365 const std::string& id);
00366 ~ExecutivePointCloudClassifier();
00367
00368 void setInputCloud(DataInCloud* input);
00369 void setInputRegionMap(DataInRegionMap* input);
00370 void setOutput(DataOut* output);
00371 virtual void update();
00372 virtual bool isId(const std::string& id) const;
00373
00374 private:
00375 Filter* mFilter;
00376 DataInCloud* mInputCloud;
00377 DataInRegionMap* mInputRegionMap;
00378 DataOut* mOutput;
00379 int timeCloud;
00380 int timeRegionMap;
00381 bool updateNecessary;
00382 std::string mId;
00383 };
00384
00388 template<typename PointT>
00389 class ExecutiveVisualizerCloud : public Executive {
00390 public:
00391 typedef VisualizerCloud<PointT> Filter;
00392 typedef jafar::velodyneutils::Data<pcl::PointCloud<PointT> > Data;
00393
00394 ExecutiveVisualizerCloud(Filter* filterIn, Data* inputIn,
00395 const std::string& idIn, int numIdIn);
00396 ~ExecutiveVisualizerCloud();
00397
00398 void setInput(Data* input);
00399 void setNumIdInput(void* numIdInput);
00400 void setControlInput(bool* controlInput);
00401 void setHandlerControlInput(bool* handlerControlInput);
00402 void setHandlerNumInput(void* handlerNumInput);
00403 virtual void update();
00404 virtual bool isId(const std::string& id) const;
00405
00406 private:
00407 Filter* filter;
00408 Data* input;
00409 int* numIdInput;
00410 bool* controlInput;
00411 bool* handlerControlInput;
00412 int* handlerNumInput;
00413 int time;
00414 bool updateNecessary;
00415 std::string id;
00416 int numId;
00417 };
00418
00422 template<typename PointT>
00423 class ExecutiveVisualizerNormals : public Executive {
00424 public:
00425 typedef VisualizerNormals<PointT> Filter;
00426 typedef jafar::velodyneutils::Data<pcl::PointCloud<PointT> > Data;
00427
00428 ExecutiveVisualizerNormals(Filter* filterIn, Data* inputIn,
00429 const std::string& idIn, int numIdIn);
00430 ~ExecutiveVisualizerNormals();
00431
00432 void setInput(Data* input);
00433 void setNumIdInput(void* numIdInput);
00434 void setControlInput(bool* controlInput);
00435 virtual void update();
00436 virtual bool isId(const std::string& id) const;
00437
00438 private:
00439 Filter* filter;
00440 Data* input;
00441 int* numIdInput;
00442 bool* controlInput;
00443 int time;
00444 bool updateNecessary;
00445 std::string id;
00446 int numId;
00447 };
00448
00449 }
00450 }
00451
00452 #endif // VELODYNEUTILS_EXECUTIVES_HPP