FLANNMatcher.cpp
Go to the documentation of this file.
00001 /*******************************************************************************
00002  *  FLANNMatcher.cpp
00003  *
00004  *  (C) 2007 AG Aktives Sehen <agas@uni-koblenz.de>
00005  *           Universitaet Koblenz-Landau
00006  *
00007  *  Additional information:
00008  *  $Id: $
00009  *******************************************************************************/
00010 
00011 #include "FLANNMatcher.h"
00012 
00013 // #include "Architecture/Tracer/Tracer.h" // TODO use ros instead
00014 // #include "Architecture/Singleton/Clock.h" // TODO
00015 
00016 #include "Workers/Math/vec2.h"
00017 
00018 #include <assert.h>
00019 #include <map>
00020 #include <list>
00021 #include <math.h>
00022 
00023 using namespace std;
00024 
00025 #define THIS FLANNMatcher
00026 
00027 THIS::THIS ()
00028 {
00029     m_hasIndex = false;
00030     m_descriptorLength = 64; // May differ, set when building an index
00031 
00032     getFlannParameters().target_precision = 0.95;
00033     getFlannParameters().log_level = FLANN_LOG_INFO;
00034     getFlannParameters().algorithm = KDTREE;
00035     getFlannParameters().checks = 32;
00036     getFlannParameters().trees = 8;
00037     getFlannParameters().branching = 32;
00038     getFlannParameters().iterations = 7;
00039     getFlannParameters().target_precision = -1;
00040 
00041     m_FlannModelData = 0;
00042 
00043     m_Log << "FLANNMatcher created\n";
00044 }
00045 
00046 THIS::THIS ( const FLANNMatcher& other )
00047 {
00048   operator= ( other );
00049 }
00050 
00051 THIS& THIS::operator= ( const FLANNMatcher& other )
00052 {
00053   if ( this == &other )
00054   {
00055     return *this;
00056   }
00057 
00058   m_Matches = other.m_Matches;
00059 
00060   //m_Log = other.m_Log;
00061 
00062   m_flannIndex = other.m_flannIndex;
00063   m_flannParams = other.m_flannParams;
00064   m_hasIndex = other.m_hasIndex;
00065   m_descriptorLength = other.m_descriptorLength;
00066 
00067   return *this;
00068 }
00069 
00070 THIS::~THIS()
00071 {
00072   clearFLANNMembers();
00073   delete[] m_FlannModelData;
00074 }
00075 
00076 void THIS::createIndex( std::vector< KeyPoint >* keyPoints ){
00077   if(keyPoints->size()==0)
00078   {
00079     // TRACE_ERROR("Cannot create index, because there are no keypoints."); // TODO use ROS
00080     return;
00081   }
00082   clearFLANNMembers();
00083   if(keyPoints->size() != 0){
00084     m_descriptorLength = keyPoints->at(0).featureVector.size();
00085   }
00086 
00087   int numFeatures = keyPoints->size();
00088   if(m_FlannModelData!=0)
00089   {
00090     delete[] m_FlannModelData;
00091 }
00092   m_FlannModelData = new float[numFeatures*m_descriptorLength];
00093   fillFlannDataWithDescriptors(keyPoints, m_FlannModelData);
00094   float speedup = 0.0;
00095   m_flannIndex = flann_build_index(m_FlannModelData, numFeatures, m_descriptorLength, &speedup, &m_flannParams);
00096   m_hasIndex = true;
00097 }
00098 
00099 void THIS::match (  std::vector< KeyPoint >* keyPoints, float maxDistRatio )
00100 {
00101     m_Matches.clear();
00102     if ( ( keyPoints->size() ==0 ) || ( m_Matches.size() !=0 ) || (!m_hasIndex) )
00103     {
00104         //TRACE_ERROR("Cannot match features."); // TODO use ROS
00105 
00106         if ( keyPoints->size() ==0 )
00107           //  TRACE_ERROR("Key Points Size is 0."); // TODO use ROS
00108         if ( m_Matches.size() !=0 )
00109           //  TRACE_ERROR("Matches not 0."); // TODO use ROS
00110         if (!m_hasIndex)
00111           //  TRACE_ERROR("No Index."); // TODO use ROS
00112 
00113         return;
00114     }
00115 
00116     // int startTime = Clock::getInstance()->getTimestamp(); // TODO
00117 
00118     unsigned int numKeypoints = keyPoints->size();
00119     int numberOfNeighbours = 2; // Number of approximate nearest neigbours to be determined
00120     int* indices = new int[numberOfNeighbours*numKeypoints]; // Holds the indices of the nearest neighbours
00121     float* distances = new float[numberOfNeighbours*numKeypoints]; // Holds the distance to the 1st and 2nd nearest neighbour
00122     float* testset = new float[numKeypoints*m_descriptorLength]; // Contains the data of the descriptors to be matched
00123     fillFlannDataWithDescriptors(keyPoints, testset);
00124     flann_find_nearest_neighbors_index(m_flannIndex, testset, numKeypoints, indices, distances, numberOfNeighbours, &m_flannParams );
00125 
00126 
00127     // check for distance ratios
00128     double distanceRatio = 0.0;
00129     for(unsigned i = 0; i < numKeypoints; i++){
00130       distanceRatio = distances[i*2+0] / distances[i*2+1];    
00131       if(distanceRatio < maxDistRatio ){
00132           KeyPointMatch match={ indices[i*2+0], i,distanceRatio, 0, 0 };
00133         m_Matches.push_back ( match );
00134       }  
00135     }
00136     delete[] indices;
00137     delete[] distances;
00138     delete[] testset;
00139     // m_Log << "\n--- " << m_Matches.size() << " keypoints matched in first phase in " << ( Clock::getInstance()->getTimestamp() - startTime ) << "ms\n"; // TODO
00140 
00141 //    eliminateMultipleMatches();
00142 }
00143 
00144 
00145 void THIS::eliminateMultipleMatches()
00146 {
00147     //It is possible that more than one ipoint in First has been matched to
00148     //the same ipoint in Second, in this case eliminate all but the closest one
00149 
00150   // int startTime = Clock::getInstance()->getTimestamp(); // TODO
00151 
00152     //maps keypoints in Second to their closest match result
00153     //first: index in m_KeyPointsB
00154     //second: iterator in m_Matches
00155     map< unsigned, MatchElem > bestMatch;
00156 
00157     m_Log << "deleting ";
00158 
00159     MatchElem currentMatch=m_Matches.begin();
00160     while ( currentMatch != m_Matches.end() )
00161     {
00162         unsigned index2=currentMatch->index2;
00163 
00164         //check if a match with this keypoint in Second was found before
00165         map< unsigned, MatchElem >::iterator previous=bestMatch.find ( index2 );
00166 
00167         //this is the first match found which maps to current second index
00168         if ( previous == bestMatch.end() )
00169         {
00170             bestMatch[ index2 ] = currentMatch;
00171             currentMatch++;
00172             continue;
00173         }
00174 
00175         MatchElem previousMatch = previous->second;
00176         //a match mapping to this index in second has been found previously, and had a higher distance
00177         //so delete the previously found match
00178         if ( currentMatch->distance < previousMatch->distance )
00179         {
00180             m_Log << previousMatch->index1 << "->" << previousMatch->index2;
00181             m_Log << " (better:" << currentMatch->index1 << "->" << currentMatch->index2 << ")  ";
00182             m_Matches.erase ( previousMatch );
00183             bestMatch[ index2 ] = currentMatch;
00184             currentMatch++;
00185             continue;
00186         }
00187         //otherwise, the previously found best match is better than current,
00188         //so delete current
00189         m_Log << currentMatch->index1 << "->" << currentMatch->index2;
00190         m_Log << " (better:" << previousMatch->index1 << "->" << previousMatch->index2 << ")  ";
00191         currentMatch=m_Matches.erase ( currentMatch );
00192     }
00193     // m_Log << "\n--- " << m_Matches.size() << " remaining after multiple match elimination in " << ( Clock::getInstance()->getTimestamp() - startTime ) << "ms\n"; // TODO
00194 
00195 }
00196 
00197 string THIS::getLog()
00198 {
00199   string log = m_Log.str();
00200   m_Log.str("");
00201   return log;
00202 }
00203 
00204 
00205 
00206 void THIS::fillFlannDataWithDescriptors(const std::vector< KeyPoint >* features, float* flannDataPtr){
00207   for(unsigned int i = 0; i < features->size(); i++){
00208     for(unsigned int j = 0; j < m_descriptorLength; j++){
00209       flannDataPtr[m_descriptorLength*i + j] = features->at(i).featureVector[j];
00210     }
00211   }
00212 }
00213 
00214 void THIS::clearFLANNMembers(){
00215   if(m_hasIndex){
00216     flann_free_index(m_flannIndex, &m_flannParams);
00217     m_hasIndex = false;
00218   }
00219 
00220 }
00221 
00222 
00223 #undef THIS


obj_rec_gui
Author(s): AGAS/agas@uni-koblenz.de
autogenerated on Mon Oct 6 2014 02:53:43