StrColParams.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Fraunhofer FKIE
00003  *
00004  * Authors: Bastian Gaspers
00005  *
00006  * Redistribution and use in source and binary forms, with or without
00007  * modification, are permitted provided that the following conditions are met:
00008  *
00009  * * Redistributions of source code must retain the above copyright
00010  *   notice, this list of conditions and the following disclaimer.
00011  * * Redistributions in binary form must reproduce the above copyright
00012  *   notice, this list of conditions and the following disclaimer in the
00013  *   documentation and/or other materials provided with the distribution.
00014  * * Neither the name of the Fraunhofer FKIE nor the names of its
00015  *   contributors may be used to endorse or promote products derived from
00016  *   this software without specific prior written permission.
00017  *
00018  * This file is part of the StructureColoring ROS package.
00019  *
00020  * The StructureColoring ROS package is free software:
00021  * you can redistribute it and/or modify it under the terms of the
00022  * GNU Lesser General Public License as published by the Free
00023  * Software Foundation, either version 3 of the License, or
00024  * (at your option) any later version.
00025  *
00026  * The StructureColoring ROS package is distributed in the hope that it will be useful,
00027  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00028  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00029  * GNU Lesser General Public License for more details.
00030  *
00031  * You should have received a copy of the GNU Lesser General Public License
00032  * along with The StructureColoring ROS package.
00033  * If not, see <http://www.gnu.org/licenses/>.
00034  */
00035 
00036 #ifndef STRCOLPARAMS_H_
00037 #define STRCOLPARAMS_H_
00038 
00039 #include <string>
00040 
00041 class StrColParams {
00042 public:
00043         StrColParams();
00044         virtual ~StrColParams();
00045 
00046         void parseParamFile(std::string filename);
00047 
00048 private:
00049         void init();
00050 
00051 public:
00052 //params for computation of segmentation
00053         float mTexelSizeFactor;
00054         unsigned int mDilateIterations;
00055         unsigned int mPhi_resolution; //number of steps from 0 to PI
00056         float mMaxSACDistanceThreshold;
00057         float mMinSACDistanceThreshold;
00058         float mSACOctreeFactor;
00059         float mMaxHTDistanceThreshold;
00060         float mHTOctreeBinSizeFactor;
00061         float mHTDistanceDeviationFactor;
00062         float mAngleEps; //angle epsilon in radians - angle between one gridcellnormal and planenormal may differ no more than angle epsilon
00063         float mAngleEpsOnMinOctreeRes;
00064         float mSACOutlierRatioThreshold;
00065         unsigned int mMinPointsInCC; //min number of points in a connected component
00066         unsigned int mMinNodesInCC;
00067         unsigned int mMinNodesInCylinder;
00068         float mMergePlanesSimilarityFactor;
00069         float mNodeToBBDistance;
00070         int mDebugSteps;
00071         int mConnectionNeighbors;
00072         float mRho_max;
00073         int mMinPointsForNormal;
00074         float mCurvThreshold;
00075         float mCurv2Threshold;
00076         float mPrincipalVarFactor;
00077         unsigned int mMinOctreeNodes;
00078         unsigned int mTriesOnEachDepth;
00079         float mMinOctreeResolution;
00080         float mSqDistFactor;
00081         float mNodeSegmentedRatio;
00082 
00083 //params for cylinders only
00084         float mNormalDistanceWeight;
00085         float mMinRadiusFactor;
00086         float mMaxRadiusFactor;
00087         float mMinCylinderRadius;
00088         float mMaxCylinderRadius;
00089         unsigned int mCylinderBins;
00090         unsigned int mCylinderPairNeighbors;
00091         float mMidPointBinSizeFactor;
00092         float mRadiusDevFactor;
00093         float mOccupiedRatio;
00094         float mCylinderHeightDev;
00095 
00096 //params from command line input
00097         bool mVerbose;
00098         bool mPGM;
00099         bool mKinect;
00100         bool mLaser;
00101         bool mABW;
00102         bool mPerceptron;
00103         bool mTextures;
00104         bool mCylinder;
00105         bool mPclSAC;
00106         bool mNoRansacStep;
00107         bool mWriteRawPic;
00108         std::string mRawPicFilename;
00109         unsigned int mRawPicCounter;
00110         bool mLoadPCD;
00111         bool mPCDnoRGB;
00112         std::string mRuntimeFilename;
00113         std::string mLaserTopic;
00114         int mPclSACmaxIter;
00115         int mOnlyDepth;
00116         std::string mInputFilename, mOutputFilename, mNormalOutputFilename;
00117 
00118         int mPostProcessing;
00119 };
00120 
00121 #endif /* STRCOLPARAMS_H_ */


structure_coloring_fkie
Author(s): Bastian Gaspers
autogenerated on Sun Jan 5 2014 11:38:09