NNRMatcher.cpp
Go to the documentation of this file.
00001 /*******************************************************************************
00002  *  NNRMatcher.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 "NNRMatcher.h"
00012 
00013 #include "Workers/Math/vec2.h"
00014 
00015 #include <assert.h>
00016 #include <map>
00017 #include <list>
00018 #include <math.h>
00019 
00020 #define THIS NNRMatcher
00021 
00022 THIS::THIS ( std::vector< KeyPoint >* keyPointsA, std::vector< KeyPoint >* keyPointsB )
00023 {
00024     m_KeyPointsA = keyPointsA;
00025     m_KeyPointsB = keyPointsB;
00026     m_Log << "NNRMatcher created\n";
00027     m_Log << "Number of keypoints (scenePoints/objectImagePoints): " << m_KeyPointsA->size() << " / " << m_KeyPointsB->size() << std::endl;
00028 }
00029 
00030 THIS::~THIS()
00031 {
00032 }
00033 
00034 void THIS::match ( float maxDistRatio )
00035 {
00036     if ( ( m_KeyPointsA->size() ==0 ) || ( m_KeyPointsB->size() ==0 ) || ( m_Matches.size() !=0 ) ) { return; }
00037 
00038     //int startTime = Clock::getInstance()->getTimestamp(); // TODO
00039 
00040     int size1=m_KeyPointsA->size();
00041     int size2=m_KeyPointsB->size();
00042 
00043     float maxDistRatioSquared=maxDistRatio*maxDistRatio;
00044 
00045     std::vector< unsigned > indPos;
00046     std::vector< unsigned > indNeg;
00047     indPos.reserve( m_KeyPointsB->size() );
00048     indNeg.reserve( m_KeyPointsB->size() );
00049 
00050     //sort keypoints2 by their sign
00051     for ( int index2=0; index2 < size2; index2++ )
00052     {
00053       if ( (*m_KeyPointsB)[index2].sign > 0 )
00054       {
00055         indPos.push_back( index2 );
00056       }
00057       else
00058       {
00059         indNeg.push_back( index2 );
00060       }
00061     }
00062 
00063     for ( int index1=0; index1 < size1; index1++ )
00064     {
00065         //index in second keypoint list corresponding to minimal distance
00066         int minIndexB=-1;
00067         //minimal distance found
00068         double minDist=1e10;
00069         //second-minimal distance
00070         double secondMinDist=1e10;
00071 
00072         //select list of indices of keypoints with positive or negative sign, according to currently matche keypoint
00073         std::vector< unsigned >& indices2 = (*m_KeyPointsA)[index1].sign > 0 ? indPos : indNeg;
00074 
00075         for ( unsigned k=0; k < indices2.size(); k++ )
00076         {
00077           int index2 = indices2[ k ];
00078           double distance = (*m_KeyPointsA)[index1].squaredDistance ( (*m_KeyPointsB)[index2] );//, secondMinDist );
00079             //new minimum found:
00080             if ( distance < minDist )
00081             {
00082                 secondMinDist=minDist;
00083                 minDist=distance;
00084                 minIndexB=index2;
00085             }
00086             else
00087             if ( distance < secondMinDist )
00088             {
00089                 secondMinDist=distance;
00090             }
00091         }
00092         if ( ( minIndexB != -1 ) && ( minDist/secondMinDist < maxDistRatioSquared ) )
00093         {
00094             KeyPointMatch match={ index1, minIndexB, minDist, 0, 0 };
00095             m_Matches.push_back ( match );
00096             m_Log << index1 << "->" << minIndexB << " (d" << minDist << "/r" << minDist/secondMinDist << ")  ";
00097         }
00098 
00099     }
00100     // m_Log << "\n--- " << m_Matches.size() << " keypoints matched in first phase in " << ( Clock::getInstance()->getTimestamp() - startTime ) << "ms\n"; // TODO
00101 
00102     eliminateMultipleMatches();
00103 
00104 }
00105 
00106 
00107 void THIS::eliminateMultipleMatches()
00108 {
00109     //It is possible that more than one ipoint in First has been matched to
00110     //the same ipoint in Second, in this case eliminate all but the closest one
00111 
00112   // int startTime = Clock::getInstance()->getTimestamp(); // TODO
00113 
00114     //maps keypoints in Second to their closest match result
00115     //first: index in m_KeyPointsB
00116     //second: iterator in m_Matches
00117     std::map< unsigned, MatchElem > bestMatch;
00118 
00119     m_Log << "deleting ";
00120 
00121     MatchElem currentMatch=m_Matches.begin();
00122     while ( currentMatch != m_Matches.end() )
00123     {
00124         unsigned index2=currentMatch->index2;
00125 
00126         //check if a match with this keypoint in Second was found before
00127         std::map< unsigned, MatchElem >::iterator previous=bestMatch.find ( index2 );
00128 
00129         //this is the first match found which maps to current second index
00130         if ( previous == bestMatch.end() )
00131         {
00132             bestMatch[ index2 ] = currentMatch;
00133             currentMatch++;
00134             continue;
00135         }
00136 
00137         MatchElem previousMatch = previous->second;
00138         //a match mapping to this index in second has been found previously, and had a higher distance
00139         //so delete the previously found match
00140         if ( currentMatch->distance < previousMatch->distance )
00141         {
00142             m_Log << previousMatch->index1 << "->" << previousMatch->index2;
00143             m_Log << " (better:" << currentMatch->index1 << "->" << currentMatch->index2 << ")  ";
00144             m_Matches.erase ( previousMatch );
00145             bestMatch[ index2 ] = currentMatch;
00146             currentMatch++;
00147             continue;
00148         }
00149         //otherwise, the previously found best match is better than current,
00150         //so delete current
00151         m_Log << currentMatch->index1 << "->" << currentMatch->index2;
00152         m_Log << " (better:" << previousMatch->index1 << "->" << previousMatch->index2 << ")  ";
00153         currentMatch=m_Matches.erase ( currentMatch );
00154     }
00155     // m_Log << "\n--- " << m_Matches.size() << " remaining after multiple match elimination in " << ( Clock::getInstance()->getTimestamp() - startTime ) << "ms\n"; // TODO
00156 
00157 }
00158 
00159 std::string THIS::getLog()
00160 {
00161     return m_Log.str();
00162 }
00163 
00164 #undef THIS


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