00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #ifndef __POINTMATCHER_INSPECTORS_H
00037 #define __POINTMATCHER_INSPECTORS_H
00038
00039 #include "PointMatcher.h"
00040 #include "Histogram.h"
00041
00042 template<typename T>
00043 struct InspectorsImpl
00044 {
00045 typedef PointMatcherSupport::Parametrizable Parametrizable;
00046 typedef PointMatcherSupport::Parametrizable P;
00047 typedef Parametrizable::Parameters Parameters;
00048 typedef Parametrizable::ParameterDoc ParameterDoc;
00049 typedef Parametrizable::ParametersDoc ParametersDoc;
00050
00051 typedef typename PointMatcher<T>::Inspector Inspector;
00052 typedef typename PointMatcher<T>::DataPoints DataPoints;
00053 typedef typename PointMatcher<T>::Matches Matches;
00054 typedef typename PointMatcher<T>::OutlierWeights OutlierWeights;
00055 typedef typename PointMatcher<T>::TransformationParameters TransformationParameters;
00056 typedef typename PointMatcher<T>::TransformationCheckers TransformationCheckers;
00057 typedef typename PointMatcher<T>::Matrix Matrix;
00058
00059
00060 struct NullInspector: public Inspector
00061 {
00062 inline static const std::string description()
00063 {
00064 return "Does nothing.";
00065 }
00066
00067
00068 NullInspector() : Inspector("NullInspector", ParametersDoc(), Parameters()) {}
00069
00070 };
00071
00072 struct PerformanceInspector: public Inspector
00073 {
00074 inline static const std::string description()
00075 {
00076 return "Keep statistics on performance.";
00077 }
00078 inline static const ParametersDoc availableParameters()
00079 {
00080 return {
00081 {"baseFileName", "base file name for the statistics files (if empty, disabled)", ""},
00082 {"dumpPerfOnExit", "dump performance statistics to stderr on exit", "0"},
00083 {"dumpStats", "dump the statistics on first and last step", "0"}
00084 };
00085 }
00086
00087 const std::string baseFileName;
00088
00089
00090 const bool bDumpPerfOnExit;
00091 const bool bDumpStats;
00092
00093 protected:
00094 typedef PointMatcherSupport::Histogram<double> Histogram;
00095 typedef std::map<std::string, Histogram> HistogramMap;
00096 HistogramMap stats;
00097
00098 public:
00099 PerformanceInspector(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00100 PerformanceInspector(const Parameters& params);
00101
00102 virtual void addStat(const std::string& name, double data);
00103 virtual void dumpStats(std::ostream& stream);
00104 virtual void dumpStatsHeader(std::ostream& stream);
00105 };
00106
00107 struct AbstractVTKInspector: public PerformanceInspector
00108 {
00109
00110 protected:
00111 virtual std::ostream* openStream(const std::string& role) = 0;
00112 virtual std::ostream* openStream(const std::string& role, const size_t iterationNumber) = 0;
00113 virtual void closeStream(std::ostream* stream) = 0;
00114 void dumpDataPoints(const DataPoints& data, std::ostream& stream);
00115 void dumpMeshNodes(const DataPoints& data, std::ostream& stream);
00116 void dumpDataLinks(const DataPoints& ref, const DataPoints& reading, const Matches& matches, const OutlierWeights& featureOutlierWeights, std::ostream& stream);
00117
00118 std::ostream* streamIter;
00119 const bool bDumpIterationInfo;
00120 const bool bDumpDataLinks;
00121 const bool bDumpReading;
00122 const bool bDumpReference;
00123 const bool bWriteBinary;
00124
00125 public:
00126 AbstractVTKInspector(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00127 virtual void init() {};
00128 virtual void dumpDataPoints(const DataPoints& cloud, const std::string& name);
00129 virtual void dumpMeshNodes(const DataPoints& cloud, const std::string& name);
00130 virtual void dumpIteration(const size_t iterationNumber, const TransformationParameters& parameters, const DataPoints& filteredReference, const DataPoints& reading, const Matches& matches, const OutlierWeights& outlierWeights, const TransformationCheckers& transformationCheckers);
00131 virtual void finish(const size_t iterationCount);
00132
00133 private:
00134 void buildGenericAttributeStream(std::ostream& stream, const std::string& attribute, const std::string& nameTag, const DataPoints& cloud, const int forcedDim);
00135
00136 void buildScalarStream(std::ostream& stream, const std::string& name, const DataPoints& ref, const DataPoints& reading);
00137 void buildScalarStream(std::ostream& stream, const std::string& name, const DataPoints& cloud);
00138
00139 void buildNormalStream(std::ostream& stream, const std::string& name, const DataPoints& ref, const DataPoints& reading);
00140 void buildNormalStream(std::ostream& stream, const std::string& name, const DataPoints& cloud);
00141
00142 void buildVectorStream(std::ostream& stream, const std::string& name, const DataPoints& ref, const DataPoints& reading);
00143 void buildVectorStream(std::ostream& stream, const std::string& name, const DataPoints& cloud);
00144
00145 void buildTensorStream(std::ostream& stream, const std::string& name, const DataPoints& ref, const DataPoints& reading);
00146 void buildTensorStream(std::ostream& stream, const std::string& name, const DataPoints& cloud);
00147
00148 void buildColorStream(std::ostream& stream, const std::string& name, const DataPoints& cloud);
00149
00150 void buildTimeStream(std::ostream& stream, const std::string& name, const DataPoints& cloud);
00151
00152
00153
00154 Matrix padWithZeros(const Matrix m, const int expectedRow, const int expectedCols);
00155 Matrix padWithOnes(const Matrix m, const int expectedRow, const int expectedCols);
00156 };
00157
00158 struct VTKFileInspector: public AbstractVTKInspector
00159 {
00160 inline static const std::string description()
00161 {
00162 return "Dump the different steps into VTK files.";
00163 }
00164 inline static const ParametersDoc availableParameters()
00165 {
00166 return {
00167 {"baseFileName", "base file name for the VTK files ", "point-matcher-output"},
00168 {"dumpPerfOnExit", "dump performance statistics to stderr on exit", "0"},
00169 {"dumpStats", "dump the statistics on first and last step", "0"},
00170 {"dumpIterationInfo", "dump iteration info", "0"},
00171 {"dumpDataLinks", "dump data links at each iteration", "0" },
00172 {"dumpReading", "dump the reading cloud at each iteration", "0"},
00173 {"dumpReference", "dump the reference cloud at each iteration", "0"},
00174 {"writeBinary", "write binary VTK files", "0"}
00175 };
00176 }
00177
00178 const std::string baseFileName;
00179 const bool bDumpIterationInfo;
00180 const bool bDumpDataLinks;
00181 const bool bDumpReading;
00182 const bool bDumpReference;
00183
00184 protected:
00185 virtual std::ostream* openStream(const std::string& role);
00186 virtual std::ostream* openStream(const std::string& role, const size_t iterationCount);
00187 virtual void closeStream(std::ostream* stream);
00188
00189 public:
00190 VTKFileInspector(const Parameters& params = Parameters());
00191 virtual void init();
00192 virtual void finish(const size_t iterationCount);
00193 };
00194 };
00195
00196 #endif // __POINTMATCHER_INSPECTORS_H