InspectorsImpl.cpp
Go to the documentation of this file.
00001 // kate: replace-tabs off; indent-width 4; indent-mode normal
00002 // vim: ts=4:sw=4:noexpandtab
00003 /*
00004 
00005 Copyright (c) 2010--2012,
00006 François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland
00007 You can contact the authors at <f dot pomerleau at gmail dot com> and
00008 <stephane at magnenat dot net>
00009 
00010 All rights reserved.
00011 
00012 Redistribution and use in source and binary forms, with or without
00013 modification, are permitted provided that the following conditions are met:
00014     * Redistributions of source code must retain the above copyright
00015       notice, this list of conditions and the following disclaimer.
00016     * Redistributions in binary form must reproduce the above copyright
00017       notice, this list of conditions and the following disclaimer in the
00018       documentation and/or other materials provided with the distribution.
00019     * Neither the name of the <organization> nor the
00020       names of its contributors may be used to endorse or promote products
00021       derived from this software without specific prior written permission.
00022 
00023 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00024 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00025 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00026 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
00027 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00028 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00030 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00031 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00032 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00033 
00034 */
00035 
00036 #include "InspectorsImpl.h"
00037 
00038 #include "PointMatcherPrivate.h"
00039 
00040 #include <cassert>
00041 #include <iostream>
00042 #include <sstream>
00043 #include <fstream>
00044 
00045 using namespace std;
00046 
00047 template<typename T>
00048 InspectorsImpl<T>::PerformanceInspector::PerformanceInspector(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params):
00049         Inspector(className,paramsDoc,params),
00050         baseFileName(Parametrizable::get<string>("baseFileName")),
00051         bDumpPerfOnExit(Parametrizable::get<bool>("dumpPerfOnExit")),
00052         bDumpStats(Parametrizable::get<bool>("dumpStats"))
00053 
00054 {//FIXME: do we need that constructor?
00055 }
00056 
00057 template<typename T>
00058 InspectorsImpl<T>::PerformanceInspector::PerformanceInspector(const Parameters& params):
00059         Inspector("PerformanceInspector", PerformanceInspector::availableParameters(), params),
00060         baseFileName(Parametrizable::get<string>("baseFileName")),
00061         bDumpPerfOnExit(Parametrizable::get<bool>("dumpPerfOnExit")),
00062         bDumpStats(Parametrizable::get<bool>("dumpStats"))
00063 {}
00064 
00065 template<typename T>
00066 void InspectorsImpl<T>::PerformanceInspector::addStat(const std::string& name, double data)
00067 {
00068         if (!bDumpStats) return;
00069         
00070         HistogramMap::iterator it(stats.find(name));
00071         if (it == stats.end())
00072                 it = stats.insert(
00073                         HistogramMap::value_type(name, 
00074                                 Histogram(16, name, baseFileName, bDumpPerfOnExit)
00075                         )
00076                 ).first;
00077         it->second.push_back(data);
00078 }
00079 
00080 template<typename T>
00081 void InspectorsImpl<T>::PerformanceInspector::dumpStats(std::ostream& stream)
00082 {
00083         // Note: this dump format will most probably change in the future
00084         for (BOOST_AUTO(it, stats.begin()); it != stats.end(); ++it)
00085         {
00086                 it->second.dumpStats(stream);
00087                 BOOST_AUTO(jt, it);
00088                 ++jt;
00089                 if (jt != stats.end())
00090                         stream << ", ";
00091         }
00092 }
00093 
00094 template<typename T>
00095 void InspectorsImpl<T>::PerformanceInspector::dumpStatsHeader(std::ostream& stream)
00096 {
00097         for (BOOST_AUTO(it, stats.begin()); it != stats.end(); ++it)
00098         {
00099                 it->second.dumpStatsHeader(stream);
00100                 BOOST_AUTO(jt, it);
00101                 ++jt;
00102                 if (jt != stats.end())
00103                         stream << ", ";
00104         }
00105 }
00106 
00107 template struct InspectorsImpl<float>::PerformanceInspector;
00108 template struct InspectorsImpl<double>::PerformanceInspector;
00109 
00110 /*
00111         // This code creates a header according to information from the datapoints
00112         std::ofstream ofs(fileName.c_str());
00113         size_t labelIndex(0);
00114         size_t labelComponent(0);
00115         const typename DataPoints::Labels labels(data.featureLabels);
00116         for (int i = 0; i < features.rows(); ++i)
00117         {
00118                 // display label for row
00119                 if (labelIndex <= labels.size())
00120                 {
00121                         const typename DataPoints::Label label(labels[labelIndex]);
00122                         ofs << label.text;
00123                         if (label.span > 1)
00124                                 ofs << "_" << labelComponent;
00125                         ++labelComponent;
00126                         if (labelComponent >= label.span)
00127                                 ++labelIndex;
00128                 }
00129                 else
00130                 {
00131                         ofs << "?";
00132                 }
00133                 ofs << " ";
00134         }*/
00135 template<typename T>
00136 InspectorsImpl<T>::AbstractVTKInspector::AbstractVTKInspector(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params):
00137         PerformanceInspector(className,paramsDoc,params),
00138         streamIter(0),
00139         bDumpIterationInfo(Parametrizable::get<bool>("dumpIterationInfo")),
00140         bDumpDataLinks(Parametrizable::get<bool>("dumpDataLinks")),
00141         bDumpReading(Parametrizable::get<bool>("dumpReading")),
00142         bDumpReference(Parametrizable::get<bool>("dumpReference"))
00143 {
00144 }
00145 
00146         
00147 template<typename T>
00148 void InspectorsImpl<T>::AbstractVTKInspector::dumpDataPoints(const DataPoints& data, std::ostream& stream)
00149 {
00150         const Matrix& features(data.features);
00151         //const Matrix& descriptors(data.descriptors);
00152         
00153         stream << "# vtk DataFile Version 3.0\n";
00154         stream << "File created by libpointmatcher\n";
00155         stream << "ASCII\n";
00156         stream << "DATASET POLYDATA\n";
00157         stream << "POINTS " << features.cols() << " float\n";
00158         if(features.rows() == 4)
00159         {
00160                 stream << features.topLeftCorner(3, features.cols()).transpose() << "\n";
00161         }
00162         else
00163         {
00164                 stream << features.transpose() << "\n";
00165         }
00166         
00167         stream << "VERTICES "  << features.cols() << " "<< features.cols() * 2 << "\n";
00168         for (int i = 0; i < features.cols(); ++i)
00169                 stream << "1 " << i << "\n";
00170         
00171 
00172         // Save points
00173         stream << "POINT_DATA " << features.cols() << "\n";
00174 
00175         // Loop through all descriptor and dispatch appropriate VTK tags
00176         for(BOOST_AUTO(it, data.descriptorLabels.begin()); it != data.descriptorLabels.end(); it++)
00177         {
00178 
00179                 // handle specific cases
00180                 if(it->text == "normals")
00181                 {
00182                         buildNormalStream(stream, "normals", data);
00183                 }
00184                 else if(it->text == "eigVectors")
00185                 {
00186                         buildTensorStream(stream, "eigVectors", data);
00187                 }
00188                 else if(it->text == "color")
00189                 {
00190                         buildColorStream(stream, "color", data);
00191                 }
00192                 // handle generic cases
00193                 else if(it->span == 1)
00194                 {
00195                         buildScalarStream(stream, it->text, data);
00196                 }
00197                 else if(it->span == 3 || it->span == 2)
00198                 {
00199                         buildVectorStream(stream, it->text, data);
00200                 }
00201                 else
00202                 {
00203                         LOG_WARNING_STREAM("Could not save label named " << it->text << " (dim=" << it->span << ").");
00204                 }
00205         }
00206         
00207         //buildScalarStream(stream, "densities", data);
00208         //buildScalarStream(stream, "obstacles", data);
00209         //buildScalarStream(stream, "inclination", data);
00210         //buildScalarStream(stream, "maxSearchDist", data);
00211         //buildScalarStream(stream, "inliers", data);
00212         //buildScalarStream(stream, "groupId", data);
00213         //buildScalarStream(stream, "simpleSensorNoise", data);
00214         
00215         //buildNormalStream(stream, "normals", data);
00216         
00217         //buildVectorStream(stream, "observationDirections", data);
00218         //buildVectorStream(stream, "eigValues", data);
00219         
00220         //buildTensorStream(stream, "eigVectors", data);
00221         
00222         //buildColorStream(stream, "color", data);
00223 
00224 }
00225 
00226 template<typename T>
00227 void InspectorsImpl<T>::AbstractVTKInspector::dumpMeshNodes(const DataPoints& data, std::ostream& stream)
00228 {
00229         //const Matrix& features(data.features);
00230         const Matrix& descriptors(data.descriptors.transpose());
00231         
00232         assert(descriptors.cols() >= 15);
00233 
00234         stream << "# vtk DataFile Version 3.0\n";
00235         stream << "Triangle mesh\n";
00236         stream << "ASCII\n";
00237         stream << "DATASET POLYDATA\n";
00238 
00239         stream << "POINTS " << descriptors.rows() * 3 << " float\n"; // not optimal: points and edges are drawn several times!
00240         for (int i = 0; i < descriptors.rows(); i++)
00241         {
00242                 // TODO: use getDescriptorByName(nameTag) to access blocks 
00243                 stream << descriptors.block(i, 3, 1, 3) << "\n";
00244                 stream << descriptors.block(i, 6, 1, 3) << "\n";
00245                 stream << descriptors.block(i, 9, 1, 3) << "\n";
00246         }
00247 
00248         //TODO: add centroids...
00249         /*
00250         stream << features.transpose() << "\n";
00251         */
00252 
00253         stream << "POLYGONS " << descriptors.rows() << " " << descriptors.rows() * 4 << "\n";
00254         for (int i = 0; i < descriptors.rows(); i++)
00255         {
00256                 stream << "3 " << (i*3) << " " << (i*3 + 1) << " " << (i*3 + 2) << "\n";
00257         }
00258         
00259         stream << "CELL_DATA " << descriptors.rows() << "\n";
00260 
00261         stream << "NORMALS triangle_normals float\n";
00262         stream << descriptors.block(0, 0, descriptors.rows(), 3) << "\n";
00263 
00264         // TODO: use descriptor labels, particularly to represent normals
00265         //stream << "POINT_DATA " << descriptors.rows() << "\n";
00266         //buildScalarStream(stream, "densities", data);
00267         //buildNormalStream(stream, "normals", data);
00268         //buildVectorStream(stream, "eigValues", data);
00269         //buildTensorStream(stream, "eigVectors", data);
00270         //buildVectorStream(stream, "observationDirections", data);
00271 }
00272 
00273 // FIXME:rethink how we dump stuff (accumulate in a correctly-referenced table, and then dump?) and unify with previous
00274 template<typename T>
00275 void InspectorsImpl<T>::AbstractVTKInspector::dumpDataLinks(
00276         const DataPoints& ref, 
00277         const DataPoints& reading, 
00278         const Matches& matches, 
00279         const OutlierWeights& featureOutlierWeights, 
00280         std::ostream& stream)
00281 {
00282 
00283         const Matrix& refFeatures(ref.features);
00284         const int refPtCount(refFeatures.cols());
00285         //const int featDim(refFeatures.rows());
00286         const Matrix& readingFeatures(reading.features);
00287         const int readingPtCount(readingFeatures.cols());
00288         const int totalPtCount(refPtCount+readingPtCount);
00289         
00290         stream << "# vtk DataFile Version 3.0\n";
00291         stream << "comment\n";
00292         stream << "ASCII\n";
00293         stream << "DATASET POLYDATA\n";
00294         
00295         stream << "POINTS " << totalPtCount << " float\n";
00296         if(refFeatures.rows() == 4)
00297         {
00298                 // reference pt
00299                 stream << refFeatures.topLeftCorner(3, refFeatures.cols()).transpose() << "\n";
00300                 // reading pt
00301                 stream << readingFeatures.topLeftCorner(3, readingFeatures.cols()).transpose() << "\n";
00302         }
00303         else
00304         {
00305                 // reference pt
00306                 stream << refFeatures.transpose() << "\n";
00307                 // reading pt
00308                 stream << readingFeatures.transpose() << "\n";
00309         }
00310         const int knn = matches.ids.rows();
00311         
00312         stream << "LINES " << readingPtCount*knn << " "  << readingPtCount*knn * 3 << "\n";
00313         //int j = 0;
00314         for(int k = 0; k < knn; k++) // knn
00315         {
00316                 for (int i = 0; i < readingPtCount; ++i)
00317                 {
00318                         stream << "2 " << refPtCount + i << " " << matches.ids(k, i) << "\n";
00319                 }
00320         }
00321 
00322         stream << "CELL_DATA " << readingPtCount*knn << "\n";
00323         stream << "SCALARS outlier float 1\n";
00324         stream << "LOOKUP_TABLE default\n";
00325         //stream << "LOOKUP_TABLE alphaOutlier\n";
00326         for(int k = 0; k < knn; k++) // knn
00327         {
00328                 for (int i = 0; i < readingPtCount; ++i) //nb pts
00329                 {
00330                         stream << featureOutlierWeights(k, i) << "\n";
00331                 }
00332         }
00333 
00334         //stream << "LOOKUP_TABLE alphaOutlier 2\n";
00335         //stream << "1 0 0 0.5\n";
00336         //stream << "0 1 0 1\n";
00337 
00338 }
00339 
00340 template<typename T>
00341 void InspectorsImpl<T>::AbstractVTKInspector::dumpDataPoints(const DataPoints& filteredReference, const std::string& name)
00342 {
00343         ostream* stream(openStream(name));
00344         dumpDataPoints(filteredReference, *stream);
00345         closeStream(stream);
00346 }
00347 
00348 template<typename T>
00349 void InspectorsImpl<T>::AbstractVTKInspector::dumpMeshNodes(const DataPoints& filteredReference, const std::string& name)
00350 {
00351         ostream* stream(openStream(name));
00352         dumpMeshNodes(filteredReference, *stream);
00353         closeStream(stream);
00354 }
00355 
00356 template<typename T>
00357 void InspectorsImpl<T>::AbstractVTKInspector::dumpIteration(
00358         const size_t iterationNumber,
00359         const TransformationParameters& parameters,
00360         const DataPoints& filteredReference,
00361         const DataPoints& reading,
00362         const Matches& matches,
00363         const OutlierWeights& outlierWeights, 
00364         const TransformationCheckers& transCheck)
00365 {
00366 
00367         if (bDumpDataLinks){
00368                 ostream* streamLinks(openStream("link", iterationNumber));
00369                 dumpDataLinks(filteredReference, reading, matches, outlierWeights, *streamLinks);
00370                 closeStream(streamLinks);
00371         }
00372         
00373         if (bDumpReading){
00374                 ostream* streamRead(openStream("reading", iterationNumber));
00375                 dumpDataPoints(reading, *streamRead);
00376                 closeStream(streamRead);
00377         }
00378         
00379         if (bDumpReference){
00380                 ostream* streamRef(openStream("reference", iterationNumber));
00381                 dumpDataPoints(filteredReference, *streamRef);
00382                 closeStream(streamRef);
00383         }
00384         
00385         if (!bDumpIterationInfo) return;
00386 
00387         // streamIter must be define by children
00388         assert(streamIter);
00389 
00390         if(iterationNumber == 0)
00391         {
00392                 //Build header
00393                 for(unsigned int j = 0; j < transCheck.size(); j++)
00394                 {
00395                         for(unsigned int i=0; i < transCheck[j]->getConditionVariableNames().size(); i++)
00396                         {
00397                                 if (!(j == 0 && i == 0))
00398                                         *streamIter << ", ";
00399                                 *streamIter << transCheck[j]->getConditionVariableNames()[i] << ", "; 
00400                                 *streamIter << transCheck[j]->getLimitNames()[i]; 
00401                         }
00402                 }
00403                 
00404                 *streamIter << "\n";
00405         }
00406 
00407         
00408         for(unsigned int j = 0; j < transCheck.size(); j++)
00409         {
00410                 for(unsigned int i=0; i < transCheck[j]->getConditionVariables().size(); i++)
00411                 {
00412                 
00413                         if (!(j == 0 && i == 0))
00414                                 *streamIter << ", ";
00415 
00416                         *streamIter << transCheck[j]->getConditionVariables()[i] << ", ";
00417                         *streamIter << transCheck[j]->getLimits()[i]; 
00418                 }
00419         }
00420 
00421         *streamIter << "\n";
00422 }
00423 
00424 template<typename T>
00425 void InspectorsImpl<T>::AbstractVTKInspector::buildGenericAttributeStream(std::ostream& stream, const std::string& attribute, const std::string& nameTag, const DataPoints& cloud, const int forcedDim)
00426 {
00427         if (!cloud.descriptorExists(nameTag))
00428                 return;
00429                 
00430         const BOOST_AUTO(desc, cloud.getDescriptorViewByName(nameTag));
00431         assert(desc.rows() <= forcedDim);
00432 
00433         if(desc.rows() != 0)
00434         {
00435                 if(attribute.compare("COLOR_SCALARS") == 0)
00436                 {
00437                         stream << attribute << " " << nameTag << " " << forcedDim << "\n";
00438                         stream << padWithOnes(desc, forcedDim, desc.cols()).transpose();
00439                 }
00440                 else
00441                 {
00442                         stream << attribute << " " << nameTag << " float\n";
00443                         if(attribute.compare("SCALARS") == 0)
00444                                 stream << "LOOKUP_TABLE default\n";
00445 
00446                         stream << padWithZeros(desc, forcedDim, desc.cols()).transpose();
00447                 }
00448                 stream << "\n";
00449         }
00450 }
00451 
00452 template<typename T>
00453 void InspectorsImpl<T>::AbstractVTKInspector::buildScalarStream(std::ostream& stream,
00454         const std::string& name,
00455         const DataPoints& cloud)
00456 {
00457         buildGenericAttributeStream(stream, "SCALARS", name, cloud, 1);
00458 }
00459 
00460 template<typename T>
00461 void InspectorsImpl<T>::AbstractVTKInspector::buildNormalStream(std::ostream& stream,
00462         const std::string& name,
00463         const DataPoints& cloud)
00464 {
00465         buildGenericAttributeStream(stream, "NORMALS", name, cloud, 3);
00466 }
00467 
00468 template<typename T>
00469 void InspectorsImpl<T>::AbstractVTKInspector::buildVectorStream(std::ostream& stream,
00470         const std::string& name,
00471         const DataPoints& cloud)
00472 {
00473         buildGenericAttributeStream(stream, "VECTORS", name, cloud, 3);
00474 }
00475 
00476 template<typename T>
00477 void InspectorsImpl<T>::AbstractVTKInspector::buildTensorStream(std::ostream& stream,
00478         const std::string& name,
00479         const DataPoints& cloud)
00480 {
00481         buildGenericAttributeStream(stream, "TENSORS", name, cloud, 9);
00482 }
00483 
00484 template<typename T>
00485 void InspectorsImpl<T>::AbstractVTKInspector::buildColorStream(std::ostream& stream,
00486         const std::string& name,
00487         const DataPoints& cloud)
00488 {
00489         buildGenericAttributeStream(stream, "COLOR_SCALARS", name, cloud, 4);
00490 }
00491 
00492 template<typename T>
00493 void InspectorsImpl<T>::AbstractVTKInspector::buildScalarStream(std::ostream& stream,
00494         const std::string& name,
00495         const DataPoints& ref, 
00496         const DataPoints& reading)
00497 {
00498                         
00499         const Matrix descRef(ref.getDescriptorByName(name));    
00500         const Matrix descRead(reading.getDescriptorByName(name));
00501 
00502         if(descRef.rows() != 0 && descRead.rows() != 0)
00503         {
00504                 stream << "SCALARS " << name << " float\n";
00505                 stream << "LOOKUP_TABLE default\n";
00506                 
00507                 stream << padWithZeros(
00508                                 descRef, 1, ref.descriptors.cols()).transpose();
00509                 stream << "\n";
00510                 stream << padWithZeros(
00511                                 descRead, 1, reading.descriptors.cols()).transpose();
00512                 stream << "\n";
00513         }
00514 }
00515 
00516 
00517 template<typename T>
00518 void InspectorsImpl<T>::AbstractVTKInspector::buildNormalStream(std::ostream& stream,
00519         const std::string& name,
00520         const DataPoints& ref, 
00521         const DataPoints& reading)
00522 {
00523                         
00524         const Matrix descRef(ref.getDescriptorByName(name));    
00525         const Matrix descRead(reading.getDescriptorByName(name));
00526 
00527         if(descRef.rows() != 0 && descRead.rows() != 0)
00528         {
00529                 stream << "NORMALS " << name << " float\n";
00530 
00531                 stream << padWithZeros(
00532                                 descRef, 3, ref.descriptors.cols()).transpose();
00533                 stream << "\n";
00534                 stream << padWithZeros(
00535                                 descRead, 3, reading.descriptors.cols()).transpose();
00536                 stream << "\n";
00537         }
00538 }
00539 
00540 
00541 template<typename T>
00542 void InspectorsImpl<T>::AbstractVTKInspector::buildVectorStream(std::ostream& stream,
00543         const std::string& name,
00544         const DataPoints& ref, 
00545         const DataPoints& reading)
00546 {
00547                         
00548         const Matrix descRef(ref.getDescriptorByName(name));    
00549         const Matrix descRead(reading.getDescriptorByName(name));
00550 
00551         if(descRef.rows() != 0 && descRead.rows() != 0)
00552         {
00553                 stream << "VECTORS " << name << " float\n";
00554 
00555                 stream << padWithZeros(
00556                                 descRef, 3, ref.descriptors.cols()).transpose();
00557                 stream << "\n";
00558                 stream << padWithZeros(
00559                                 descRead, 3, reading.descriptors.cols()).transpose();
00560                 stream << "\n";
00561         }
00562 }
00563 
00564 
00565 template<typename T>
00566 void InspectorsImpl<T>::AbstractVTKInspector::buildTensorStream(std::ostream& stream,
00567         const std::string& name,
00568         const DataPoints& ref, 
00569         const DataPoints& reading)
00570 {
00571                         
00572         const Matrix descRef(ref.getDescriptorByName(name));    
00573         const Matrix descRead(reading.getDescriptorByName(name));
00574 
00575         if(descRef.rows() != 0 && descRead.rows() != 0)
00576         {
00577                 stream << "TENSORS " << name << " float\n";
00578 
00579                 stream << padWithZeros(
00580                                 descRef, 9, ref.descriptors.cols()).transpose();
00581                 stream << "\n";
00582                 stream << padWithZeros(
00583                                 descRead, 9, reading.descriptors.cols()).transpose();
00584                 stream << "\n";
00585         }
00586 }
00587 
00588 template<typename T>
00589 typename PointMatcher<T>::Matrix InspectorsImpl<T>::AbstractVTKInspector::padWithZeros(
00590         const Matrix m,
00591         const int expectedRow,
00592         const int expectedCols)
00593 {
00594         assert(m.cols() <= expectedCols || m.rows() <= expectedRow);
00595         if(m.cols() == expectedCols && m.rows() == expectedRow)
00596         {
00597                 return m;
00598         }
00599         else
00600         {
00601                 Matrix tmp = Matrix::Zero(expectedRow, expectedCols); 
00602                 tmp.topLeftCorner(m.rows(), m.cols()) = m;
00603                 return tmp;
00604         }
00605 
00606 }
00607 
00608 template<typename T>
00609 typename PointMatcher<T>::Matrix InspectorsImpl<T>::AbstractVTKInspector::padWithOnes(
00610         const Matrix m,
00611         const int expectedRow,
00612         const int expectedCols)
00613 {
00614         assert(m.cols() <= expectedCols || m.rows() <= expectedRow);
00615         if(m.cols() == expectedCols && m.rows() == expectedRow)
00616         {
00617                 return m;
00618         }
00619         else
00620         {
00621                 Matrix tmp = Matrix::Ones(expectedRow, expectedCols); 
00622                 tmp.topLeftCorner(m.rows(), m.cols()) = m;
00623                 return tmp;
00624         }
00625 
00626 }
00627 
00628 template<typename T>
00629 void InspectorsImpl<T>::AbstractVTKInspector::finish(const size_t iterationCount)
00630 {
00631 }
00632 
00633 
00634 //-----------------------------------
00635 // VTK File inspector
00636 
00637 template<typename T>
00638 InspectorsImpl<T>::VTKFileInspector::VTKFileInspector(const Parameters& params):
00639         AbstractVTKInspector("VTKFileInspector", VTKFileInspector::availableParameters(), params),
00640         baseFileName(Parametrizable::get<string>("baseFileName")),
00641         bDumpIterationInfo(Parametrizable::get<bool>("dumpIterationInfo")),
00642         bDumpDataLinks(Parametrizable::get<bool>("dumpDataLinks")),
00643         bDumpReading(Parametrizable::get<bool>("dumpReading")),
00644         bDumpReference(Parametrizable::get<bool>("dumpReference"))
00645 {
00646 }
00647 
00648 template<typename T>
00649 void InspectorsImpl<T>::VTKFileInspector::init()
00650 {
00651 
00652         if (!bDumpIterationInfo) return;
00653  
00654         ostringstream oss;
00655         oss << baseFileName << "-iterationInfo.csv";
00656         std::cerr << "writing to " << oss.str() << std::endl;
00657 
00658         this->streamIter = new ofstream(oss.str().c_str());
00659         if (this->streamIter->fail())
00660                 throw std::runtime_error("Couldn't open the file \"" + oss.str() + "\". Check if directory exist.");
00661         
00662 }
00663 
00664 template<typename T>
00665 void InspectorsImpl<T>::VTKFileInspector::finish(const size_t iterationCount)
00666 {
00667         if (!bDumpIterationInfo) return;
00668         closeStream(this->streamIter);
00669 }
00670 
00671 template<typename T>
00672 std::ostream* InspectorsImpl<T>::VTKFileInspector::openStream(const std::string& role)
00673 {
00674         string filteredStr = role;
00675         if(role.substr(role.size()-4,4) == ".vtk")
00676                 filteredStr = role.substr(0, role.size()-4);
00677 
00678         ostringstream oss;
00679         if(baseFileName != "")
00680                 oss << baseFileName << "-" << filteredStr << ".vtk";
00681         else
00682                 oss << filteredStr << ".vtk";
00683 
00684         std::cerr << "writing to " << oss.str() << std::endl;
00685         ofstream* file = new ofstream(oss.str().c_str());
00686         if (file->fail())
00687                 throw std::runtime_error("Couldn't open the file \"" + oss.str() + "\". Check if directory exist.");
00688         return file;
00689 }
00690 
00691 template<typename T>
00692 std::ostream* InspectorsImpl<T>::VTKFileInspector::openStream(const std::string& role, const size_t iterationNumber)
00693 {
00694         ostringstream oss;
00695         oss << baseFileName << "-" << role << "-" << iterationNumber << ".vtk";
00696         ofstream* file = new ofstream(oss.str().c_str());
00697         if (file->fail())
00698                 throw std::runtime_error("Couldn't open the file \"" + oss.str() + "\". Check if directory exist.");
00699         return file;
00700 }
00701 
00702 template<typename T>
00703 void InspectorsImpl<T>::VTKFileInspector::closeStream(std::ostream* stream)
00704 {
00705         delete stream;
00706 }
00707 
00708 
00709 
00710 template struct InspectorsImpl<float>::VTKFileInspector;
00711 template struct InspectorsImpl<double>::VTKFileInspector;


upstream_src
Author(s):
autogenerated on Mon Oct 6 2014 10:27:41