MultiObjectTLD.h
Go to the documentation of this file.
00001 /* Copyright (C) 2012 Christian Lutz, Thorsten Engesser
00002  * 
00003  * This file is part of motld
00004  * 
00005  * This program is free software: you can redistribute it and/or modify
00006  * it under the terms of the GNU General Public License as published by
00007  * the Free Software Foundation, either version 3 of the License, or
00008  * (at your option) any later version.
00009  * 
00010  * This program is distributed in the hope that it will be useful,
00011  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00012  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00013  * GNU General Public License for more details.
00014  * 
00015  * You should have received a copy of the GNU General Public License
00016  * along with this program.  If not, see <http://www.gnu.org/licenses/>.
00017  */
00018 
00019 #ifndef MULTIOBJECTTLD_H
00020 #define MULTIOBJECTTLD_H
00021 
00022 #define DEBUG 0
00023 #define TIMING 0
00024 
00025 #include <iostream>
00026 #include <fstream>
00027 #include <vector>
00028 #include "LKTracker.h"
00029 #include "FernFilter.h"
00030 #include "NNClassifier.h"
00031 #include "Matrix.h"
00032 
00033 #define COLOR_MODE_GRAY 0
00034 #define COLOR_MODE_RGB 1
00035 
00037 #define STATUS_LOST 0
00038 #define STATUS_UNSURE 1
00039 #define STATUS_OK 2
00040 
00042 #define DEBUG_DRAW_DETECTIONS 1
00043 #define DEBUG_DRAW_PATCHES 2
00044 #define DEBUG_DRAW_CROSSES 4
00045 
00046 
00047 #define ENABLE_CLUSTERING 1
00048 
00049 
00050 namespace motld {
00051 
00053   struct MOTLDSettings
00054   {
00057     int colorMode;
00059     int patchSize;
00061     int numFerns;
00063     int featuresPerFern;
00065     int scaleMin, scaleMax; 
00067     int bbMin;
00069     bool useColor;
00071     bool allowFastChange;
00073     bool enableFastRotation;
00074 
00076     MOTLDSettings(int cm = COLOR_MODE_GRAY)
00077       {
00078         colorMode = cm;
00079         patchSize = 15;  
00080         numFerns = 8;
00081         featuresPerFern = 10;
00082         scaleMin = -10;
00083         scaleMax = 11;
00084         bbMin = 24;
00085         useColor = false;
00086         allowFastChange = false;
00087         enableFastRotation = false;
00088       }
00089   };
00090 
00092   class MultiObjectTLD
00093   {
00094   public:
00100     MultiObjectTLD(const int width, const int height, const MOTLDSettings& settings = MOTLDSettings())
00101       : ivWidth(width), ivHeight(height), 
00102         ivColorMode(settings.colorMode), ivPatchSize(settings.patchSize), ivBBmin(settings.bbMin), 
00103         ivUseColor(settings.useColor && ivColorMode == COLOR_MODE_RGB), 
00104         ivEnableFastRotation(settings.enableFastRotation), ivLKTracker(LKTracker(width, height)), 
00105         ivNNClassifier(NNClassifier(width, height, ivPatchSize, ivUseColor, settings.allowFastChange)), 
00106       ivFernFilter(FernFilter(width, height, settings.numFerns, settings.featuresPerFern)),
00107       ivNObjects(0), ivLearningEnabled(true), ivNLastDetections(0) { };
00108 
00112     void addObject(ObjectBox b);
00118     void addObjects(std::vector<ObjectBox> obs);
00125     void processFrame(unsigned char * img);
00127     void enableLearning(bool enable = true) { ivLearningEnabled = enable; };
00135     int getStatus(const int objId = 0) const;
00137     bool getValid() const { return ivNObjects > 0 ? ivValid[0] : false; };
00139     ObjectBox getObjectBox() const { return ivCurrentBoxes[0]; };
00141     std::vector<ObjectBox> getObjectBoxes() const { return ivCurrentBoxes; };
00155     void writeDebugImage(unsigned char * src, char * filename, int mode = 255) const;
00157     void getDebugImage(unsigned char * src, Matrix& rMat, Matrix& gMat, Matrix& bMat, int mode = 255) const;
00158   
00160     static MultiObjectTLD loadClassifier(const char * filename);
00162     void saveClassifier(const char * filename) const;
00163   
00164   private:
00165     int ivWidth;
00166     int ivHeight;
00167     //MOTLDSettings ivSettings;
00168     int ivColorMode;
00169     int ivPatchSize;
00170     int ivBBmin;
00171     bool ivUseColor;
00172     bool ivEnableFastRotation;
00173     LKTracker ivLKTracker;
00174     NNClassifier ivNNClassifier;
00175     FernFilter ivFernFilter;
00176 
00177     int ivNObjects;
00178     float ivAspectRatio;
00179     std::vector<ObjectBox> ivCurrentBoxes;
00180     std::vector<bool> ivDefined;
00181     std::vector<bool> ivValid;
00182     std::vector<NNPatch> ivCurrentPatches;
00183     bool ivLearningEnabled;
00184   
00185     Matrix ivCurImage;
00186     unsigned char * ivCurImagePtr;
00187     std::vector<FernDetection> ivLastDetections;
00188     std::vector<FernDetection> ivLastDetectionClusters;
00189     int ivNLastDetections;
00190     void clusterDetections(float threshold);
00191   
00192     MultiObjectTLD (int width, int height, int colorMode, int patchSize, int bbMin, bool useColor,
00193                     bool fastRotation, NNClassifier nnc, FernFilter ff, int nObjects, 
00194                     float aspectRatio, bool learningEnabled);
00195   };
00196 
00197 /**************************************************************************************************
00198  * IMPLEMENTATION                                                                                 *
00199  **************************************************************************************************/
00200 
00201   void MultiObjectTLD::addObject(ObjectBox b)
00202   {
00203     std::vector<ObjectBox> obs;
00204     obs.push_back(b);
00205     addObjects(obs);
00206   }
00207 
00208   void MultiObjectTLD::addObjects(std::vector<ObjectBox> obs)
00209   {
00210     int n = obs.size(); 
00211     if (n == 0)
00212       return;
00213     for (int i = 0; i < n; i++)
00214     {
00215       obs[i].objectId = ivNObjects + i;
00216       if (obs[i].objectId == 0)
00217         ivAspectRatio = obs[i].width / (float)obs[i].height;
00218       else
00219       { // Force aspect ratio to be the same as of the first box
00220         float centerx = obs[i].x + 0.5 * obs[i].width,
00221           centery = obs[i].y + 0.5 * obs[i].height;
00222         obs[i].width = sqrt(ivAspectRatio * obs[i].width * obs[i].height);
00223         obs[i].height = obs[i].width / ivAspectRatio;
00224         obs[i].x = centerx - 0.5 * obs[i].width;
00225         obs[i].y = centery - 0.5 * obs[i].height;
00226       }
00227     }
00228 
00229     if (ivNObjects == 0)
00230     { 
00231       if (ivCurImage.size() == 0)
00232       { 
00233         std::cerr << "Please insert an image via processFrame() before adding objects!" << std::endl;
00234         return;
00235       }
00236       // This is the first frame
00237       ivLKTracker.initFirstFrame(ivCurImage);
00238       std::vector<Matrix> initNegPatches = ivFernFilter.addObjects(ivCurImage, obs);
00239       for (size_t i = 0; i < initNegPatches.size(); i++)
00240       {
00241         NNPatch p(initNegPatches[i]);
00242         ivNNClassifier.trainNN(p, -1, false);
00243       }  
00244 #if TIMING
00245       std::ofstream t_file("runtime.txt");
00246       t_file << "tracker\tdetector\tnn\tlearner\tsum";
00247       t_file.close();
00248 #endif
00249     }else 
00250       ivFernFilter.addObjects(ivCurImage, obs);
00251   
00252     for (int i = 0; i < n; i++)
00253     {
00254       ivCurrentBoxes.push_back(obs[i]);
00255       ivDefined.push_back(true);
00256       ivValid.push_back(true);
00257       NNPatch p(obs[i], ivCurImage, ivPatchSize, ivUseColor ? ivCurImagePtr : NULL, ivWidth, ivHeight);
00258       ivCurrentPatches.push_back(p);
00259       ivNNClassifier.addObject(p);
00260     }
00261     ivNObjects += n;
00262   }
00263 
00264   int MultiObjectTLD::getStatus(const int objId) const
00265   {
00266     if (objId >= ivNObjects)
00267       return STATUS_LOST;
00268     if (ivValid[objId])
00269       return STATUS_OK;
00270     if (ivDefined[objId])
00271       return STATUS_UNSURE;
00272     return STATUS_LOST;
00273   }
00274 
00275   void MultiObjectTLD::processFrame(unsigned char * img)
00276   {
00277     ivCurImagePtr = img;
00278     ivCurImage = Matrix(ivWidth, ivHeight);
00279     /*Matrix curImageR;
00280       Matrix curImageG;
00281       Matrix curImageB;*/
00282     if (ivColorMode == COLOR_MODE_RGB)
00283     {
00284       /*
00285         int size = ivHeight * ivWidth;
00286         curImageR.setSize(ivWidth, ivHeight); curImageR.copyFromCharArray(img);
00287         curImageG.setSize(ivWidth, ivHeight); curImageG.copyFromCharArray(img + size);
00288         curImageB.setSize(ivWidth, ivHeight); curImageB.copyFromCharArray(img + 2*size);
00289         ivCurImage.fromRGB(curImageR, curImageG, curImageB);
00290       */
00291       ivCurImage.fromRGB(img);
00292     }
00293     else //if(ivColorMode == COLOR_MODE_GRAY)
00294     {
00295       ivCurImage.copyFromCharArray(img);
00296     }
00297     if (ivNObjects <= 0)
00298       return;
00299     std::vector<NNPatch*> detectionPatches;
00300 #if TIMING
00301     int t_start = getTime(), t_end = 0, t_tracker = 0, t_detector = 0, t_nn = 0, t_learner = 0;
00302 #endif
00303     // TRACKER
00304     ivLKTracker.processFrame(ivCurImage, ivCurrentBoxes, ivDefined);
00305 #if TIMING
00306     t_end = getTime(); t_tracker = t_end - t_start;
00307 #endif
00308 #if DEBUG 
00309 #if TIMING
00310     std::cout << "\tneeded " << t_tracker;
00311 #endif
00312     std::cout << "ms\ttConf = {";    
00313 #endif
00314     std::vector<float> tConf;
00315     for (int o = 0; o < ivNObjects; o++)
00316     {
00317       if (ivDefined[o])
00318       {
00319         ivCurrentPatches[o] = NNPatch(ivCurrentBoxes[o], ivCurImage, ivPatchSize,
00320                                       ivUseColor ? img : NULL, ivWidth, ivHeight);
00321         tConf.push_back(ivNNClassifier.getConf(ivCurrentPatches[o], o, true));
00322         ivValid[o] = tConf[o] > 0.65;
00323       }else{
00324         tConf.push_back(0);
00325         ivValid[o] = false;
00326       }
00327 #if DEBUG
00328       std::cout << (o?", ":"") << tConf[o];
00329 #endif
00330     }
00331 #if DEBUG
00332     std::cout << "}" << std::endl;
00333 #endif
00334 #if TIMING
00335     t_start = getTime();
00336 #endif 
00337   
00338     // DETECTOR
00339     ivLastDetections = ivFernFilter.scanPatch(ivCurImage);
00340 #if TIMING
00341     t_end = getTime();
00342     t_detector = t_end - t_start;
00343     t_start = t_end;
00344 #endif
00345     ivNLastDetections = ivLastDetections.size();
00346     ivLastDetectionClusters.clear();
00347     if (ivNLastDetections > 0)
00348     {
00349       for (int i = 0; i < ivNLastDetections; ++i)
00350       {
00351         detectionPatches.push_back(new NNPatch(ivLastDetections[i].patch));
00352         ivLastDetections[i].confidence = 
00353           ivNNClassifier.getConf(*detectionPatches[i], ivLastDetections[i].box.objectId, false,
00354                                  ivLastDetections[i].box, ivUseColor ? img : NULL, ivWidth, ivHeight);
00355       }
00356 #if ENABLE_CLUSTERING
00357       clusterDetections(0.5);
00358 #endif
00359       for (int o = 0; o < ivNObjects; o++)
00360       {
00361         double bestConf = -1;
00362         int bestId = -1;
00363 #if ENABLE_CLUSTERING
00364         NNPatch bestCluster;      
00365         for (size_t i = 0; i < ivLastDetectionClusters.size(); ++i)
00366           if (ivLastDetectionClusters[i].box.objectId == o)
00367           {
00368             NNPatch curPatch(ivLastDetectionClusters[i].box, ivCurImage, ivPatchSize,
00369                              ivUseColor ? img : NULL, ivWidth, ivHeight);
00370             ivLastDetectionClusters[i].confidence = ivNNClassifier.getConf(curPatch, o, true);
00371             if (ivLastDetectionClusters[i].confidence > bestConf)
00372             {
00373               bestConf = ivLastDetectionClusters[i].confidence;
00374               bestId = i;
00375               bestCluster = curPatch;
00376             }
00377           }
00378         if (bestConf > tConf[o] && bestConf > 0.65 && (!ivDefined[o] 
00379                                                        || rectangleOverlap(ivLastDetectionClusters[bestId].box, ivCurrentBoxes[o]) < 0.7))
00380         {
00381           //if there is a (better) cluster of detections away from tracker result / and tracker failed
00382           ivCurrentBoxes[o] = ivLastDetectionClusters[bestId].box;    
00383           ivCurrentPatches[o] = bestCluster;  
00384 #if DEBUG  
00385           std::cout << "DETECTOR: changed object " << o << " box to (" 
00386                     << round(ivCurrentBoxes[o].x) << "," << round(ivCurrentBoxes[o].y) << ", " 
00387                     << round(ivCurrentBoxes[o].width) << "," << round(ivCurrentBoxes[o].height) 
00388                     << ") with conf=" << bestConf << std::endl;
00389 #endif
00390           ivDefined[o] = true;
00391           if (bestConf > 0.65)
00392             ivValid[o] = true;      
00393         }
00394 #else //no clustering, process detections directly
00395         for (unsigned int i = 0; i < ivLastDetections.size(); ++i)
00396           if (ivLastDetections[i].box.objectId == o && ivLastDetections[i].confidence > bestConf)
00397           {
00398             bestConf = ivLastDetections[i].confidence;
00399             bestId = i;
00400           }
00401         if (bestConf > tConf[o] && bestConf > 0.7 && (!ivDefined[o] 
00402                                                       || rectangleOverlap(ivLastDetections[bestId].box, ivCurrentBoxes[o]) < 0.9))
00403         {
00404           //if there is a (better) detection away from tracker result
00405           ivCurrentBoxes[o] = ivLastDetections[bestId].box;    
00406           ivCurrentPatches[o] = *detectionPatches[bestId];     
00407 #if DEBUG 
00408           std::cout << "DETECTOR: changed object " << o << " box to (" 
00409                     << round(ivCurrentBoxes[o].x) << "," << round(ivCurrentBoxes[o].y) << ", " 
00410                     << round(ivCurrentBoxes[o].width) << "," << round(ivCurrentBoxes[o].height) 
00411                     << ") with conf=" << bestConf << std::endl;
00412 #endif
00413           ivDefined[o] = true;
00414           if (bestConf > 0.65)
00415             ivValid[o] = true;      
00416         }
00417 #endif
00418         else if (ivDefined[o]) // tracker defined
00419         {
00420           //weighted average (10x tracker + close (overlap>0.7) detections)  
00421           int tmpn = 10;
00422           float tmpx = 10*ivCurrentBoxes[o].x, tmpy = 10*ivCurrentBoxes[o].y, 
00423             tmpw = 10*ivCurrentBoxes[o].width, tmph = 10*ivCurrentBoxes[o].height;
00424           for (int i = 0; i < ivNLastDetections; ++i)
00425           {
00426             if (ivLastDetections[i].box.objectId == o)
00427             {
00428               float overlap = rectangleOverlap(ivCurrentBoxes[o], ivLastDetections[i].box);
00429               if (overlap > 0.7)
00430               {
00431                 if (ivLastDetections[i].confidence > 0.6)
00432                 {
00433                   tmpn++;
00434                   tmpx += ivLastDetections[i].box.x;
00435                   tmpy += ivLastDetections[i].box.y;
00436                   tmpw += ivLastDetections[i].box.width;
00437                   tmph += ivLastDetections[i].box.height;
00438                 }            
00439               }
00440             }
00441           }  
00442           if (tmpn > 10)
00443           {
00444             ivCurrentBoxes[o].x = tmpx / tmpn;
00445             ivCurrentBoxes[o].y = tmpy / tmpn;
00446             ivCurrentBoxes[o].width = tmpw / tmpn;
00447             ivCurrentBoxes[o].height = tmph / tmpn;
00448             ivCurrentPatches[o] = NNPatch(ivCurrentBoxes[o], ivCurImage, ivPatchSize,
00449                                           ivUseColor ? img : NULL, ivWidth, ivHeight);
00450             tConf[o] = ivNNClassifier.getConf(ivCurrentPatches[o], o, false);
00451             ivValid[o] = tConf[o] > 0.65;
00452 #if DEBUG
00453             std::cout << "\ttracker[" << o << "] result averaged with " << (tmpn-10) 
00454                       << " close detections,\tnew conf = " << tConf[o] << std::endl;
00455 #endif
00456           }    
00457           if (tConf[o] < 0.5)
00458             ivDefined[o] = false;
00459         }      
00460 #if DEBUG
00461         else if (bestConf > 0)
00462           std::cout << "\tbest cluster for object " << o << ": conf=" << bestConf << std::endl;
00463 #endif
00464       }// end for(o)
00465     }// end if(ivNLastDetections > 0)
00466 #if TIMING
00467     t_end = getTime();
00468     t_nn = t_end - t_start;
00469     t_start = t_end;
00470 #endif
00471   
00472     // LEARNER
00473     if (ivEnableFastRotation)
00474       ivNNClassifier.removeWarps();
00475     std::vector<ObjectBox> learnBoxes;
00476     // train positive examples
00477     for (int o = 0; o < ivNObjects; o++)
00478     {
00479       ivCurrentBoxes[o].objectId = o;
00480       if (ivValid[o] && !(ivCurrentBoxes[o].x < 0 || ivCurrentBoxes[o].y < 0
00481                           || ivCurrentBoxes[o].x + ivCurrentBoxes[o].width >= ivWidth-1
00482                           || ivCurrentBoxes[o].y + ivCurrentBoxes[o].height >= ivHeight-1)
00483           && ivCurrentBoxes[o].width >= ivBBmin && ivCurrentBoxes[o].height >= ivBBmin)
00484       {
00485         learnBoxes.push_back(ivCurrentBoxes[o]);
00486         if (ivLearningEnabled)
00487           ivNNClassifier.trainNN(ivCurrentPatches[o], o, true);
00488       }
00489     }
00490     // train negative examples
00491     if (ivLearningEnabled)
00492     {
00493       for (int i = 0; i < ivNLastDetections; ++i)
00494       {
00495         bool learn = true;
00496         for (int o = 0; o < ivNObjects; o++)
00497           if(!ivDefined[ivLastDetections[i].box.objectId] 
00498              || (ivDefined[o] && rectangleOverlap(ivCurrentBoxes[o], ivLastDetections[i].box) > 0.3))
00499           {
00500             learn = false;
00501             break;
00502           }
00503         if (learn)
00504           ivNNClassifier.trainNN(*detectionPatches[i], ivLastDetections[i].box.objectId, false);
00505       }
00506     }
00507 #if TIMING
00508     t_end = getTime();
00509     t_nn += t_end - t_start;
00510     t_start = t_end;
00511 #endif
00512     // update fern filter
00513     std::vector<Matrix> warpedPatches = ivFernFilter.learn(ivCurImage, learnBoxes, !ivLearningEnabled);
00514 #if TIMING
00515     t_end = getTime();
00516     t_learner = t_end - t_start;
00517 #endif
00518     if (ivEnableFastRotation)
00519       for (size_t i = 0; i < learnBoxes.size(); ++i)
00520       {
00521         ivNNClassifier.trainNN(NNPatch(warpedPatches[2*i]), learnBoxes[i].objectId, true, true);
00522         ivNNClassifier.trainNN(NNPatch(warpedPatches[2*i+1]), learnBoxes[i].objectId, true, true);
00523       }
00524   
00525     // clean up
00526     for (int i = 0; i < ivNLastDetections; ++i)
00527       delete detectionPatches[i];
00528     detectionPatches.clear();
00529 #if TIMING
00530     // save time information (for analyzing performance)
00531     std::ofstream t_file("runtime.txt", std::ios_base::out | std::ios_base::app);  
00532     t_file << std::endl << t_tracker << "\t" << t_detector << "\t" << t_nn << "\t" << t_learner 
00533            << "\t" << (t_tracker + t_detector + t_nn + t_learner);
00534     t_file.close();
00535 #endif
00536   }
00537 
00538   void MultiObjectTLD::clusterDetections(float threshold)
00539   {
00540     if (ivNLastDetections == 0)
00541       return;
00542     if (ivNLastDetections == 1)
00543     {
00544       ivLastDetectionClusters = ivLastDetections;
00545       return;
00546     }
00547     //init
00548     int* clId = new int[ivNLastDetections];
00549     std::vector<ObjectBox> clBox;
00550     std::vector<int> clN;
00551     int nClusters = 1;
00552     clBox.push_back(ivLastDetections[0].box);
00553     clN.push_back(ivNLastDetections);
00554     for (int i = 0; i < ivNLastDetections; ++i)
00555       clId[i] = 0;
00556     bool terminated = false;
00557     int terminationcounter = 0;
00558     while (!terminated && terminationcounter < 100)
00559     {
00560       terminationcounter++;
00561       // compute new cluster means
00562       for (int i = 0; i < nClusters; ++i)
00563       {
00564         clBox[i].x = clBox[i].y = clBox[i].width = clBox[i].height = 0;
00565         clN[i] = 0;
00566       }
00567       for (int i = 0; i < ivNLastDetections; ++i)
00568       {
00569         clBox[clId[i]].x += ivLastDetections[i].box.x;
00570         clBox[clId[i]].y += ivLastDetections[i].box.y;
00571         clBox[clId[i]].width += ivLastDetections[i].box.width;
00572         clBox[clId[i]].height += ivLastDetections[i].box.height;
00573         clN[clId[i]]++;
00574       }
00575       for (int i = 0; i < nClusters; ++i)
00576       {
00577         if (!clN[i])
00578         {
00579 #if DEBUG
00580           std::cout << "there was an empty cluster" << std::endl;
00581 #endif
00582           continue; // should not happen, just to be sure
00583         }
00584         clBox[i].x /= clN[i]; 
00585         clBox[i].y /= clN[i];
00586         clBox[i].width /= clN[i]; 
00587         clBox[i].height /= clN[i];
00588       }
00589     
00590       // compute new assignments
00591       terminated = true;
00592       float minOverlap = 2.0f;
00593       int minOverlapId = -1;
00594       for (int i = 0; i < ivNLastDetections; ++i)
00595       {
00596         int maxOverlapId = -1;
00597         float maxOverlap = -2;
00598         // search for nearest cluster with same objectId
00599         for (int j = 0; j < nClusters; ++j){
00600           float overlap = -1;
00601           if (clBox[j].objectId == ivLastDetections[i].box.objectId)
00602             overlap = rectangleOverlap(clBox[j], ivLastDetections[i].box);
00603           if (overlap > maxOverlap){
00604             maxOverlap = overlap;
00605             maxOverlapId = j;
00606           }
00607         }
00608         if (clId[i] != maxOverlapId)
00609         {
00610           clId[i] = maxOverlapId;
00611           terminated = false;
00612         }
00613         if (maxOverlap < minOverlap)
00614         {
00615           minOverlap = maxOverlap;
00616           minOverlapId = i;
00617         }
00618       } 
00619       // no assignment changes
00620       if (terminated)
00621       { 
00622         if (minOverlap >= threshold)
00623         {
00624           terminated = true;
00625           break;
00626         }else{
00627           // add new cluster (the box with minimal overlap)
00628           clId[minOverlapId] = nClusters;
00629           clBox.push_back(ivLastDetections[minOverlapId].box);   
00630           clN.push_back(1);
00631           nClusters++;
00632           terminated = false;
00633         }
00634       }
00635     }
00636     for (int i = 0; i < nClusters; ++i)
00637     {
00638       if (!clN[i])
00639       {
00640 #if DEBUG
00641         std::cout << "Clustering: unused cluster!" << std::endl;
00642 #endif
00643         continue; // should not happen, just to be sure
00644       }
00645       FernDetection clDet = {clBox[i], Matrix(), 0, 0, 0, 0};
00646       ivLastDetectionClusters.push_back(clDet);
00647     }
00648     delete[] clId;
00649   }
00650 
00651   void MultiObjectTLD::writeDebugImage(unsigned char * src, char* filename, int mode) const
00652   { 
00653     Matrix rMat;
00654     Matrix gMat;
00655     Matrix bMat;
00656     getDebugImage(src, rMat, gMat, bMat, mode);
00657     writePPM(filename, rMat, gMat, bMat);  
00658   }
00659 
00660   void MultiObjectTLD::getDebugImage(unsigned char * src, Matrix& rMat, Matrix& gMat, Matrix& bMat, int mode) const
00661   { 
00662     int size = ivHeight * ivWidth;
00663     rMat.setSize(ivWidth, ivHeight); 
00664     rMat.copyFromCharArray(src);
00665     gMat.setSize(ivWidth, ivHeight); 
00666     gMat.copyFromCharArray(src + (ivColorMode == COLOR_MODE_RGB ? size : 0));
00667     bMat.setSize(ivWidth, ivHeight); 
00668     bMat.copyFromCharArray(src + (ivColorMode == COLOR_MODE_RGB ? 2*size : 0));
00669   
00670     if (mode & DEBUG_DRAW_DETECTIONS)
00671     {
00672       for (std::vector<FernDetection>::const_iterator it = ivLastDetections.begin(); 
00673            it < ivLastDetections.end(); ++it)
00674       {
00675         gMat.drawDashedBox(it->box, 255, 3, true);
00676         if (ivNObjects > 1)
00677           gMat.drawNumber(it->box.x, it->box.y, it->box.objectId);
00678       }
00679     
00680       for (std::vector<FernDetection>::const_iterator it = ivLastDetectionClusters.begin(); 
00681            it < ivLastDetectionClusters.end(); ++it)
00682       {
00683         bMat.drawDashedBox(it->box, 255);
00684         gMat.drawDashedBox(it->box, 0);
00685       }
00686     }
00687   
00688     for (int i = 0; i < ivNObjects; i++)
00689       if (ivDefined[i])
00690       {
00691         rMat.drawBox(ivCurrentBoxes[i], 255);
00692         gMat.drawBox(ivCurrentBoxes[i], (ivValid[i] ? 0 : 255));
00693         bMat.drawBox(ivCurrentBoxes[i], 0);
00694         if (ivNObjects > 1)
00695         {
00696           int numberposx = ivCurrentBoxes[i].x + ivCurrentBoxes[i].width - 1,
00697             numberposy = ivCurrentBoxes[i].y + ivCurrentBoxes[i].height - 8;
00698           rMat.drawNumber(numberposx, numberposy, i, 255);
00699           gMat.drawNumber(numberposx, numberposy, i, (ivValid[i] ? 0 : 255));
00700           bMat.drawNumber(numberposx, numberposy, i, 0);
00701         }
00702       }
00703   
00704     if (mode & DEBUG_DRAW_CROSSES)
00705     {
00706       const std::vector<int> * debugPoints = ivLKTracker.getDebugPoints();
00707       for (unsigned int i = 0; i < debugPoints->size(); i += 2)
00708       {
00709         rMat.drawCross((*debugPoints)[i], (*debugPoints)[i+1], 0);
00710         gMat.drawCross((*debugPoints)[i], (*debugPoints)[i+1], 0);
00711         bMat.drawCross((*debugPoints)[i], (*debugPoints)[i+1], 255);    
00712       }
00713     }
00714   
00715     const std::vector<std::vector<NNPatch> > * posPatches = ivNNClassifier.getPosPatches();
00716     const std::vector<NNPatch> * negPatches = ivNNClassifier.getNegPatches();
00717     
00718     unsigned int picspercol = ivHeight / ivPatchSize;  
00719 
00720     if (mode & DEBUG_DRAW_PATCHES)
00721       for (unsigned int i = 0; i < negPatches->size() && i < 3*picspercol; ++i)
00722       {
00723         int x = ivPatchSize * (i/picspercol), y = ivPatchSize * (i%picspercol);
00724         rMat.drawPatch((*negPatches)[i].patch, x, y, (*negPatches)[i].avg);
00725         gMat.drawPatch((*negPatches)[i].patch, x, y, (*negPatches)[i].avg);
00726         bMat.drawPatch((*negPatches)[i].patch, x, y, (*negPatches)[i].avg);
00727       }
00728   
00729     bool drawhistograms = posPatches->size() > 0 && (*posPatches)[0].size() > 0 
00730       && (*posPatches)[0][0].histogram != NULL;
00731     int startx = ivWidth;
00732     for (unsigned int p = 0; p < posPatches->size(); p++)
00733     {
00734       for (unsigned int i = 0; i < (*posPatches)[p].size() && i < 3*picspercol; ++i)
00735       {
00736         if ((i%picspercol) == 0)
00737           startx -= ivPatchSize * (1 + drawhistograms);
00738         if (startx < 0)
00739           return;
00740         int y = ivPatchSize * (i%picspercol);
00741         if (drawhistograms && (*posPatches)[p][i].histogram != NULL)
00742         {
00743           rMat.drawHistogram((*posPatches)[p][i].histogram, startx+ivPatchSize, y, 255, 7, ivPatchSize);
00744           gMat.drawHistogram((*posPatches)[p][i].histogram, startx+ivPatchSize, y, 0, 7, ivPatchSize);
00745           bMat.drawHistogram((*posPatches)[p][i].histogram, startx+ivPatchSize, y, 0, 7, ivPatchSize);
00746         }
00747         rMat.drawPatch((*posPatches)[p][i].patch, startx, y, (*posPatches)[p][i].avg);
00748         gMat.drawPatch((*posPatches)[p][i].patch, startx, y, (*posPatches)[p][i].avg);
00749         bMat.drawPatch((*posPatches)[p][i].patch, startx, y, (*posPatches)[p][i].avg);
00750         if (!(mode & DEBUG_DRAW_PATCHES))
00751           break;
00752       }
00753     }
00754   }
00755 
00756   MultiObjectTLD::MultiObjectTLD(int width, int height, int colorMode, int patchSize, int bbMin, 
00757                                  bool useColor, bool fastRotation, NNClassifier nnc, FernFilter ff, 
00758                                  int nObjects, float aspectRatio, bool learningEnabled)
00759     : ivWidth(width), ivHeight(height), ivColorMode(colorMode), ivPatchSize(patchSize), 
00760       ivBBmin(bbMin), ivUseColor(useColor), ivEnableFastRotation(fastRotation),
00761       ivLKTracker(LKTracker(width, height)), ivNNClassifier(nnc), ivFernFilter(ff), 
00762     ivNObjects(nObjects), ivAspectRatio(aspectRatio), 
00763     ivLearningEnabled(learningEnabled), ivNLastDetections(0)
00764   {
00765 #if TIMING
00766     std::ofstream t_file("runtime.txt");
00767     t_file << "tracker\tdetector\tnn\tlearner\tsum";
00768     t_file.close();
00769 #endif
00770     ivCurrentBoxes = std::vector<ObjectBox>(nObjects);
00771     ivDefined = std::vector<bool>(nObjects, false);
00772     ivValid = std::vector<bool>(nObjects, false);
00773     ivCurrentPatches = std::vector<NNPatch>(nObjects);
00774   }
00775 
00776 
00777   void MultiObjectTLD::saveClassifier(const char* filename) const
00778   {
00779     std::ofstream fileOutput(filename, std::ios::out | std::ios::binary);
00780   
00781     // 1. General motld Data
00782     fileOutput.write((char*)&ivWidth, sizeof(int));
00783     fileOutput.write((char*)&ivHeight, sizeof(int));
00784     fileOutput.write((char*)&ivColorMode, sizeof(int));
00785     fileOutput.write((char*)&ivPatchSize, sizeof(int));
00786     fileOutput.write((char*)&ivBBmin, sizeof(int));
00787     fileOutput.write((char*)&ivUseColor, sizeof(bool));
00788     fileOutput.write((char*)&ivEnableFastRotation, sizeof(bool));
00789     fileOutput.write((char*)&ivNObjects, sizeof(int));
00790     fileOutput.write((char*)&ivAspectRatio, sizeof(float));
00791     fileOutput.write((char*)&ivLearningEnabled, sizeof(bool));
00792   
00793     // 2. nnClassifier
00794     ivNNClassifier.saveToStream(fileOutput);
00795   
00796     // 3. FernFilter
00797     ivFernFilter.saveToStream(fileOutput);
00798   
00799     // eof string
00800     const char * endstring = "eNd!";
00801     fileOutput.write(endstring, 4*sizeof(char));
00802     fileOutput.close();
00803   }
00804 
00805   MultiObjectTLD MultiObjectTLD::loadClassifier(const char* filename)
00806   {
00807     std::ifstream fileInput(filename, std::ios::in | std::ios::binary);
00808   
00809     // 1. General motld Data
00810     int width, height, colorMode, patchSize, bbMin, nObjects; 
00811     float aspectRatio; bool learningEnabled, useColor, fastRotation;
00812     fileInput.read((char*)&width, sizeof(int));
00813     fileInput.read((char*)&height, sizeof(int));
00814     fileInput.read((char*)&colorMode, sizeof(int));
00815     fileInput.read((char*)&patchSize, sizeof(int));
00816     fileInput.read((char*)&bbMin, sizeof(int));
00817     fileInput.read((char*)&useColor, sizeof(bool));
00818     fileInput.read((char*)&fastRotation, sizeof(bool));
00819     fileInput.read((char*)&nObjects, sizeof(int));
00820     fileInput.read((char*)&aspectRatio, sizeof(float));
00821     fileInput.read((char*)&learningEnabled, sizeof(bool));
00822   
00823     // 2. nnClassifier
00824     NNClassifier nnc(fileInput); 
00825   
00826     // 3. FernFilter
00827     FernFilter ff = FernFilter::loadFromStream(fileInput);
00828   
00829     // parse eof string
00830     char * endstring = new char[5]; endstring[4] = '\0';
00831     fileInput.read(endstring, 4*sizeof(char));
00832     if (endstring[0] == 'e' && endstring[1] == 'N' && 
00833         endstring[2] == 'd' && endstring[3] == '!') 
00834     {
00835       std::cout << "File sucessfully loaded!" << std::endl;
00836     }
00837     else
00838     {
00839       std::cerr << "Error on loading file!" << std::endl;
00840     }
00841   
00842     fileInput.close();
00843   
00844     return MultiObjectTLD(width, height, colorMode, patchSize, bbMin, useColor, fastRotation, nnc, ff, 
00845                           nObjects, aspectRatio, learningEnabled);
00846   }
00847 
00848 }
00849 
00850 #endif // MULTIOBJECTTLD_H
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


motld
Author(s): Jost Tobias Springenberg, Jan Wuelfing
autogenerated on Wed Dec 26 2012 16:24:49