Ajout prototype Wrapper ROS matcher

This commit is contained in:
Unknown 2018-08-01 15:23:50 +02:00
parent f17bbbcc51
commit 373a75ae87
409 changed files with 133617 additions and 507 deletions

View file

@ -0,0 +1,717 @@
#include "ASIFT_matcher.hpp"
ASIFT_matcher::ASIFT_matcher(): _nb_refs(0), _total_num_matchings(0), _resize_imgs(false), _showDebug(false)
{
default_sift_parameters(_siftParam);
}
ASIFT_matcher::ASIFT_matcher(const char* ref_path): ASIFT_matcher()
{
if(!loadReferences(ref_path))
{
std::cerr<<"Error : Failed to load references"<<std::endl;
}
}
// ASIFT_matcher::~ASIFT_matcher()
// {
// }
//Return true if successfull
bool ASIFT_matcher::addReference(const char* image_path, unsigned int num_tilts)
{
///// Read input
// float * iarr1;
// size_t w1, h1;
// if (NULL == (iarr1 = read_png_f32_gray(image_path, &w1, &h1))) {
// std::cerr << "Unable to load image file " << image_path << std::endl;
// return false;
// }
// std::vector<float> ipixels1(iarr1, iarr1 + w1 * h1);
// free(iarr1); /*memcheck*/
// cout<<"Size : "<<w1<<"/"<<h1<<" - "<<ipixels1.size()<<endl;
cimg_library::CImg<float> image;
try
{
image.assign(image_path);
}
catch(cimg_library::CImgIOException)
{
std::cerr << "Unable to load image file " << image_path << std::endl;
return false;
}
//Convert to grayscale
cimg_library::CImg<float> gray(image.width(), image.height(), 1, 1, 0);
cimg_forXY(image,x,y) {
// Separation of channels
int R = (int)image(x,y,0,0);
int G = (int)image(x,y,0,1);
int B = (int)image(x,y,0,2);
// Arithmetic addition of channels for gray
// int grayValue = (int)(0.33*R + 0.33*G + 0.33*B);
// Real weighted addition of channels for gray
int grayValueWeight = (int)(0.299*R + 0.587*G + 0.114*B);
// saving píxel values into image information
// gray(x,y,0,0) = grayValue;
gray(x,y,0,0) = grayValueWeight;
}
std::vector<float> ipixels1;
size_t w1=gray.width(), h1=gray.height();
ipixels1.assign(gray.begin(), gray.end());
std::cout<<"Building reference from "<< image_path << std::endl;
return addReference(ipixels1, w1, h1, num_tilts);
}
//Image : Gray scale image (image size = w*h)
bool ASIFT_matcher::addReference(const vector<float>& image, unsigned int w, unsigned int h, unsigned int num_tilts)
{
if(image.size()!=w*h)
{
cerr<<"Error : Input image size doesn't correspond with parameters"<<endl;
return false;
}
int w1=w, h1=h;
vector<float> ipixels1 = image;
///// Resize the images to area wS*hW in remaining the apsect-ratio
///// Resize if the resize flag is not set or if the flag is set unequal to 0
float wS = IM_X;
float hS = IM_Y;
float zoom1=0;
int wS1=0, hS1=0;
vector<float> ipixels1_zoom;
if(_resize_imgs)
{
cout << "WARNING: The input image is resized to " << wS << "x" << hS << " for ASIFT. " << endl
<< " But the results will be normalized to the original image size." << endl << endl;
float InitSigma_aa = 1.6;
float fproj_p, fproj_bg;
char fproj_i;
float *fproj_x4, *fproj_y4;
int fproj_o;
fproj_o = 3;
fproj_p = 0;
fproj_i = 0;
fproj_bg = 0;
fproj_x4 = 0;
fproj_y4 = 0;
float areaS = wS * hS;
// Resize image 1
float area1 = w1 * h1;
zoom1 = sqrt(area1/areaS);
wS1 = (int) (w1 / zoom1);
hS1 = (int) (h1 / zoom1);
int fproj_sx = wS1;
int fproj_sy = hS1;
float fproj_x1 = 0;
float fproj_y1 = 0;
float fproj_x2 = wS1;
float fproj_y2 = 0;
float fproj_x3 = 0;
float fproj_y3 = hS1;
/* Anti-aliasing filtering along vertical direction */
if ( zoom1 > 1 )
{
float sigma_aa = InitSigma_aa * zoom1 / 2;
GaussianBlur1D(ipixels1,w1,h1,sigma_aa,1);
GaussianBlur1D(ipixels1,w1,h1,sigma_aa,0);
}
// simulate a tilt: subsample the image along the vertical axis by a factor of t.
ipixels1_zoom.resize(wS1*hS1);
fproj (ipixels1, ipixels1_zoom, w1, h1, &fproj_sx, &fproj_sy, &fproj_bg, &fproj_o, &fproj_p,
&fproj_i , fproj_x1 , fproj_y1 , fproj_x2 , fproj_y2 , fproj_x3 , fproj_y3, fproj_x4, fproj_y4);
}
else
{
ipixels1_zoom.resize(w1*h1);
ipixels1_zoom = ipixels1;
wS1 = w1;
hS1 = h1;
zoom1 = 1;
}
///// Compute ASIFT keypoints
asift_keypoints keys;
int num_keys = 0;
time_t tstart, tend;
tstart = time(0);
num_keys = compute_asift_keypoints(ipixels1_zoom, wS1, hS1, num_tilts, _showDebug, keys, _siftParam);
tend = time(0);
//Save data
_im_refs.push_back(ipixels1_zoom);
_size_refs.push_back(make_pair(wS1,hS1));
_zoom_refs.push_back(zoom1);
_num_keys.push_back(num_keys);
_num_tilts.push_back(num_tilts);
_keys.push_back(keys);
_nb_refs++;
cout<<"Reference built in "<< difftime(tend, tstart) << " seconds." << endl;
cout<<" "<< num_keys <<" ASIFT keypoints found."<< endl;
return true;
}
//Return number of match
unsigned int ASIFT_matcher::match(const char* image_path, unsigned int num_tilts)
{
if(_nb_refs<=0)
{
cout<<"ASIFT_matcher Error : Trying to match without reference"<<endl;
return 0;
}
///// Read input
// float * iarr1;
// size_t w1, h1;
// if (NULL == (iarr1 = read_png_f32_gray(image_path, &w1, &h1))) {
// std::cerr << "Unable to load image file " << image_path << std::endl;
// return 1;
// }
// std::vector<float> ipixels1(iarr1, iarr1 + w1 * h1);
// free(iarr1); /*memcheck*/
cimg_library::CImg<float> image;
try
{
image.assign(image_path);
}
catch(cimg_library::CImgIOException)
{
std::cerr << "Unable to load image file " << image_path << std::endl;
return 0;
}
//Convert to grayscale
cimg_library::CImg<float> gray(image.width(), image.height(), 1, 1, 0);
cimg_forXY(image,x,y) {
// Separation of channels
int R = (int)image(x,y,0,0);
int G = (int)image(x,y,0,1);
int B = (int)image(x,y,0,2);
// Arithmetic addition of channels for gray
// int grayValue = (int)(0.33*R + 0.33*G + 0.33*B);
// Real weighted addition of channels for gray
int grayValueWeight = (int)(0.299*R + 0.587*G + 0.114*B);
// saving píxel values into image information
// gray(x,y,0,0) = grayValue;
gray(x,y,0,0) = grayValueWeight;
}
vector<float> ipixels1;
size_t w1=gray.width(), h1=gray.height();
ipixels1.assign(gray.begin(), gray.end());
std::cout<<"Matching from "<<image_path<<std::endl;
return match(ipixels1, w1, h1, num_tilts);
}
//Image : Gray scale image (image size = w*h)
//Return number of match
unsigned int ASIFT_matcher::match(const vector<float>& image, unsigned int w, unsigned int h, unsigned int num_tilts)
{
if(image.size()!=w*h)
{
cerr<<"Error : Input image size doesn't correspond with parameters"<<endl;
return 0;
}
int w1=w, h1=h;
vector<float> ipixels1 = image;
///// Resize the images to area wS*hW in remaining the apsect-ratio
///// Resize if the resize flag is not set or if the flag is set unequal to 0
float wS = IM_X;
float hS = IM_Y;
float zoom1=0;
int wS1=0, hS1=0;
vector<float> ipixels1_zoom;
if(_resize_imgs)
{
cout << "WARNING: The input image is resized to " << wS << "x" << hS << " for ASIFT. " << endl
<< " But the results will be normalized to the original image size." << endl << endl;
float InitSigma_aa = 1.6;
float fproj_p, fproj_bg;
char fproj_i;
float *fproj_x4, *fproj_y4;
int fproj_o;
fproj_o = 3;
fproj_p = 0;
fproj_i = 0;
fproj_bg = 0;
fproj_x4 = 0;
fproj_y4 = 0;
float areaS = wS * hS;
// Resize image 1
float area1 = w1 * h1;
zoom1 = sqrt(area1/areaS);
wS1 = (int) (w1 / zoom1);
hS1 = (int) (h1 / zoom1);
int fproj_sx = wS1;
int fproj_sy = hS1;
float fproj_x1 = 0;
float fproj_y1 = 0;
float fproj_x2 = wS1;
float fproj_y2 = 0;
float fproj_x3 = 0;
float fproj_y3 = hS1;
/* Anti-aliasing filtering along vertical direction */
if ( zoom1 > 1 )
{
float sigma_aa = InitSigma_aa * zoom1 / 2;
GaussianBlur1D(ipixels1,w1,h1,sigma_aa,1);
GaussianBlur1D(ipixels1,w1,h1,sigma_aa,0);
}
// simulate a tilt: subsample the image along the vertical axis by a factor of t.
ipixels1_zoom.resize(wS1*hS1);
fproj (ipixels1, ipixels1_zoom, w1, h1, &fproj_sx, &fproj_sy, &fproj_bg, &fproj_o, &fproj_p,
&fproj_i , fproj_x1 , fproj_y1 , fproj_x2 , fproj_y2 , fproj_x3 , fproj_y3, fproj_x4, fproj_y4);
}
else
{
ipixels1_zoom.resize(w1*h1);
ipixels1_zoom = ipixels1;
wS1 = w1;
hS1 = h1;
zoom1 = 1;
}
///// Compute ASIFT keypoints
asift_keypoints keys;
int num_keys = 0;
time_t tstart, tend;
tstart = time(0);
num_keys = compute_asift_keypoints(ipixels1_zoom, wS1, hS1, num_tilts, _showDebug, keys, _siftParam);
tend = time(0);
cout<< "Keypoints computation accomplished in " << difftime(tend, tstart) << " seconds." << endl;
cout<<" "<< num_keys <<" ASIFT keypoints found."<< endl;
//// Match ASIFT keypoints
_total_num_matchings=0;
for(unsigned int i = 0; i<_nb_refs;i++)
{
int num_matchings = 0;
matchingslist matchings;
cout << "Matching the keypoints..." << endl;
tstart = time(0);
try
{
num_matchings = compute_asift_matches(num_tilts, _num_tilts[i], w, h, _size_refs[i].first, _size_refs[i].second, _showDebug, keys, _keys[i], matchings, _siftParam);
}
catch(const bad_alloc& ba)
{
cerr<<"ERROR: ASIFT_matcher::match - ";
cerr << ba.what() << endl;
}
// cout<< _keys[i].size()<< " " << _keys[i][0].size() <<" "<< _keys[i][0][0].size()<<endl;
tend = time(0);
cout << "Keypoints matching accomplished in " << difftime(tend, tstart) << " seconds." << endl;
_num_matchings.push_back(num_matchings);
_total_num_matchings += num_matchings;
_matchings.push_back(matchings);
}
return _total_num_matchings;
}
//Return true if successfull
bool ASIFT_matcher::computeROI(int& x, int& y, unsigned int& h, unsigned int& w) const
{
if(getNbMatch()==0)
{
cerr<<"Error : cannot compute ROI without matchs"<<endl;
return false;
}
pair<int,int> upLe, doRi; //UpLeft / DownRight
//Initialisation
for(unsigned int i=0;i<_matchings.size();i++)
{
if(getNbMatchs()[i]!=0)
{
upLe = make_pair(_matchings[i][0].first.x,_matchings[i][0].first.y);
doRi = make_pair(_matchings[i][0].first.x,_matchings[i][0].first.y);
}
}
//Compute ROI
for(unsigned int i=0;i<_matchings.size();i++)
{
for(unsigned int j=0;j<_matchings[i].size();j++)
{
keypoint kp = _matchings[i][j].first;
if(kp.x<upLe.first)
upLe.first = kp.x;
if(kp.y<upLe.second)
upLe.second=kp.y;
if(kp.x>doRi.first)
doRi.first=kp.x;
if(kp.y>doRi.second)
doRi.second=kp.y;
}
}
x=upLe.first; //Système de coordonée ? (devrait etre bon)
y=upLe.second;
h=doRi.second-y;
w=doRi.first-x;
return true;
}
//Return true if successfull
bool ASIFT_matcher::computeCenter(int& cx, int& cy) const
{
if(getNbMatch()==0)
{
cerr<<"Error : cannot compute Center without matchs"<<endl;
return false;
}
unsigned int total_kp =0;
cx=0;cy=0;
for(unsigned int i=0;i<_matchings.size();i++)
{
for(unsigned int j=0;j<_matchings[i].size();j++)
{
keypoint kp = _matchings[i][j].first;
cx+=kp.x;
cy+=kp.y;
}
total_kp += _matchings[i].size();
}
cx/=total_kp;
cy/=total_kp;
return true;
}
//Filter keypoint which are far (Euclidian distance) from the center.
//Not optimized
//threshold : 1-68%/2-95%/3-99%
//Return true if successfull
bool ASIFT_matcher::distFilter(int threshold=2)
{
cout<<"filtering keypoint..."<<endl;
if(getNbMatch()==0)
{
cerr<<"Error : cannot filter points without matchs"<<endl;
return false;
}
//Compute standard deviation
int cx, cy;
unsigned int total_kp =0;
unsigned int euc_dist, dist_avg =0, dist_var=0, std_dev;
vector< vector< int > > kp_euc_dist;
if(computeCenter(cx,cy))
{
// cout<<"Center : "<<cx<<" / "<<cy<<endl;
//Compute means/average distance to center + euclidian distances to center for each keypoint
for(unsigned int i=0;i<_matchings.size();i++)
{
vector<int> temp_euc_dist;
for(unsigned int j=0;j<_matchings[i].size();j++)
{
keypoint kp = _matchings[i][j].first;
euc_dist =sqrt((kp.x-cx)*(kp.x-cx)+(kp.y-cy)+(kp.y-cy));
dist_avg+=euc_dist;
temp_euc_dist.push_back(euc_dist);
}
total_kp += _matchings[i].size();
kp_euc_dist.push_back(temp_euc_dist);
}
dist_avg/=total_kp;
// cout<<"Dist avg: "<<dist_avg<<endl;
//Compute variance
for(unsigned int i=0;i<_matchings.size();i++)
{
for(unsigned int j=0;j<_matchings[i].size();j++)
{
euc_dist =kp_euc_dist[i][j];
dist_var+=(euc_dist-dist_avg)*(euc_dist-dist_avg);
}
}
dist_var/=total_kp;
//Compute standard deviation
std_dev=sqrt(dist_var);
// cout<<"Standard Deviation : "<<std_dev<<endl;
//Filter
vector< matchingslist > filtered_match;
for(unsigned int i=0;i<_matchings.size();i++)
{
matchingslist new_match;
for(unsigned int j=0;j<_matchings[i].size();j++)
{
euc_dist =kp_euc_dist[i][j];
if(euc_dist<dist_avg+threshold*std_dev) //Filtering Condition
{
new_match.push_back(_matchings[i][j]);
}
}
filtered_match.push_back(new_match);
_num_matchings[i]=new_match.size();
}
//Save filtered matchs
_matchings = filtered_match;
return true;
}
return false;
}
//Save reference data necessary for the matching
//Doesn't save references images or Sift parameters
bool ASIFT_matcher::saveReferences(const char* ref_path) const
{
// Write all the keypoints (row, col, scale, orientation, desciptor (128 integers))
std::ofstream file_key1(ref_path);
if (file_key1.is_open())
{
file_key1<<_nb_refs<<" "<<std::endl;
for(unsigned int j=0; j<_keys.size();j++)
{
asift_keypoints kps =_keys[j];
// Follow the same convention of David Lowe:
// the first line contains the number of keypoints and the length of the desciptors (128)
// Added number of tilts
// Added sizes
file_key1 << _num_keys[j] << " " << VecLength << " " <<_size_refs[j].first<<" "<<_size_refs[j].second<<" "<<std::endl; //<<_num_tilts[j] << " "
for (int tt = 0; tt < (int) kps.size(); tt++)
{
for (int rr = 0; rr < (int) kps[tt].size(); rr++)
{
keypointslist::iterator ptr = kps[tt][rr].begin();
for(int i=0; i < (int) kps[tt][rr].size(); i++, ptr++)
{
file_key1 << _zoom_refs[j]*ptr->x << " " << _zoom_refs[j]*ptr->y << " " << _zoom_refs[j]*ptr->scale << " " << ptr->angle;
for (int ii = 0; ii < (int) VecLength; ii++)
{
file_key1 << " " << ptr->vec[ii];
}
file_key1 << std::endl;
}
}
}
// file_key1<<std::endl;
}
}
else
{
std::cerr << "Unable to open the file :"<<ref_path;
return false;
}
file_key1.close();
return true;
}
//Load reference data necessary for the matching
//Doesn't load references images or Sift parameters
//TODO : split data between different tilts
bool ASIFT_matcher::loadReferences(const char* ref_path)
{
std::ifstream ref_file(ref_path);
std::string line, tmp;
std::stringstream iss;
pair<int,int> size_tmp;
if (ref_file.is_open())
{
std::getline(ref_file, line);
std::string::size_type sz;
// _nb_refs = std::stoi(line, &sz); //C++11
_nb_refs = atoi(line.c_str());
_keys = std::vector<asift_keypoints>(_nb_refs);
_num_keys = std::vector< int >(_nb_refs);
_size_refs= std::vector< pair<int,int> >(_nb_refs);
_num_tilts = std::vector< int >(_nb_refs,1);
_zoom_refs = std::vector<float>(_nb_refs,1);
for(unsigned int i = 0; i<_nb_refs;i++)
{
std::getline(ref_file, line);
std::stringstream iss(line);
std::getline(iss,tmp,' ');
_num_keys[i]=atoi(tmp.c_str());
std::getline(iss,tmp,' ');
if(VecLength!=atoi(tmp.c_str()))
{
std::cerr<<"Error VecLength doesn't correspond..."<<std::endl;
return false;
}
// std::getline(iss,tmp,' ');
// _num_tilts[i]=atoi(tmp.c_str());
std::getline(iss,tmp,' ');
size_tmp.first=atoi(tmp.c_str());
std::getline(iss,tmp,' ');
size_tmp.second=atoi(tmp.c_str());
_size_refs[i]=size_tmp;
keypointslist list;
for(unsigned int j =0; j<(unsigned int)_num_keys[i];j++)
{
keypoint nkp;
std::getline(ref_file, line);
std::stringstream iss(line);
// if(j==0)
// cout<<line<<endl;
std::getline(iss,tmp,' ');
// std::stof(nb_ref, nkp.x); //C++11
nkp.x=atof(tmp.c_str());
// if(j<5)
// cout<<"x : "<<nkp.x<<endl;
std::getline(iss,tmp,' ');
nkp.y=atof(tmp.c_str());
// if(j<5)
// cout<<"y : "<<nkp.y<<endl;
std::getline(iss,tmp,' ');
nkp.scale=atof(tmp.c_str());
// if(j<5)
// cout<<"Scale : "<<nkp.scale<<endl;
std::getline(iss,tmp,' ');
nkp.angle=atof(tmp.c_str());
for(unsigned int k=0; k<(int) VecLength; k++)
{
std::getline(iss,tmp,' ');
nkp.vec[k]=atof(tmp.c_str());
}
list.push_back(nkp);
// if(j<5)
// {
// cout<<"x : "<<list[j].x<<endl;
// cout<<"y : "<<list[j].y<<endl;
// cout<<"Scale : "<<list[j].scale<<endl;
// }
}
std::vector< keypointslist > vkps(1,list);
asift_keypoints akps(1,vkps);
_keys[i]=akps;
// std::getline(ref_file, line);
}
}
else
{
std::cerr << "Unable to open the file :"<<ref_path;
return false;
}
ref_file.close();
return true;
}
ASIFT_matcher& ASIFT_matcher::operator=(const ASIFT_matcher& m)
{
_nb_refs=m.getNbRef();
_im_refs=m.getRefImgs();
_size_refs=m.getSizeRef();
_zoom_refs=m.getZoomRef();
_num_keys=m.getNumKeys();
_num_tilts=m.getNumTilts();
_keys=m.getKeys();
_total_num_matchings=m.getNbMatch();
_num_matchings=getNbMatchs();
_matchings=m.getMatch();
_siftParam=m.getSiftPar();
_resize_imgs=m.isResizingImg();
_showDebug=m.isShowingDebug();
return *this;
}
//Debugging function
void ASIFT_matcher::print() const
{
for(unsigned int i=0; i< _keys.size();i++)
{
cout<<"Ref size:"<<i<<" - size :"<<_keys[i].size()<<endl;
for(unsigned int j=0; j<_keys[i].size();j++)
{
cout<<" "<<j<<" - size :"<<_keys[i][j].size()<<endl;
for(unsigned int k=0; k<_keys[i][j].size();k++)
{
cout<<" "<<k<<" - size :"<<_keys[i][j][k].size()<<endl;
double sx=0,sy=0,ss=0,sa=0, sv=0;
for(unsigned int l=0; l<_keys[i][j][k].size();l++)
{
sx+=_keys[i][j][k][l].x;
sy+=_keys[i][j][k][l].y;
ss+=_keys[i][j][k][l].scale;
sa+=_keys[i][j][k][l].angle;
for(unsigned int v=0;v<VecLength;v++)
{
sv+=_keys[i][j][k][l].vec[v];
}
// cout<<" "<<sx<<"-"<<sy<<"-"<<ss<<"-"<<sa<<"-"<<sv<<endl;
}
cout<<" "<<sx<<"-"<<sy<<"-"<<ss<<"-"<<sa<<"-"<<sv<<endl;
}
}
}
}

View file

@ -0,0 +1,101 @@
#ifndef ASIFTMATCHER_HPP
#define ASIFTMATCHER_HPP
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <time.h>
#include <vector>
#include <sstream>
#ifdef _OPENMP
#include <omp.h>
#endif
#include "demo_lib_sift.h"
// #include "io_png/io_png.h"
#include "library.h"
#include "frot.h"
#include "fproj.h"
#include "compute_asift_keypoints.h"
#include "compute_asift_matches.h"
#include "CImg.h" //Need ImageMagick package
# define IM_X 800
# define IM_Y 600
using namespace std;
typedef vector< vector< keypointslist > > asift_keypoints;
//ASIFT wrapper
class ASIFT_matcher
{
public:
ASIFT_matcher();
ASIFT_matcher(const char* ref_path);
ASIFT_matcher(const ASIFT_matcher& matcher) { *this = matcher;}
// virtual ~ASIFT_matcher();
bool addReference(const char* image_path, unsigned int num_tilts=1);
bool addReference(const vector<float>& image, unsigned int w, unsigned int h, unsigned int num_tilts =1);
unsigned int match(const char* image_path, unsigned int num_tilts =1);
unsigned int match(const vector<float>& image, unsigned int w, unsigned int h, unsigned int num_tilts =1);
bool computeROI(int& x, int& y, unsigned int& h, unsigned int& w) const; //Compute the bounding rectangle of the keypoints
bool computeCenter(int& cx, int& cy) const;
bool distFilter(int threshold); //Filter keypoint which are far (Euclidian distance) from the center.
bool saveReferences(const char* ref_path) const;
bool loadReferences(const char* ref_path);
ASIFT_matcher& operator=(const ASIFT_matcher& m);
unsigned int getNbRef() const{ return _nb_refs;}
const vector< vector< float > >& getRefImgs() const{ return _im_refs;}
const vector< pair<int,int> >& getSizeRef() const{ return _size_refs;}
const vector<float>& getZoomRef() const{ return _zoom_refs;}
const std::vector<int>& getNumKeys() const{ return _num_keys;}
const std::vector<int>& getNumTilts() const{ return _num_tilts;}
const std::vector< asift_keypoints >& getKeys() const{ return _keys;}
const vector < unsigned int >& getNbMatchs() const{ return _num_matchings;}
unsigned int getNbMatch() const{ return _total_num_matchings;}
const vector< matchingslist >& getMatch() const{ return _matchings;}
vector< matchingslist >& getMatch(){ return _matchings;}
const siftPar& getSiftPar() const{ return _siftParam;}
void setSiftPar(const siftPar &newSiftPar){ _siftParam = newSiftPar;}
bool isResizingImg() const{ return _resize_imgs;}
void setResizeImg(bool resize_imgs){ _resize_imgs=resize_imgs;}
bool isShowingDebug() const{ return _showDebug;}
void showDebug(bool showDebug){ _showDebug=showDebug;}
void print() const; //Debugging function
protected:
//Reference Images
// vector< image > _im_refs;
unsigned int _nb_refs;// = 0; //Number of reference images
vector< vector< float > > _im_refs; //Reference images used for matching
vector< pair<int,int> > _size_refs; //Width/Height
vector<float> _zoom_refs; //Zoom coeffs
//ASIFT Keypoints
vector< int > _num_keys; //Number of keypoint/reference
vector< int > _num_tilts; //Number of tilts/reference (Speed VS Precision)
vector< asift_keypoints > _keys; //Keypoints
//Matchs
unsigned int _total_num_matchings;
vector < unsigned int > _num_matchings; //Number of match/reference
vector< matchingslist > _matchings; //Matchs
siftPar _siftParam; //SIFT parameters
//Flags
bool _resize_imgs;// = false; //Resize images to IM_X/IM_Y ?
bool _showDebug;// = 0; //Show debugging messages ?
};
#endif

60936
asift_match/src/CImg.h Normal file

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,57 @@
#include "ROS_matcher.hpp"
ROS_matcher::ROS_matcher(): _num_tilt(1), _status(MATCHER_STATUS_WAITING_INIT)
{
_center_pub = _nh.advertise<geometry_msgs::PointStamped>("/ROS_matcher/center", 10);
message_filters::Subscriber<sensor_msgs::CameraInfo> info_sub(_nh, "/camera/rgb/camera_info", 1);
message_filters::Subscriber<sensor_msgs::Image> image_sub(_nh, "/camera/rgb/image_raw", 1);
message_filters::Subscriber<sensor_msgs::PointCloud2> pointcloud_sub(_nh, "/camera/depth_registered/points", 1);
message_filters::TimeSynchronizer<sensor_msgs::CameraInfo, sensor_msgs::Image, sensor_msgs::PointCloud2> sync(info_sub, image_sub, pointcloud_sub, 10);
sync.registerCallback(boost::bind(&ROS_matcher::cameraCallback, this, _1, _2, _3));
unsigned int nb_ref =2;
std::string refData[] = {
"book_training/train_image_000.png",
"book_training/train_image_001.png",
"book_training/train_image_002.png",
"book_training/train_image_003.png"};
for(unsigned int i=0; i<nb_ref;i++)
{
matcher.addReference(refData[i].c_str(), _num_tilt);
}
}
void ROS_matcher::cameraCallback(const sensor_msgs::CameraInfo::ConstPtr& info_msg, const sensor_msgs::Image::ConstPtr& image_msg, const sensor_msgs::PointCloud2::ConstPtr& pointcloud_msg)
{
if(_status == MATCHER_STATUS_IDLE)
{
unsigned int width = image_msg->width, height = image_msg->height;
std::vector<float> image(height*width);
//Conversion en niveau de gris
if(image_msg->encoding == "yuv422")
{
for(unsigned int i=0; i<height*width; i++)
{
image[i]=image_msg->data[3*i];
}
}
else
{
ROS_WARN("Encoding doesn't correspond to yuv422");
return;
}
int nb_match=0;
nb_match = matcher.match(image, width, height, _num_tilt);
ROS_INFO("Match : %d", nb_match);
}
else
{
ROS_INFO("Matcher not ready to process");
}
}

View file

@ -0,0 +1,45 @@
#ifndef ROSMATCHER_HPP
#define ROSMATCHER_HPP
#include <ros/ros.h>
#include <tf/tf.h>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/Image.h>
#include <geometry_msgs/PointStamped.h>
#include "ASIFT_matcher.hpp"
enum MATCHER_STATUS{
MATCHER_STATUS_IDLE=0,
MATCHER_STATUS_PROCESSING,
MATCHER_STATUS_WAITING_INIT};
class ROS_matcher
{
protected:
ros::NodeHandle _nh;
//Publisher ROS
ros::Publisher _center_pub;
//Subscriber ROS
// ros::Subscriber _image_sub;
//Matcher
int _num_tilt;
ASIFT_matcher matcher;
MATCHER_STATUS _status;
public:
ROS_matcher();
// ~ROS_matcher();
void cameraCallback(const sensor_msgs::CameraInfo::ConstPtr& info_msg, const sensor_msgs::Image::ConstPtr& image_msg, const sensor_msgs::PointCloud2::ConstPtr& pointcloud_msg);
};
#endif

View file

@ -0,0 +1,12 @@
#include "ROS_matcher.hpp"
int main(int argc, char *argv[])
{
ros::init(argc, argv, "ROS_matcher");
ROS_matcher ros_matcher;
ros::spin();
return 0;
}

Binary file not shown.

After

Width:  |  Height:  |  Size: 522 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 552 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 484 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 458 KiB

View file

@ -0,0 +1,8 @@
Book cMo for training image 005
rows: 4
cols: 4
data:
- [-0.2314201876, -0.9583649151, 0.1672763771, 0.09835545579]
- [0.7484075924, -0.06552319445, 0.6599945353, -0.0974700766]
- [-0.6215551242, 0.2779269699, 0.7324109687, 0.5499983612]
- [0; 0; 0; 1]

View file

@ -0,0 +1,8 @@
Book cMo for training image 008
rows: 4
cols: 4
data:
- [0.02063568325, -0.5653102458, -0.8246202123, 0.0403687505]
- [0.8210674394, 0.4801939642, -0.3086454546, -0.1745029756]
- [0.5704580865, -0.6706996964, 0.4740669666, 0.4630312508]
- [0, 0, 0, 1]

View file

@ -0,0 +1,9 @@
Book cMo for training image 007
rows: 4
cols: 4
data:
- [-0.03609085509, -0.3148440768, 0.9484569877, 0.04713881051]
- [-0.8006242946, 0.5771011583, 0.1611055304, 0.02971868344]
- [-0.5980787482, -0.7535432704, -0.2728998912, 0.6240615433]
- [0, 0, 0, 1]

View file

@ -0,0 +1,569 @@
// Copyright (c) 2008-2011, Guoshen Yu <yu@cmap.polytechnique.fr>
// Copyright (c) 2008-2011, Jean-Michel Morel <morel@cmla.ens-cachan.fr>
//
// WARNING:
// This file implements an algorithm possibly linked to the patent
//
// Jean-Michel Morel and Guoshen Yu, Method and device for the invariant
// affine recognition recognition of shapes (WO/2009/150361), patent pending.
//
// This file is made available for the exclusive aim of serving as
// scientific tool to verify of the soundness and
// completeness of the algorithm description. Compilation,
// execution and redistribution of this file may violate exclusive
// patents rights in certain countries.
// The situation being different for every country and changing
// over time, it is your responsibility to determine which patent
// rights restrictions apply to you before you compile, use,
// modify, or redistribute this file. A patent lawyer is qualified
// to make this determination.
// If and only if they don't conflict with any patent terms, you
// can benefit from the following license terms attached to this
// file.
//
// This program is provided for scientific and educational only:
// you can use and/or modify it for these purposes, but you are
// not allowed to redistribute this work or derivative works in
// source or executable form. A license must be obtained from the
// patent right holders for any other use.
//
//
//*------------------------ compute_asift_keypoints -------------------------*/
// Compute the ASIFT keypoints on the input image.
//
// Please report bugs and/or send comments to Guoshen Yu yu@cmap.polytechnique.fr
//
// Reference: J.M. Morel and G.Yu, ASIFT: A New Framework for Fully Affine Invariant Image
// Comparison, SIAM Journal on Imaging Sciences, vol. 2, issue 2, pp. 438-469, 2009.
// Reference: ASIFT online demo (You can try ASIFT with your own images online.)
// http://www.ipol.im/pub/algo/my_affine_sift/
/*---------------------------------------------------------------------------*/
#include <assert.h>
#include <stdlib.h>
#include <stdio.h>
#include <math.h>
#include <time.h>
#include "compute_asift_keypoints.h"
#ifdef _OPENMP
#include <omp.h>
#endif
#define ABS(x) (((x) > 0) ? (x) : (-(x)))
/* InitSigma gives the amount of smoothing applied to the image at the
first level of each octave. In effect, this determines the sampling
needed in the image domain relative to amount of smoothing. Good
values determined experimentally are in the range 1.2 to 1.8.
*/
/* float InitSigma_aa = 1.0;*/
static float InitSigma_aa = 1.6;
#define round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5))
/* Gaussian convolution kernels are truncated at this many sigmas from
the center. While it is more efficient to keep this value small,
experiments show that for consistent scale-space analysis it needs
a value of about 3.0, at which point the Gaussian has fallen to
only 1% of its central value. A value of 2.0 greatly reduces
keypoint consistency, and a value of 4.0 is better than 3.0.
*/
const float GaussTruncate1 = 4.0;
/* --------------------------- Blur image --------------------------- */
/* Same as ConvBuffer, but implemented with loop unrolling for increased
speed. This is the most time intensive routine in keypoint detection,
so deserves careful attention to efficiency. Loop unrolling simply
sums 5 multiplications at a time to allow the compiler to schedule
operations better and avoid loop overhead. This almost triples
speed of previous version on a Pentium with gcc.
*/
void ConvBufferFast(float *buffer, float *kernel, int rsize, int ksize)
{
int i;
float *bp, *kp, *endkp;
float sum;
for (i = 0; i < rsize; i++) {
sum = 0.0;
bp = &buffer[i];
kp = &kernel[0];
endkp = &kernel[ksize];
/* Loop unrolling: do 5 multiplications at a time. */
// while (kp + 4 < endkp) {
// sum += (double) bp[0] * (double) kp[0] + (double) bp[1] * (double) kp[1] + (double) bp[2] * (double) kp[2] +
// (double) bp[3] * (double) kp[3] + (double) bp[4] * (double) kp[4];
// bp += 5;
// kp += 5;
// }
// /* Do 2 multiplications at a time on remaining items. */
// while (kp + 1 < endkp) {
// sum += (double) bp[0] * (double) kp[0] + (double) bp[1] * (double) kp[1];
// bp += 2;
// kp += 2;
// }
// /* Finish last one if needed. */
// if (kp < endkp) {
// sum += (double) *bp * (double) *kp;
// }
while (kp < endkp) {
sum += *bp++ * *kp++;
}
buffer[i] = sum;
}
}
/* Convolve image with the 1-D kernel vector along image rows. This
is designed to be as efficient as possible. Pixels outside the
image are set to the value of the closest image pixel.
*/
void ConvHorizontal(vector<float>& image, int width, int height, float *kernel, int ksize)
{
int rows, cols, r, c, i, halfsize;
float buffer[4000];
vector<float> pixels(width*height);
rows = height;
cols = width;
halfsize = ksize / 2;
pixels = image;
assert(cols + ksize < 4000);
for (r = 0; r < rows; r++) {
/* Copy the row into buffer with pixels at ends replicated for
half the mask size. This avoids need to check for ends
within inner loop. */
for (i = 0; i < halfsize; i++)
buffer[i] = pixels[r*cols];
for (i = 0; i < cols; i++)
buffer[halfsize + i] = pixels[r*cols+i];
for (i = 0; i < halfsize; i++)
buffer[halfsize + cols + i] = pixels[r*cols+cols-1];
ConvBufferFast(buffer, kernel, cols, ksize);
for (c = 0; c < cols; c++)
pixels[r*cols+c] = buffer[c];
}
image = pixels;
}
/* Same as ConvHorizontal, but apply to vertical columns of image.
*/
void ConvVertical(vector<float>& image, int width, int height, float *kernel, int ksize)
{
int rows, cols, r, c, i, halfsize;
float buffer[4000];
vector<float> pixels(width*height);
rows = height;
cols = width;
halfsize = ksize / 2;
pixels = image;
assert(rows + ksize < 4000);
for (c = 0; c < cols; c++) {
for (i = 0; i < halfsize; i++)
buffer[i] = pixels[c];
for (i = 0; i < rows; i++)
buffer[halfsize + i] = pixels[i*cols+c];
for (i = 0; i < halfsize; i++)
buffer[halfsize + rows + i] = pixels[(rows - 1)*cols+c];
ConvBufferFast(buffer, kernel, rows, ksize);
for (r = 0; r < rows; r++)
pixels[r*cols+c] = buffer[r];
}
image = pixels;
}
/* 1D Convolve image with a Gaussian of width sigma and store result back
in image. This routine creates the Gaussian kernel, and then applies
it in horizontal (flag_dir=0) OR vertical directions (flag_dir!=0).
*/
void GaussianBlur1D(vector<float>& image, int width, int height, float sigma, int flag_dir)
{
float x, kernel[100], sum = 0.0;
int ksize, i;
/* The Gaussian kernel is truncated at GaussTruncate sigmas from
center. The kernel size should be odd.
*/
ksize = (int)(2.0 * GaussTruncate1 * sigma + 1.0);
ksize = MAX(3, ksize); /* Kernel must be at least 3. */
if (ksize % 2 == 0) /* Make kernel size odd. */
ksize++;
assert(ksize < 100);
/* Fill in kernel values. */
for (i = 0; i <= ksize; i++) {
x = i - ksize / 2;
kernel[i] = exp(- x * x / (2.0 * sigma * sigma));
sum += kernel[i];
}
/* Normalize kernel values to sum to 1.0. */
for (i = 0; i < ksize; i++)
kernel[i] /= sum;
if (flag_dir == 0)
{
ConvHorizontal(image, width, height, kernel, ksize);
}
else
{
ConvVertical(image, width, height, kernel, ksize);
}
}
void compensate_affine_coor1(float *x0, float *y0, int w1, int h1, float t1, float t2, float Rtheta)
{
float x_ori, y_ori;
float x_tmp, y_tmp;
float x1 = *x0;
float y1 = *y0;
Rtheta = Rtheta*PI/180;
if ( Rtheta <= PI/2 )
{
x_ori = 0;
y_ori = w1 * sin(Rtheta) / t1;
}
else
{
x_ori = -w1 * cos(Rtheta) / t2;
y_ori = ( w1 * sin(Rtheta) + h1 * sin(Rtheta-PI/2) ) / t1;
}
float sin_Rtheta = sin(Rtheta);
float cos_Rtheta = cos(Rtheta);
/* project the coordinates of im1 to original image before tilt-rotation transform */
/* Get the coordinates with respect to the 'origin' of the original image before transform */
x1 = x1 - x_ori;
y1 = y1 - y_ori;
/* Invert tilt */
x1 = x1 * t2;
y1 = y1 * t1;
/* Invert rotation (Note that the y direction (vertical) is inverse to the usual concention. Hence Rtheta instead of -Rtheta to inverse the rotation.) */
x_tmp = cos_Rtheta*x1 - sin_Rtheta*y1;
y_tmp = sin_Rtheta*x1 + cos_Rtheta*y1;
x1 = x_tmp;
y1 = y_tmp;
*x0 = x1;
*y0 = y1;
}
/* -------------- MAIN FUNCTION ---------------------- */
int compute_asift_keypoints(vector<float>& image, int width, int height, int num_of_tilts, int verb, vector< vector< keypointslist > >& keys_all, siftPar &siftparameters)
// Compute ASIFT keypoints in the input image.
// Input:
// image: input image
// width, height: width and height of the input image.
// num_of_tilts: number of tilts to simulate.
// verb: 1/0 --> show/don not show verbose messages. (1 for debugging)
// keys_all (output): ASIFT keypoints. It is a 2D matrix with varying rows and columns. Each entry keys_all[tt][rr]
// stores the SIFT keypoints calculated on the image with the simulated tilt index tt and simulated rotation index rr (see the code below). In the coordinates of the keypoints,
// the affine distortions have been compensated.
// siftparameters: SIFT parameters.
//
// Output: the number of keypoints
{
vector<float> image_t, image_tmp1, image_tmp;
float t_min, t_k;
int num_tilt, tt, num_rot_t2, rr;
int fproj_o;
float fproj_p, fproj_bg;
char fproj_i;
float *fproj_x4, *fproj_y4;
// float frot_b=0;
float frot_b=128;
char *frot_k;
int counter_sim=0, num_sim;
int flag_dir = 1;
float BorderFact=6*sqrt(2.);
int num_keys_total=0;
fproj_o = 3;
fproj_p = 0;
fproj_i = 0;
fproj_bg = 0;
fproj_x4 = 0;
fproj_y4 = 0;
frot_k = 0;
num_rot_t2 = 10;
t_min = 1;
t_k = sqrt(2.);
num_tilt = num_of_tilts;
if ( num_tilt < 1)
{
printf("Number of tilts num_tilt should be equal or larger than 1. \n");
exit(-1);
}
image_tmp1 = image;
/* Calculate the number of simulations, and initialize keys_all */
keys_all = std::vector< vector< keypointslist > >(num_tilt);
for (tt = 1; tt <= num_tilt; tt++)
{
float t = t_min * pow(t_k, tt-1);
if ( t == 1 )
{
counter_sim ++;
keys_all[tt-1] = std::vector< keypointslist >(1);
}
else
{
int num_rot1 = round(num_rot_t2*t/2);
if ( num_rot1%2 == 1 )
{
num_rot1 = num_rot1 + 1;
}
num_rot1 = num_rot1 / 2;
counter_sim += num_rot1;
keys_all[tt-1] = std::vector< keypointslist >(num_rot1);
}
}
num_sim = counter_sim;
if ( verb )
{
printf("%d affine simulations will be performed. \n", num_sim);
}
counter_sim = 0;
/* Affine simulation (rotation+tilt simulation) */
// Loop on tilts.
#ifdef _OPENMP
omp_set_nested(1);
#endif
#pragma omp parallel for private(tt)
for (tt = 1; tt <= num_tilt; tt++)
{
float t = t_min * pow(t_k, tt-1);
float t1 = 1;
float t2 = 1/t;
// If tilt t = 1, do not simulate rotation.
if ( t == 1 )
{
// copy the image from vector to array as compute_sift_keypoints uses only array.
float *image_tmp1_float = new float[width*height];
for (int cc = 0; cc < width*height; cc++)
image_tmp1_float[cc] = image_tmp1[cc];
compute_sift_keypoints(image_tmp1_float,keys_all[tt-1][0],width,height,siftparameters);
delete[] image_tmp1_float;
}
else
{
// The number of rotations to simulate under the current tilt.
int num_rot1 = round(num_rot_t2*t/2);
if ( num_rot1%2 == 1 )
{
num_rot1 = num_rot1 + 1;
}
num_rot1 = num_rot1 / 2;
float delta_theta = PI/num_rot1;
// Loop on rotations.
#pragma omp parallel for private(rr)
for ( int rr = 1; rr <= num_rot1; rr++ )
{
float theta = delta_theta * (rr-1);
theta = theta * 180 / PI;
vector<float> image_t;
int width_r, height_r;
// simulate a rotation: rotate the image with an angle theta. (the outside of the rotated image are padded with the value frot_b)
frot(image, image_t, width, height, &width_r, &height_r, &theta, &frot_b , frot_k);
/* Tilt */
int width_t = (int) (width_r * t1);
int height_t = (int) (height_r * t2);
int fproj_sx = width_t;
int fproj_sy = height_t;
float fproj_x1 = 0;
float fproj_y1 = 0;
float fproj_x2 = width_t;
float fproj_y2 = 0;
float fproj_x3 = 0;
float fproj_y3 = height_t;
/* Anti-aliasing filtering along vertical direction */
/* sigma_aa = InitSigma_aa * log2(t);*/
float sigma_aa = InitSigma_aa * t / 2;
GaussianBlur1D(image_t,width_r,height_r,sigma_aa,flag_dir);
// simulate a tilt: subsample the image along the vertical axis by a factor of t.
vector<float> image_tmp(width_t*height_t);
fproj (image_t, image_tmp, width_r, height_r, &fproj_sx, &fproj_sy, &fproj_bg, &fproj_o, &fproj_p, &fproj_i , fproj_x1 , fproj_y1 , fproj_x2 , fproj_y2 , fproj_x3 , fproj_y3, fproj_x4, fproj_y4);
vector<float> image_tmp1 = image_tmp;
if ( verb )
{
printf("Rotation theta = %.2f, Tilt t = %.2f. w=%d, h=%d, sigma_aa=%.2f, \n", theta, t, width_t, height_t, sigma_aa);
}
float *image_tmp1_float = new float[width_t*height_t];
for (int cc = 0; cc < width_t*height_t; cc++)
image_tmp1_float[cc] = image_tmp1[cc];
// compute SIFT keypoints on simulated image.
keypointslist keypoints;
keypointslist keypoints_filtered;
compute_sift_keypoints(image_tmp1_float,keypoints,width_t,height_t,siftparameters);
delete[] image_tmp1_float;
/* check if the keypoint is located on the boundary of the parallelogram (i.e., the boundary of the distorted input image). If so, remove it to avoid boundary artifacts. */
if ( keypoints.size() != 0 )
{
for ( int cc = 0; cc < (int) keypoints.size(); cc++ )
{
float x0, y0, x1, y1, x2, y2, x3, y3 ,x4, y4, d1, d2, d3, d4, scale1, theta1, sin_theta1, cos_theta1, BorderTh;
x0 = keypoints[cc].x;
y0 = keypoints[cc].y;
scale1= keypoints[cc].scale;
theta1 = theta * PI / 180;
sin_theta1 = sin(theta1);
cos_theta1 = cos(theta1);
/* the coordinates of the 4 submits of the parallelogram */
if ( theta <= 90 )
{
x1 = height * sin_theta1;
y1 = 0;
y2 = width * sin_theta1;
x3 = width * cos_theta1;
x4 = 0;
y4 = height * cos_theta1;
x2 = x1 + x3;
y3 = y2 + y4;
/* note that the vertical direction goes from top to bottom!!!
The calculation above assumes that the vertical direction goes from the bottom to top. Thus the vertical coordinates need to be reversed!!! */
y1 = y3 - y1;
y2 = y3 - y2;
y4 = y3 - y4;
y3 = 0;
y1 = y1 * t2;
y2 = y2 * t2;
y3 = y3 * t2;
y4 = y4 * t2;
}
else
{
y1 = -height * cos_theta1;
x2 = height * sin_theta1;
x3 = 0;
y3 = width * sin_theta1;
x4 = -width * cos_theta1;
y4 = 0;
x1 = x2 + x4;
y2 = y1 + y3;
/* note that the vertical direction goes from top to bottom!!!
The calculation above assumes that the vertical direction goes from the bottom to top. Thus the vertical coordinates need to be reversed!!! */
y1 = y2 - y1;
y3 = y2 - y3;
y4 = y2 - y4;
y2 = 0;
y1 = y1 * t2;
y2 = y2 * t2;
y3 = y3 * t2;
y4 = y4 * t2;
}
/* the distances from the keypoint to the 4 sides of the parallelogram */
d1 = ABS((x2-x1)*(y1-y0)-(x1-x0)*(y2-y1)) / sqrt((x2-x1)*(x2-x1)+(y2-y1)*(y2-y1));
d2 = ABS((x3-x2)*(y2-y0)-(x2-x0)*(y3-y2)) / sqrt((x3-x2)*(x3-x2)+(y3-y2)*(y3-y2));
d3 = ABS((x4-x3)*(y3-y0)-(x3-x0)*(y4-y3)) / sqrt((x4-x3)*(x4-x3)+(y4-y3)*(y4-y3));
d4 = ABS((x1-x4)*(y4-y0)-(x4-x0)*(y1-y4)) / sqrt((x1-x4)*(x1-x4)+(y1-y4)*(y1-y4));
BorderTh = BorderFact*scale1;
if (!((d1<BorderTh) || (d2<BorderTh) || (d3<BorderTh) || (d4<BorderTh) ))
{
// Normalize the coordinates of the matched points by compensate the simulate affine transformations
compensate_affine_coor1(&x0, &y0, width, height, 1/t2, t1, theta);
keypoints[cc].x = x0;
keypoints[cc].y = y0;
keypoints_filtered.push_back(keypoints[cc]);
}
}
}
keys_all[tt-1][rr-1] = keypoints_filtered;
}
}
}
{
for (tt = 0; tt < (int) keys_all.size(); tt++)
for (rr = 0; rr < (int) keys_all[tt].size(); rr++)
{
num_keys_total += (int) keys_all[tt][rr].size();
}
printf("%d ASIFT keypoints are detected. \n", num_keys_total);
}
return num_keys_total;
}

View file

@ -0,0 +1,53 @@
// Copyright (c) 2008-2011, Guoshen Yu <yu@cmap.polytechnique.fr>
// Copyright (c) 2008-2011, Jean-Michel Morel <morel@cmla.ens-cachan.fr>
//
// WARNING:
// This file implements an algorithm possibly linked to the patent
//
// Jean-Michel Morel and Guoshen Yu, Method and device for the invariant
// affine recognition recognition of shapes (WO/2009/150361), patent pending.
//
// This file is made available for the exclusive aim of serving as
// scientific tool to verify of the soundness and
// completeness of the algorithm description. Compilation,
// execution and redistribution of this file may violate exclusive
// patents rights in certain countries.
// The situation being different for every country and changing
// over time, it is your responsibility to determine which patent
// rights restrictions apply to you before you compile, use,
// modify, or redistribute this file. A patent lawyer is qualified
// to make this determination.
// If and only if they don't conflict with any patent terms, you
// can benefit from the following license terms attached to this
// file.
//
// This program is provided for scientific and educational only:
// you can use and/or modify it for these purposes, but you are
// not allowed to redistribute this work or derivative works in
// source or executable form. A license must be obtained from the
// patent right holders for any other use.
//
//
//*------------------------ compute_asift_keypoints -------------------------*/
// Compute the ASIFT keypoints on the input image.
//
// Please report bugs and/or send comments to Guoshen Yu yu@cmap.polytechnique.fr
//
// Reference: J.M. Morel and G.Yu, ASIFT: A New Framework for Fully Affine Invariant Image
// Comparison, SIAM Journal on Imaging Sciences, vol. 2, issue 2, pp. 438-469, 2009.
// Reference: ASIFT online demo (You can try ASIFT with your own images online.)
// http://www.ipol.im/pub/algo/my_affine_sift/
/*---------------------------------------------------------------------------*/
#include "library.h"
#include "demo_lib_sift.h"
#include "frot.h"
#include "fproj.h"
#include <vector>
using namespace std;
int compute_asift_keypoints(vector<float>& image, int width, int height, int num_of_tilts, int verb, vector< vector< keypointslist > >& keys_all, siftPar &siftparameters);
void GaussianBlur1D(vector<float>& image, int width, int height, float sigma, int flag_dir);

View file

@ -0,0 +1,791 @@
// Copyright (c) 2008-2011, Guoshen Yu <yu@cmap.polytechnique.fr>
// Copyright (c) 2008-2011, Jean-Michel Morel <morel@cmla.ens-cachan.fr>
//
// WARNING:
// This file implements an algorithm possibly linked to the patent
//
// Jean-Michel Morel and Guoshen Yu, Method and device for the invariant
// affine recognition recognition of shapes (WO/2009/150361), patent pending.
//
// This file is made available for the exclusive aim of serving as
// scientific tool to verify of the soundness and
// completeness of the algorithm description. Compilation,
// execution and redistribution of this file may violate exclusive
// patents rights in certain countries.
// The situation being different for every country and changing
// over time, it is your responsibility to determine which patent
// rights restrictions apply to you before you compile, use,
// modify, or redistribute this file. A patent lawyer is qualified
// to make this determination.
// If and only if they don't conflict with any patent terms, you
// can benefit from the following license terms attached to this
// file.
//
// This program is provided for scientific and educational only:
// you can use and/or modify it for these purposes, but you are
// not allowed to redistribute this work or derivative works in
// source or executable form. A license must be obtained from the
// patent right holders for any other use.
//
//
//*------------------------ compute_asift_matches-- -------------------------*/
// Match the ASIFT keypoints.
//
// Please report bugs and/or send comments to Guoshen Yu yu@cmap.polytechnique.fr
//
// Reference: J.M. Morel and G.Yu, ASIFT: A New Framework for Fully Affine Invariant Image
// Comparison, SIAM Journal on Imaging Sciences, vol. 2, issue 2, pp. 438-469, 2009.
// Reference: ASIFT online demo (You can try ASIFT with your own images online.)
// http://www.ipol.im/pub/algo/my_affine_sift/
/*---------------------------------------------------------------------------*/
#include <assert.h>
#include <stdio.h>
#include <stdlib.h>
#include <math.h>
#include <time.h>
#ifdef _OPENMP
#include <omp.h>
#endif
#include "compute_asift_matches.h"
#include "libMatch/match.h"
#include "orsa.h"
#define round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5))
/* Remove the repetitive matches that appear in different simulations and retain only one */
void unique_match1(matchingslist &seg_in, matchingslist &seg_out, vector< vector <float> > &Minfoall_in, vector< vector <float> > &Minfoall_out)
{
int i_in, i_out;
float x1_in, x2_in, y1_in, y2_in, x1_out, x2_out, y1_out, y2_out;
int flag_unique;
float d1, d2;
int Th2 = 2;
seg_out.push_back(seg_in[0]);
Minfoall_out.push_back(Minfoall_in[0]);
/* For other matches */
if ( seg_in.size() > 1 )
{
/* check if a match is unique. if yes, copy */
/* Bug fix by Xiaoyu Sun (Sichuan university) (Dec 13, 2015) */
/* Original version
matchingslist::iterator ptr_in = seg_in.begin();
for ( i_in = 1; i_in < (int) seg_in.size(); i_in++, ptr_in++ )
*/
/* Bug fixed */
matchingslist::iterator ptr_in = seg_in.begin();
ptr_in++;
for ( i_in = 1; i_in < (int) seg_in.size(); i_in++, ptr_in++ )
{
x1_in = ptr_in->first.x;
y1_in = ptr_in->first.y;
x2_in = ptr_in->second.x;
y2_in = ptr_in->second.y;
flag_unique = 1;
matchingslist::iterator ptr_out = seg_out.begin();
for ( i_out = 0; i_out < (int) seg_out.size(); i_out++, ptr_out++ )
{
x1_out = ptr_out->first.x;
y1_out = ptr_out->first.y;
x2_out = ptr_out->second.x;
y2_out = ptr_out->second.y;
d1 = (x1_in - x1_out)*(x1_in - x1_out) + (y1_in - y1_out)*(y1_in - y1_out);
d2 = (x2_in - x2_out)*(x2_in - x2_out) + (y2_in - y2_out)*(y2_in - y2_out);
if ( ( d1 <= Th2) && ( d2 <= Th2) )
{
flag_unique = 0;
continue;
}
}
if ( flag_unique == 1 )
{
seg_out.push_back(seg_in[i_in]);
Minfoall_out.push_back(Minfoall_in[i_in]);
}
}
}
}
/* Remove the ALL one-to-multiple matches. */
void clean_match1(matchingslist &seg_in, matchingslist &seg_out, vector< vector <float> > &Minfoall_in, vector< vector <float> > &Minfoall_out)
{
int i1, i2;
float x1_in, x2_in, y1_in, y2_in, x1_out, x2_out, y1_out, y2_out;
// Guoshen Yu, 2010.09.22, Windows version
// int flag_unique[seg_in.size()];
int tmp_size = seg_in.size();
int *flag_unique = new int[tmp_size];
int sum_flag=0;
float d1, d2;
int Th1 = 1;
int Th2 = 4;
for ( i1 = 0; i1 < (int) seg_in.size(); i1++ )
{
flag_unique[i1] = 1;
}
/* Set the flag of redundant matches to 0. */
matchingslist::iterator ptr_in = seg_in.begin();
for ( i1 = 0; i1 < (int) seg_in.size() - 1; i1++, ptr_in++ )
{
x1_in = ptr_in->first.x;
y1_in = ptr_in->first.y;
x2_in = ptr_in->second.x;
y2_in = ptr_in->second.y;
matchingslist::iterator ptr_out = ptr_in+1;
for ( i2 = i1 + 1; i2 < (int) seg_in.size(); i2++, ptr_out++ )
{
x1_out = ptr_out->first.x;
y1_out = ptr_out->first.y;
x2_out = ptr_out->second.x;
y2_out = ptr_out->second.y;
d1 = (x1_in - x1_out)*(x1_in - x1_out) + (y1_in - y1_out)*(y1_in - y1_out);
d2 = (x2_in - x2_out)*(x2_in - x2_out) + (y2_in - y2_out)*(y2_in - y2_out);
/* If redundant, set flags of both elements to 0.*/
if ( ( ( d1 <= Th1) && ( d2 > Th2) ) || ( ( d1 > Th2) && ( d2 <= Th1) ) )
{
flag_unique[i1] = 0;
flag_unique[i2] = 0;
}
}
}
for ( i1 = 0; i1 < (int) seg_in.size(); i1++ )
{
sum_flag += flag_unique[i1];
}
/* Copy the matches that are not redundant */
if ( sum_flag > 0 )
{
for ( i1 = 0; i1 < (int) seg_in.size(); i1++ )
{
if ( flag_unique[i1] == 1 )
{
seg_out.push_back(seg_in[i1]);
Minfoall_out.push_back(Minfoall_in[i1]);
}
}
}
else
{
printf("Warning: all matches are redundant and are thus removed! This step of match cleaning is short circuited. (Normally this should not happen...)\n");
}
// Guoshen Yu, 2010.09.22, Windows version
delete [] flag_unique;
}
/* Remove the ALL multiple-to-one matches */
void clean_match2(matchingslist &seg_in, matchingslist &seg_out, vector< vector <float> > &Minfoall_in, vector< vector <float> > &Minfoall_out)
{
int i1, i2;
float x1_in, x2_in, y1_in, y2_in, x1_out, x2_out, y1_out, y2_out;
// Guoshen Yu, 2010.09.22, Windows version
// int flag_unique[seg_in.size()];
int tmp_size = seg_in.size();
int *flag_unique = new int[tmp_size];
int sum_flag=0;
float d1, d2;
int Th1 = 1;
int Th2 = 4;
for ( i1 = 0; i1 < (int) seg_in.size(); i1++ )
{
flag_unique[i1] = 1;
}
/* Set the flag of redundant matches to 0. */
matchingslist::iterator ptr_in = seg_in.begin();
for ( i1 = 0; i1 < (int) seg_in.size() - 1; i1++, ptr_in++ )
{
x1_in = ptr_in->first.x;
y1_in = ptr_in->first.y;
x2_in = ptr_in->second.x;
y2_in = ptr_in->second.y;
matchingslist::iterator ptr_out = ptr_in+1;
for ( i2 = i1 + 1; i2 < (int) seg_in.size(); i2++, ptr_out++ )
{
x1_out = ptr_out->first.x;
y1_out = ptr_out->first.y;
x2_out = ptr_out->second.x;
y2_out = ptr_out->second.y;
d1 = (x1_in - x1_out)*(x1_in - x1_out) + (y1_in - y1_out)*(y1_in - y1_out);
d2 = (x2_in - x2_out)*(x2_in - x2_out) + (y2_in - y2_out)*(y2_in - y2_out);
/* If redundant, set flags of both elements to 0.*/
if ( ( d1 > Th2) && ( d2 <= Th1) )
{
flag_unique[i1] = 0;
flag_unique[i2] = 0;
}
}
}
for ( i1 = 0; i1 < (int) seg_in.size(); i1++ )
{
sum_flag += flag_unique[i1];
}
/* Copy the matches that are not redundant */
if ( sum_flag > 0 )
{
for ( i1 = 0; i1 < (int) seg_in.size(); i1++ )
{
if ( flag_unique[i1] == 1 )
{
seg_out.push_back(seg_in[i1]);
Minfoall_out.push_back(Minfoall_in[i1]);
}
}
}
else
{
printf("Warning: all matches are redundant and are thus removed! This step of match cleaning is short circuited. (Normally this should not happen...)\n");
}
// Guoshen Yu, 2010.09.22, Windows version
delete [] flag_unique;
}
// Normalize the coordinates of the matched points by compensating the simulate affine transformations
void compensate_affine_coor(matching &matching1, int w1, int h1, int w2, int h2, float t1, float t2, float Rtheta, float t_im2_1, float t_im2_2, float Rtheta2)
{
float x_ori, y_ori;
float x_ori2, y_ori2, x_tmp, y_tmp;
float x1, y1, x2, y2;
Rtheta = Rtheta*PI/180;
if ( Rtheta <= PI/2 )
{
x_ori = 0;
y_ori = w1 * sin(Rtheta) / t1;
}
else
{
x_ori = -w1 * cos(Rtheta) / t2;
y_ori = ( w1 * sin(Rtheta) + h1 * sin(Rtheta-PI/2) ) / t1;
}
Rtheta2 = Rtheta2*PI/180;
if ( Rtheta2 <= PI/2 )
{
x_ori2 = 0;
y_ori2 = w2 * sin(Rtheta2) / t_im2_1;
}
else
{
x_ori2 = -w2 * cos(Rtheta2) / t_im2_2;
y_ori2 = ( w2 * sin(Rtheta2) + h2 * sin(Rtheta2-PI/2) ) / t_im2_1;
}
float sin_Rtheta = sin(Rtheta);
float cos_Rtheta = cos(Rtheta);
float sin_Rtheta2 = sin(Rtheta2);
float cos_Rtheta2 = cos(Rtheta2);
x1 = matching1.first.x;
y1 = matching1.first.y;
x2 = matching1.second.x;
y2 = matching1.second.y;
/* project the coordinates of im1 to original image before tilt-rotation transform */
/* Get the coordinates with respect to the 'origin' of the original image before transform */
x1 = x1 - x_ori;
y1 = y1 - y_ori;
/* Invert tilt */
x1 = x1 * t2;
y1 = y1 * t1;
/* Invert rotation (Note that the y direction (vertical) is inverse to the usual concention. Hence Rtheta instead of -Rtheta to inverse the rotation.) */
x_tmp = cos_Rtheta*x1 - sin_Rtheta*y1;
y_tmp = sin_Rtheta*x1 + cos_Rtheta*y1;
x1 = x_tmp;
y1 = y_tmp;
/* Coordinate projection on image2 */
/* Get the coordinates with respect to the 'origin' of the original image before transform */
x2 = x2 - x_ori2;
y2 = y2 - y_ori2;
/* Invert tilt */
x2 = x2 * t_im2_2;
y2 = y2 * t_im2_1;
/* Invert rotation (Note that the y direction (vertical) is inverse to the usual concention. Hence Rtheta instead of -Rtheta to inverse the rotation.) */
x_tmp = cos_Rtheta2*x2 - sin_Rtheta2*y2;
y_tmp = sin_Rtheta2*x2 + cos_Rtheta2*y2;
x2 = x_tmp;
y2 = y_tmp;
matching1.first.x = x1;
matching1.first.y = y1;
matching1.second.x = x2;
matching1.second.y = y2;
}
int compute_asift_matches(int num_of_tilts1, int num_of_tilts2, int w1, int h1, int w2, int h2, int verb, vector< vector< keypointslist > >& keys1, vector< vector< keypointslist > >& keys2, matchingslist &matchings, siftPar &siftparameters)
// Match the ASIFT keypoints.
// Input:
// num_of_tilts1, num_of_tilts2: number of tilts that have been simulated on the two images. (They can be different.)
// w1, h1, w2, h2: widht/height of image1/image2.
// verb: 1/0 --> show/don not show verbose messages. (1 for debugging)
// keys1, keys2: ASIFT keypoints of image1/image2. (They should be calculated with compute_asift_keypoints.)
// matchings (output): the coordinates (col1, row1, col2, row2) of all the matching points.
//
// Output: the number of matching points.
{
float t_min, t_k, t;
int num_tilt1, num_tilt2, tt, num_rot_t2, num_rot1, rr;
int cc;
int tt2, rr2, num_rot1_2;
float t_im2;
/* It stores the coordinates of ALL matches points of ALL affine simulations */
vector< vector <float> > Minfoall;
int Tmin = 8;
float nfa_max = -2;
num_rot_t2 = 10;
t_min = 1;
t_k = sqrt(2.);
num_tilt1 = num_of_tilts1;
num_tilt2 = num_of_tilts2;
if ( ( num_tilt1 < 1 ) || ( num_tilt2 < 1 ) )
{
printf("Number of tilts num_tilt should be equal or larger than 1. \n");
exit(-1);
}
/* Initialize the vector structure for the matching points */
std::vector< vector< vector < vector < matchingslist > > > > matchings_vec(num_tilt1);
std::vector< vector< vector< vector< vector< vector <float> > > > > > Minfoall_vec(num_tilt1);
for (tt = 1; tt <= num_tilt1; tt++)
{
t = t_min * pow(t_k, tt-1);
if ( t == 1 )
{
num_rot1 = 1;
}
else
{
num_rot1 = round(num_rot_t2*t/2);
if ( num_rot1%2 == 1 )
{
num_rot1 = num_rot1 + 1;
}
num_rot1 = num_rot1 / 2;
}
matchings_vec[tt-1].resize(num_rot1);
Minfoall_vec[tt-1].resize(num_rot1);
for ( rr = 1; rr <= num_rot1; rr++ )
{
matchings_vec[tt-1][rr-1].resize(num_tilt2);
Minfoall_vec[tt-1][rr-1].resize(num_tilt2);
for (tt2 = 1; tt2 <= num_tilt2; tt2++)
{
t_im2 = t_min * pow(t_k, tt2-1);
if ( t_im2 == 1 )
{
num_rot1_2 = 1;
}
else
{
num_rot1_2 = round(num_rot_t2*t_im2/2);
if ( num_rot1_2%2 == 1 )
{
num_rot1_2 = num_rot1_2 + 1;
}
num_rot1_2 = num_rot1_2 / 2;
}
matchings_vec[tt-1][rr-1][tt2-1].resize(num_rot1_2);
Minfoall_vec[tt-1][rr-1][tt2-1].resize(num_rot1_2);
}
}
}
///*
// * setup the tilt and rotation parameters
// * for all the loops, this vector will hold
// * the following parameters:
// * tt, num_rot1, rr, tt2, num_rot1_2, rr2
// */
//vector<int> tilt_rot;
///* loop on tilts for image 1 */
//for (int tt = 1; tt <= num_tilt1; tt++)
//{
// float t = t_min * pow(t_k, tt-1);
// int num_rot1;
// /* if tilt t = 1, do not simulate rotation. */
// if ( 1 == tt )
// num_rot1 = 1;
// else
// {
// /* number of rotations to simulate */
// num_rot1 = round(num_rot_t2 * t / 2);
// if ( num_rot1%2 == 1 )
// num_rot1 = num_rot1 + 1;
// num_rot1 = num_rot1 / 2;
// }
// /* loop on rotations for image 1 */
// for (int rr = 1; rr <= num_rot1; rr++ )
// {
// /* loop on tilts for image 2 */
// for (int tt2 = 1; tt2 <= num_tilt2; tt2++)
// {
// float t_im2 = t_min * pow(t_k, tt2-1);
// int num_rot1_2;
// if ( tt2 == 1 )
// num_rot1_2 = 1;
// else
// {
// num_rot1_2 = round(num_rot_t2 * t_im2 / 2);
// if ( num_rot1_2%2 == 1 )
// num_rot1_2 = num_rot1_2 + 1;
// num_rot1_2 = num_rot1_2 / 2;
// }
// /* loop on rotations for image 2 */
// for (int rr2 = 1; rr2 <= num_rot1_2; rr2++ )
// {
// tilt_rot.push_back(tt);
// tilt_rot.push_back(num_rot1);
// tilt_rot.push_back(rr);
// tilt_rot.push_back(tt2);
// tilt_rot.push_back(num_rot1_2);
// tilt_rot.push_back(rr2);
// }
// }
// }
//}
/* Calculate the number of simulations */
#ifdef _OPENMP
omp_set_nested(1);
#endif
// loop on tilts for image 1.
#pragma omp parallel for private(tt)
for (int tt = 1; tt <= num_tilt1; tt++)
{
float t = t_min * pow(t_k, tt-1);
/* Attention: the t1, t2 do not follow the same convention as in compute_asift_keypoints */
float t1 = t;
float t2 = 1;
int num_rot1;
// If tilt t = 1, do not simulate rotation.
if ( tt == 1 )
{
num_rot1 = 1;
}
else
{
// The number of rotations to simulate under the current tilt.
num_rot1 = round(num_rot_t2*t/2);
if ( num_rot1%2 == 1 )
{
num_rot1 = num_rot1 + 1;
}
num_rot1 = num_rot1 / 2;
}
float delta_theta = PI/num_rot1;
// Loop on rotations for image 1.
#pragma omp parallel for private(rr)
for ( int rr = 1; rr <= num_rot1; rr++ )
{
float theta = delta_theta * (rr-1);
theta = theta * 180 / PI;
/* Read the keypoints of image 1 */
keypointslist keypoints1 = keys1[tt-1][rr-1];
// loop on tilts for image 2.
#pragma omp parallel for private(tt2)
for (int tt2 = 1; tt2 <= num_tilt2; tt2++)
{
float t_im2 = t_min * pow(t_k, tt2-1);
/* Attention: the t1, t2 do not follow the same convention as in asift_v1.c */
float t_im2_1 = t_im2;
float t_im2_2 = 1;
int num_rot1_2;
if ( tt2 == 1 )
{
num_rot1_2 = 1;
}
else
{
num_rot1_2 = round(num_rot_t2*t_im2/2);
if ( num_rot1_2%2 == 1 )
{
num_rot1_2 = num_rot1_2 + 1;
}
num_rot1_2 = num_rot1_2 / 2;
}
float delta_theta2 = PI/num_rot1_2;
#pragma omp parallel for private(rr2)
// Loop on rotations for image 2.
for ( int rr2 = 1; rr2 <= num_rot1_2; rr2++ )
{
float theta2 = delta_theta2 * (rr2-1);
theta2 = theta2 * 180 / PI;
/* Read the keypoints of image2. */
keypointslist keypoints2 = keys2[tt2-1][rr2-1];
// Match the keypoints of image1 and image2.
matchingslist matchings1;
compute_sift_matches(keypoints1,keypoints2,matchings1,siftparameters);
if ( verb )
{
printf("t1=%.2f, theta1=%.2f, num keys1 = %d, t2=%.2f, theta2=%.2f, num keys2 = %d, num matches=%d\n", t, theta, (int) keypoints1.size(), t_im2, theta2, (int) keypoints2.size(), (int) matchings1.size());
}
/* Store the matches */
if ( matchings1.size() > 0 )
{
matchings_vec[tt-1][rr-1][tt2-1][rr2-1] = matchingslist(matchings1.size());
Minfoall_vec[tt-1][rr-1][tt2-1][rr2-1].resize(matchings1.size());
for ( int cc = 0; cc < (int) matchings1.size(); cc++ )
{
///// In the coordinates the affine transformations have been normalized already in compute_asift_keypoints. So no need to normalize here.
// Normalize the coordinates of the matched points by compensating the simulate affine transformations
// compensate_affine_coor(matchings1[cc], w1, h1, w2, h2, t1, t2, theta, t_im2_1, t_im2_2, theta2);
matchings_vec[tt-1][rr-1][tt2-1][rr2-1][cc] = matchings1[cc];
vector<float> Minfo_1match(6);
Minfo_1match[0] = t1;
Minfo_1match[1] = t2;
Minfo_1match[2] = theta;
Minfo_1match[3] = t_im2_1;
Minfo_1match[4] = t_im2_2;
Minfo_1match[5] = theta2;
Minfoall_vec[tt-1][rr-1][tt2-1][rr2-1][cc] = Minfo_1match;
}
}
}
}
}
}
// Move the matches to a 1D vector
for (tt = 1; tt <= num_tilt1; tt++)
{
t = t_min * pow(t_k, tt-1);
if ( t == 1 )
{
num_rot1 = 1;
}
else
{
num_rot1 = round(num_rot_t2*t/2);
if ( num_rot1%2 == 1 )
{
num_rot1 = num_rot1 + 1;
}
num_rot1 = num_rot1 / 2;
}
for ( rr = 1; rr <= num_rot1; rr++ )
{
for (tt2 = 1; tt2 <= num_tilt2; tt2++)
{
t_im2 = t_min * pow(t_k, tt2-1);
if ( t_im2 == 1 )
{
num_rot1_2 = 1;
}
else
{
num_rot1_2 = round(num_rot_t2*t_im2/2);
if ( num_rot1_2%2 == 1 )
{
num_rot1_2 = num_rot1_2 + 1;
}
num_rot1_2 = num_rot1_2 / 2;
}
for ( rr2 = 1; rr2 <= num_rot1_2; rr2++ )
{
for ( cc=0; cc < (int) matchings_vec[tt-1][rr-1][tt2-1][rr2-1].size(); cc++ )
{
matchings.push_back(matchings_vec[tt-1][rr-1][tt2-1][rr2-1][cc]);
Minfoall.push_back(Minfoall_vec[tt-1][rr-1][tt2-1][rr2-1][cc]);
}
}
}
}
}
if ( verb )
{
printf("The number of matches is %d \n", (int) matchings.size());
}
if ( matchings.size() > 0 )
{
/* Remove the repetitive matches that appear in different simulations and retain only one. */
// Since tilts are simuated on both image 1 and image 2, it is normal to have repetitive matches.
matchingslist matchings_unique;
vector< vector<float> > Minfoall_unique;
unique_match1(matchings, matchings_unique, Minfoall, Minfoall_unique);
matchings = matchings_unique;
Minfoall = Minfoall_unique;
if ( verb )
{
printf("The number of unique matches is %d \n", (int) matchings.size());
}
// There often appear to be some one-to-multiple/multiple-to-one matches (one point in image 1 matches with many points in image 2/vice versa).
// This is an artifact of SIFT on interpolated images, as the interpolation tends to create some auto-similar structures (steps for example).
// These matches need to be removed.
/* Separating the removal of multiple-to-one and one-to-multiple in two steps:
- first remove multiple-to-one
- then remove one-to-multiple
This allows to avoid removing some good matches: multiple-to-one matches is much more frequent than one-to-multiple. Sometimes some of the feature points in image 1 that take part in "multiple-to-one" bad matches have also correct matches in image 2. The modified scheme avoid removing these good matches. */
// Remove to multiple-to-one matches
matchings_unique.clear();
Minfoall_unique.clear();
clean_match2(matchings, matchings_unique, Minfoall, Minfoall_unique);
matchings = matchings_unique;
Minfoall = Minfoall_unique;
// Remove to one-to-multiple matches
matchings_unique.clear();
Minfoall_unique.clear();
clean_match1(matchings, matchings_unique, Minfoall, Minfoall_unique);
matchings = matchings_unique;
Minfoall = Minfoall_unique;
if ( verb )
{
printf("The number of final matches is %d \n", (int) matchings.size());
}
// If enough matches to do epipolar filtering
if ( (int) matchings.size() >= Tmin )
{
//////// Use ORSA to filter out the incorrect matches.
// store the coordinates of the matching points
vector<Match> match_coor;
for ( cc = 0; cc < (int) matchings.size(); cc++ )
{
Match match1_coor;
match1_coor.x1 = matchings[cc].first.x;
match1_coor.y1 = matchings[cc].first.y;
match1_coor.x2 = matchings[cc].second.x;
match1_coor.y2 = matchings[cc].second.y;
match_coor.push_back(match1_coor);
}
std::vector<float> index;
// Guoshen Yu, 2010.09.23
// index.clear();
int t_value_orsa=10000;
int verb_value_orsa=0;
int n_flag_value_orsa=0;
int mode_value_orsa=2;
int stop_value_orsa=0;
// epipolar filtering with the Moisan-Stival ORSA algorithm.
// float nfa = orsa(w1, h1, match_coor, index, t_value_orsa, verb_value_orsa, n_flag_value_orsa, mode_value_orsa, stop_value_orsa);
float nfa = orsa((w1+w2)/2, (h1+h2)/2, match_coor, index, t_value_orsa, verb_value_orsa, n_flag_value_orsa, mode_value_orsa, stop_value_orsa);
// if the matching is significant, register the good matches
if ( nfa < nfa_max )
{
// extract meaningful matches
matchings_unique.clear();
Minfoall_unique.clear();
for ( cc = 0; cc < (int) index.size(); cc++ )
{
matchings_unique.push_back(matchings[(int)index[cc]]);
Minfoall_unique.push_back(Minfoall[(int)index[cc]]);
}
matchings = matchings_unique;
Minfoall = Minfoall_unique;
cout << "The two images match! " << matchings.size() << " matchings are identified. log(nfa)=" << nfa << "." << endl;
}
else
{
matchings.clear();
Minfoall.clear();
cout << "The two images do not match. The matching is not significant: log(nfa)=" << nfa << "." << endl;
}
}
else
{
matchings.clear();
Minfoall.clear();
cout << "The two images do not match. Not enough matches to do epipolar filtering." << endl;
}
}
else
{
cout << "The two images do not match.\n" << endl;
}
return matchings.size();
}

View file

@ -0,0 +1,51 @@
// Copyright (c) 2008-2011, Guoshen Yu <yu@cmap.polytechnique.fr>
// Copyright (c) 2008-2011, Jean-Michel Morel <morel@cmla.ens-cachan.fr>
//
// WARNING:
// This file implements an algorithm possibly linked to the patent
//
// Jean-Michel Morel and Guoshen Yu, Method and device for the invariant
// affine recognition recognition of shapes (WO/2009/150361), patent pending.
//
// This file is made available for the exclusive aim of serving as
// scientific tool to verify of the soundness and
// completeness of the algorithm description. Compilation,
// execution and redistribution of this file may violate exclusive
// patents rights in certain countries.
// The situation being different for every country and changing
// over time, it is your responsibility to determine which patent
// rights restrictions apply to you before you compile, use,
// modify, or redistribute this file. A patent lawyer is qualified
// to make this determination.
// If and only if they don't conflict with any patent terms, you
// can benefit from the following license terms attached to this
// file.
//
// This program is provided for scientific and educational only:
// you can use and/or modify it for these purposes, but you are
// not allowed to redistribute this work or derivative works in
// source or executable form. A license must be obtained from the
// patent right holders for any other use.
//
//
//*------------------------ compute_asift_matches-- -------------------------*/
// Match the ASIFT keypoints.
//
// Please report bugs and/or send comments to Guoshen Yu yu@cmap.polytechnique.fr
//
// Reference: J.M. Morel and G.Yu, ASIFT: A New Framework for Fully Affine Invariant Image
// Comparison, SIAM Journal on Imaging Sciences, vol. 2, issue 2, pp. 438-469, 2009.
// Reference: ASIFT online demo (You can try ASIFT with your own images online.)
// http://www.ipol.im/pub/algo/my_affine_sift/
/*---------------------------------------------------------------------------*/
#include "library.h"
#include "demo_lib_sift.h"
#include "frot.h"
#include "fproj.h"
#include <vector>
using namespace std;
int compute_asift_matches(int num_of_tilts1, int num_of_tilts2, int w1, int h1, int w2, int h2, int verb, vector< vector< keypointslist > >& keys1, vector< vector< keypointslist > >& keys2, matchingslist &matchings, siftPar &siftparameters);

1222
asift_match/src/demo_lib_sift.cpp Executable file

File diff suppressed because it is too large Load diff

298
asift_match/src/demo_lib_sift.h Executable file
View file

@ -0,0 +1,298 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
// WARNING:
// This file implements an algorithm possibly linked to the patent
//
// David Lowe "Method and apparatus for identifying scale invariant
// features in an image and use of same for locating an object in an
// image", U.S. Patent 6,711,293.
//
// This file is made available for the exclusive aim of serving as
// scientific tool to verify of the soundness and
// completeness of the algorithm description. Compilation,
// execution and redistribution of this file may violate exclusive
// patents rights in certain countries.
// The situation being different for every country and changing
// over time, it is your responsibility to determine which patent
// rights restrictions apply to you before you compile, use,
// modify, or redistribute this file. A patent lawyer is qualified
// to make this determination.
// If and only if they don't conflict with any patent terms, you
// can benefit from the following license terms attached to this
// file.
//
// This program is provided for scientific and educational only:
// you can use and/or modify it for these purposes, but you are
// not allowed to redistribute this work or derivative works in
// source or executable form. A license must be obtained from the
// patent right holders for any other use.
#ifndef _CLIBSIFT_H_
#define _CLIBSIFT_H_
///////////// Description
/// For each octave:
/// - Divide in par.Scales scales
/// - Convolve and compute differences of convolved scales
/// - Look for a 3x3 multiscale extrema and contraste enough and with no predominant direction (no 1d edge)
/// For each extrema
/// - Compute orientation histogram in neighborhood.
/// - Generate a keypoint for each mode with this orientation
/// For each keypoint
/// - Create vector
///////////// Possible differences with MW
/// Gaussian convolution
#include <stdlib.h>
#include <assert.h>
#include "numerics1.h"
#include "library.h"
#include "filter.h"
#include "domain.h"
#include "splines.h"
#include "flimage.h"
#include <vector>
// BASIC STRUCTURES:
// Keypoints:
#define OriSize 8
#define IndexSize 4
#define VecLength IndexSize * IndexSize * OriSize
/* Keypoint structure:
position: x,y
scale: s
orientation: angle
descriptor: array of gradient orientation histograms in a neighbors */
struct keypoint {
float x,y,
scale,
angle;
float vec[VecLength];
};
/* Keypoint structure:
position: x,y
scale: s
orientation: angle
descriptor: array of gradient orientation histograms in a neighbors */
struct keypoint_char {
float x,y,
scale,
angle;
unsigned char vec[VecLength];
};
/* Keypoint structure:
position: x,y
scale: s
orientation: angle
descriptor: array of gradient orientation histograms in a neighbors */
struct keypoint_short {
float x,y,
scale,
angle;
unsigned short vec[VecLength];
};
/* Keypoint structure:
position: x,y
scale: s
orientation: angle
descriptor: array of gradient orientation histograms in a neighbors */
struct keypoint_int {
float x,y,
scale,
angle;
unsigned int vec[VecLength];
};
/* List of keypoints: just use the standard class vector: */
typedef std::vector<keypoint> keypointslist;
/* List of keypoints: just use the standard class vector: */
typedef std::vector<keypoint_char> keypointslist_char;
typedef std::vector<keypoint_short> keypointslist_short;
typedef std::vector<keypoint_int> keypointslist_int;
/* Matching: just use the standard class pair: */
typedef std::pair<keypoint,keypoint> matching;
/* List of matchings: just use the standard class vector: */
typedef std::vector<matching> matchingslist;
struct siftPar
{
int OctaveMax;
int DoubleImSize;
int order;
/* InitSigma gives the amount of smoothing applied to the image at the
first level of each octave. In effect, this determines the sampling
needed in the image domain relative to amount of smoothing. Good
values determined experimentally are in the range 1.2 to 1.8.
*/
float InitSigma /*= 1.6*/;
/* Peaks in the DOG function must be at least BorderDist samples away
from the image border, at whatever sampling is used for that scale.
Keypoints close to the border (BorderDist < about 15) will have part
of the descriptor landing outside the image, which is approximated by
having the closest image pixel replicated. However, to perform as much
matching as possible close to the edge, use BorderDist of 4.
*/
int BorderDist /*= 5*/;
/* Scales gives the number of discrete smoothing levels within each octave.
For example, Scales = 2 implies dividing octave into 2 intervals, so
smoothing for each scale sample is sqrt(2) more than previous level.
Value of 2 works well, but higher values find somewhat more keypoints.
*/
int Scales /*= 3*/;
/// Decreasing PeakThresh allows more non contrasted keypoints
/* Magnitude of difference-of-Gaussian value at a keypoint must be above
this threshold. This avoids considering points with very low contrast
that are dominated by noise. It is divided by Scales because more
closely spaced scale samples produce smaller DOG values. A value of
0.08 considers only the most stable keypoints, but applications may
wish to use lower values such as 0.02 to find keypoints from low-contast
regions.
*/
//#define PeakThreshInit 255*0.04
//#define PeakThresh PeakThreshInit / Scales
float PeakThresh /*255.0 * 0.04 / 3.0*/;
/// Decreasing EdgeThresh allows more edge points
/* This threshold eliminates responses at edges. A value of 0.08 means
that the ratio of the largest to smallest eigenvalues (principle
curvatures) is below 10. A value of 0.14 means ratio is less than 5.
A value of 0.0 does not eliminate any responses.
Threshold at first octave is different.
*/
float EdgeThresh /*0.06*/;
float EdgeThresh1 /*0.08*/;
/* OriBins gives the number of bins in the histogram (36 gives 10
degree spacing of bins).
*/
int OriBins /*36*/;
/* Size of Gaussian used to select orientations as multiple of scale
of smaller Gaussian in DOG function used to find keypoint.
Best values: 1.0 for UseHistogramOri = FALSE; 1.5 for TRUE.
*/
float OriSigma /*1.5*/;
/// Look for local (3-neighborhood) maximum with valuer larger or equal than OriHistThresh * maxval
/// Setting one returns a single peak
/* All local peaks in the orientation histogram are used to generate
keypoints, as long as the local peak is within OriHistThresh of
the maximum peak. A value of 1.0 only selects a single orientation
at each location.
*/
float OriHistThresh /*0.8*/;
/// Feature vector is normalized to has euclidean norm 1.
/// This threshold avoid the excessive concentration of information on single peaks
/* Index values are thresholded at this value so that regions with
high gradients do not need to match precisely in magnitude.
Best value should be determined experimentally. Value of 1.0
has no effect. Value of 0.2 is significantly better.
*/
float MaxIndexVal /*0.2*/;
/* This constant specifies how large a region is covered by each index
vector bin. It gives the spacing of index samples in terms of
pixels at this scale (which is then multiplied by the scale of a
keypoint). It should be set experimentally to as small a value as
possible to keep features local (good values are in range 3 to 5).
*/
int MagFactor /*3*/;
/* Width of Gaussian weighting window for index vector values. It is
given relative to half-width of index, so value of 1.0 means that
weight has fallen to about half near corners of index patch. A
value of 1.0 works slightly better than large values (which are
equivalent to not using weighting). Value of 0.5 is considerably
worse.
*/
float IndexSigma /*1.0*/;
/* If this is TRUE, then treat gradients with opposite signs as being
the same. In theory, this could create more illumination invariance,
but generally harms performance in practice.
*/
int IgnoreGradSign /*0*/;
float MatchRatio /*0.6*/;
/*
In order to constrain the research zone for matches.
Useful for example when looking only at epipolar lines
*/
float MatchXradius /*= 1000000.0f*/;
float MatchYradius /*= 1000000.0f*/;
int noncorrectlylocalized;
};
//////////////////////////////////////////////////////////
/// SIFT
//////////////////////////////////////////////////////////
void default_sift_parameters(siftPar &par);
void compute_sift_keypoints(float *input, keypointslist& keypoints,int width, int height, siftPar &par);
// MATCHING DETECTION FUNCTION:
void compute_sift_matches( keypointslist& keys1, keypointslist& keys2, matchingslist& matchings, siftPar &par);
#endif // _LIBSIFT_H_

145
asift_match/src/domain.cpp Executable file
View file

@ -0,0 +1,145 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#include "domain.h"
#define DEBUG 0
void apply_zoom(float *input, float *out, float zoom, int order, int width, int height)
{
int nwidth = (int)( zoom * (float) width);
int nheight = (int)( zoom * (float) height);
float *coeffs;
float *ref;
float cx[12],cy[12],ak[13];
// Guoshen Yu, 2010.09.22, Windows versions
vector<float> input_vec, coeffs_vec, ref_vec;
input_vec = vector<float>(width*height);
coeffs_vec = vector<float>(width*height);
ref_vec = vector<float>(width*height);
for (int i = 0; i < width*height; i++)
input_vec[i] = input[i];
if (order!=0 && order!=1 && order!=-3 &&
order!=3 && order!=5 && order!=7 && order!=9 && order!=11)
{
printf("unrecognized interpolation order.\n");
exit(-1);
}
if (order>=3) {
coeffs = new float[width*height];
// Guoshen Yu, 2010.09.21, Windows version
//finvspline(input,order,coeffs,width,height);
finvspline(input_vec,order,coeffs_vec,width,height);
for (int i = 0; i < width*height; i++)
coeffs[i] = coeffs_vec[i];
ref = coeffs;
if (order>3) init_splinen(ak,order);
} else
{
coeffs = NULL;
ref = input;
}
int xi,yi;
float xp,yp;
float res;
int n1,n2;
float bg = 0.0f;
float p=-0.5;
for(int i=0; i < nwidth; i++)
for(int j=0; j < nheight; j++)
{
xp = (float) i / zoom;
yp = (float) j / zoom;
if (order == 0) {
xi = (int)floor((double)xp);
yi = (int)floor((double)yp);
if (xi<0 || xi>=width || yi<0 || yi>=height)
res = bg;
else res = input[yi*width+xi];
} else {
if (xp<0. || xp>=(float)width || yp<0. || yp>=(float)height) res=bg;
else {
xp -= 0.5; yp -= 0.5;
int xi = (int)floor((double)xp);
int yi = (int)floor((double)yp);
float ux = xp-(float)xi;
float uy = yp-(float)yi;
switch (order)
{
case 1: /* first order interpolation (bilinear) */
n2 = 1;
cx[0]=ux; cx[1]=1.-ux;
cy[0]=uy; cy[1]=1.-uy;
break;
case -3: /* third order interpolation (bicubic Keys' function) */
n2 = 2;
keys(cx,ux,p);
keys(cy,uy,p);
break;
case 3: /* spline of order 3 */
n2 = 2;
spline3(cx,ux);
spline3(cy,uy);
break;
default: /* spline of order >3 */
n2 = (1+order)/2;
splinen(cx,ux,ak,order);
splinen(cy,uy,ak,order);
break;
}
res = 0.; n1 = 1-n2;
if (xi+n1>=0 && xi+n2<width && yi+n1>=0 && yi+n2<height) {
int adr = yi*width+xi;
for (int dy=n1;dy<=n2;dy++)
for (int dx=n1;dx<=n2;dx++)
res += cy[n2-dy]*cx[n2-dx]*ref[adr+width*dy+dx];
} else
// Guoshen Yu, 2010.09.21, Windows
for (int i = 0; i < width*height; i++)
ref_vec[i] = ref[i];
for (int dy=n1;dy<=n2;dy++)
for (int dx=n1;dx<=n2;dx++)
// Guoshen Yu, 2010.09.21, Windows
// res += cy[n2-dy]*cx[n2-dx]*v(ref,xi+dx,yi+dy,bg,width,height);
res += cy[n2-dy]*cx[n2-dx]*v(ref_vec,xi+dx,yi+dy,bg,width,height);
}
}
out[j*nwidth+i] = res;
}
}

40
asift_match/src/domain.h Executable file
View file

@ -0,0 +1,40 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#ifndef _DOMAIN_H_
#define _DOMAIN_H_
#include "numerics1.h"
#include "library.h"
#include "splines.h"
/// Compute homography from n points using svd
void compute_planar_homography_n_points(float *x0, float *y0, float *x1, float *y1, int n, float **H);
/// Compute homography using svd + Ransac
void compute_ransac_planar_homography_n_points(float *x0, float *y0, float *x1, float *y1, int n, int niter, float tolerance, float **H);
/// Compute homography by using Lionel Code
void compute_moisan_planar_homography_n_points(float *x0, float *y0, float *x1, float *y1, int n, int niter, float &epsilon, float **H, int &counter, int recursivity);
/// Apply planar homography to image
void compute_planar_homography_bounding_box(int width, int height, float **H, float *x0, float *y0, int *nwidth, int *nheight);
void apply_planar_homography(float *input, int width, int height, float **H, float bg, int order, float *out, float x0, float y0, int nwidth, int nheight);
/// Apply zoom of factor z
void apply_zoom(float *input, float *out, float zoom, int order, int width, int height);
/// Apply general transformation
void apply_general_transformation(float *input, float *transformx, float* transformy, float *out, float bg, int order, int width, int height, int nwidth,int nheight);
#endif

460
asift_match/src/filter.cpp Executable file
View file

@ -0,0 +1,460 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#include "filter.h"
/////////////////////////////////////////////////////////////// Build Gaussian filters
float * directional_gauss_filter(float xsigma, float ysigma, float angle, int *kwidth, int *kheight)
{
int ksize = (int)(2.0 * 2.0 * MAX(xsigma, ysigma) + 1.0);
float *kernel = new float[ksize*ksize];
float xsigma2 = xsigma*xsigma;
float ysigma2 = ysigma*ysigma;
int l2 = ksize/2;
for(int y = -l2; y <= l2; y++)
for(int x = -l2; x <= l2; x++)
{
float a = (float) angle * PI / 180.0f;
float sina = sin(a);
float cosa = cos(a);
float ax = (float) x * cosa + (float) y * sina;
float ay = -(float) x * sina + (float) y * cosa;
kernel[(y+l2) * ksize + x + l2] = exp(-(ax*ax)/(2.0f*xsigma2) - (ay*ay)/(2.0f*ysigma2) );
}
float sum=0.0;
for(int i=0; i < ksize*ksize; i++) sum += kernel[i];
for(int i=0; i < ksize*ksize; i++) kernel[i] /= sum;
*kwidth = ksize;
*kheight = ksize;
return kernel;
}
/* Convolution with a kernel */
/* No padding applied to the image */
void convol(float *u,float *v,int width,int height,float *kernel,int kwidth,int kheight)
{
// float S;
// int K2,L2,m,n,kmin,kmax,lmin,lmax,l,k;
int K2 = kwidth / 2;
int L2 = kheight / 2;
for(int y=0 ; y < height; y++)
for (int x=0 ; x < width; x++) {
float S = 0.0;
// kmax = MIN(kwidth-1,n+K2);
// kmin = MAX(0,1+n+K2-width);
// lmax = MIN(kheight-1,m+L2);
// lmin = MAX(0,1+m+L2-height);
for (int l = -L2; l <= L2; l++)
for (int k = -K2 ; k<= K2; k++)
{
int px=x+k;
int py=y+l;
if (px>=0 && px < width && py>=0 && py<height)
S += u[width*py + px] * kernel[kwidth*(l+L2) + k+K2];
}
v[y*width+x] = (float) S;
}
}
void median(float *u,float *v, float radius, int niter, int width,int height)
{
int iradius = (int)(radius+1.0);
int rsize=(2*iradius+1)*(2*iradius+1);
float * vector = new float[rsize];
float * index = new float[rsize];
for(int n=0; n< niter;n++){
for(int x=0;x<width;x++)
for(int y=0;y<height;y++){
int count=0;
for(int i=-iradius;i<=iradius;i++)
for(int j=-iradius;j<=iradius;j++)
if ((float) (i*i + j*j) <= iradius*iradius){
int x0=x+i;
int y0=y+j;
if (x0>=0 && y0>=0 && x0 < width && y0 < height) {
vector[count] = u[y0*width+x0];
index[count] = count;
count++;
}
}
quick_sort(vector,index,count);
v[y*width+x] = vector[count/2];
}
copy(v,u,width*height);
}
delete[] vector;
delete[] index;
}
void remove_outliers(float *igray,float *ogray,int width, int height)
{
int bloc=1;
int bsize = (2*bloc+1)*(2*bloc+1)-1;
for(int x=bloc;x<width-bloc;x++)
for(int y=bloc;y<height-bloc;y++) {
int l = y*width+x;
int countmax=0;
int countmin=0;
float valueg0 = igray[l];
// float distmin = MAXFLOAT;
float distmin = FLT_MAX; // Guoshen Yu
float green = igray[l];
for(int i=-bloc;i<=bloc;i++)
for(int j=-bloc;j<=bloc;j++)
if ((i!=0 || j!=0)){
int l0 = (y+j)*width+x+i;
int valueg = (int) igray[l0];
if (valueg0>valueg) countmax++;
if (valueg0<valueg) countmin++;
float dist = fabsf(valueg - valueg0);
if (dist < distmin) {distmin=dist;green=valueg;}
}
if (countmin == bsize || countmax == bsize ) ogray[l]=green;
else ogray[l] = igray[l];
}
}
/* Convolution with a separable kernel */
/* boundary condition: 0=zero, 1=symmetry */
void separable_convolution(float *u, float *v, int width, int height,float * xkernel, int xsize,float *ykernel,int ysize,int boundary)
{
int width2 = 2*width;
int height2 = 2*height;
float *tmp = (float *) malloc(width*height*sizeof(float));
/* convolution along x axis */
float sum = 0.0;
int org = xsize / 2;
for (int y=height;y--;)
for (int x=width;x--;) {
sum = 0.0;
for (int i=xsize;i--;) {
int s = x-i+org;
switch(boundary) {
case 0:
if (s>=0 && s<width) sum += xkernel[i]*u[y*width+s];
break;
case 1:
while (s<0) s+=width2;
while (s>=width2) s-=width2;
if (s>=width) s = width2-1-s;
sum += xkernel[i]*u[y*width+s];
break;
}
}
tmp[y*width+x] = sum;
}
/* convolution along y axis */
org = ysize / 2;
for (int y=height;y--;)
for (int x=width;x--;) {
sum=0.0;
for (int i=ysize;i--;) {
int s = y-i+org;
switch(boundary) {
case 0:
if (s>=0 && s<height) sum += ykernel[i]*tmp[s*width+x];
break;
case 1:
while (s<0) s+=height2;
while (s>=height2) s-=height2;
if (s>=height) s = height2-1-s;
sum += ykernel[i]*tmp[s*width+x];
break;
}
}
v[y*width+x] = sum;
}
free(tmp);
}
void gaussian_convolution(float *u, float *v, int width, int height, float sigma)
{
int ksize;
float * kernel;
ksize = (int)(2.0 * 4.0 * sigma + 1.0);
kernel = gauss(1,sigma,&ksize);
int boundary = 1;
copy(u,v,width*height);
horizontal_convolution(v, v, width, height, kernel, ksize, boundary);
vertical_convolution(v, v, width, height, kernel, ksize, boundary);
delete[] kernel; /*memcheck*/
}
void gaussian_convolution(float *u, float *v, int width, int height, float sigma, int ksize)
{
float * kernel;
kernel = gauss(1,sigma,&ksize);
int boundary = 1;
copy(u,v,width*height);
horizontal_convolution(v, v, width, height, kernel, ksize, boundary);
vertical_convolution(v, v, width, height, kernel, ksize, boundary);
}
void fast_separable_convolution(float *u, float *v, int width, int height,float * xkernel, int xsize,float *ykernel,int ysize,int boundary)
{
copy(u,v,width*height);
horizontal_convolution(v, v, width, height, xkernel, xsize, boundary);
vertical_convolution(v, v, width, height, ykernel, ysize, boundary);
}
/* Loop unrolling simply sums 5 multiplications
at a time to allow the compiler to schedule
operations better and avoid loop overhead.
*/
void buffer_convolution(float *buffer,float *kernel,int size,int ksize)
{
for (int i = 0; i < size; i++) {
float sum = 0.0;
float *bp = &buffer[i];
float *kp = &kernel[0];
/* Loop unrolling: do 5 multiplications at a time. */
// int k=0;
for(int k = 0; k < ksize; k++)
sum += *bp++ * *kp++;
// for(;k + 4 < ksize; bp += 5, kp += 5, k += 5)
// sum += bp[0] * kp[0] + bp[1] * kp[1] + bp[2] * kp[2] +
// bp[3] * kp[3] + bp[4] * kp[4];
/* Do multiplications at a time on remaining items. */
// for(; k < ksize; bp++ , kp++, k++) sum += *bp * (*kp);
buffer[i] = sum;
}
}
/* Convolve image with the 1-D kernel vector along image rows. This
is designed to be as efficient as possible.
*/
void horizontal_convolution(float *u, float *v, int width, int height, float *kernel, int ksize, int boundary)
{
int halfsize = ksize / 2;
int buffersize = width + ksize;
float *buffer = new float[buffersize];
for (int r = 0; r < height; r++) {
/// symmetry
int l = r*width;
if (boundary == 1)
for (int i = 0; i < halfsize; i++)
buffer[i] = u[l + halfsize - 1 - i ];
else
for (int i = 0; i < halfsize; i++)
buffer[i] = 0.0;
for (int i = 0; i < width; i++)
buffer[halfsize + i] = u[l + i];
if (boundary == 1)
for (int i = 0; i < halfsize; i++)
buffer[i + width + halfsize] = u[l + width - 1 - i];
else
for (int i = 0; i < halfsize; i++)
buffer[i + width + halfsize] = 0.0;
buffer_convolution(buffer, kernel, width, ksize);
for (int c = 0; c < width; c++)
v[r*width+c] = buffer[c];
}
delete[] buffer; /*memcheck*/
}
void vertical_convolution(float *u, float *v, int width, int height, float *kernel,int ksize, int boundary)
{
int halfsize = ksize / 2;
int buffersize = height + ksize;
float *buffer = new float[buffersize];
for (int c = 0; c < width; c++) {
if (boundary == 1)
for (int i = 0; i < halfsize; i++)
buffer[i] = u[(halfsize-i-1)*width + c];
else
for (int i = 0; i < halfsize; i++)
buffer[i] = 0.0f;
for (int i = 0; i < height; i++)
buffer[halfsize + i] = u[i*width + c];
if (boundary == 1)
for (int i = 0; i < halfsize; i++)
buffer[halfsize + height + i] = u[(height - i - 1)*width+c];
else
for (int i = 0; i < halfsize; i++)
buffer[halfsize + height + i] = 0.0f;
buffer_convolution(buffer, kernel, height, ksize);
for (int r = 0; r < height; r++)
v[r*width+c] = buffer[r];
}
delete[] buffer; /*memcheck*/
}
void heat(float *input, float *out, float step, int niter, float sigma, int width, int height)
{
int i,j,n,ksize,size,im,i1,j1,jm;
float *kernel = NULL, *laplacian = NULL, *convolved = NULL;
size = width*height;
if (sigma > 0.0) kernel = gauss(0,sigma,&ksize);
laplacian = (float *) malloc(size*sizeof(float));
convolved = (float *) malloc(size*sizeof(float));
for(n=0; n < niter; n++)
{
if (sigma > 0.0)
{
separable_convolution(input,convolved,width,height, kernel, ksize,kernel,ksize,1);
for(i=0; i< size; i++) laplacian[i] = convolved[i] - input[i];
} else
{
for (i=0; i < width;i++)
for (j=0; j< height ;j++)
{
if (j==0) jm=1; else jm=j-1;
if (j==height-1) j1=height-2; else j1=j+1;
if (i==0) im=1; else im=i-1;
if (i==width-1) i1=width-2; else i1=i+1;
laplacian[j*width + i] = - 4.0 * input[width*j+i] + input[width*j+im]+ input[width*j+i1]+input[width*jm + i] + input[width*j1 + i];
}
}
for(i=0; i < size; i++) out[i] = input[i] + step * laplacian[i];
copy(out,input,size);
}
free(laplacian);
free(convolved);
if (kernel) free(kernel);
}

38
asift_match/src/filter.h Executable file
View file

@ -0,0 +1,38 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#ifndef _FILTER_H_
#define _FILTER_H_
#include "library.h"
float * directional_gauss_filter(float xsigma, float ysigma, float angle, int *kwidth, int *kheight);
void median(float *u,float *v, float radius, int niter, int width,int height);
void remove_outliers(float *igray,float *ogray,int width, int height);
/// Convolution with a separable kernel, boundary condition: 0=zero, 1=symmetry
void separable_convolution(float *u, float *v, int width, int height, float *xkernel, int xsize, float *ykernel, int ysize,int boundary);
void buffer_convolution(float *buffer,float *kernel,int size,int ksize);
void horizontal_convolution(float *u, float *v, int width, int height, float *kernel, int ksize, int boundary);
void vertical_convolution(float *u, float *v, int width, int height, float *kernel,int ksize, int boundary);
void fast_separable_convolution(float *u, float *v, int width, int height,float * xkernel, int xsize,float *ykernel,int ysize,int boundary);
/// Can be called with u=v
void gaussian_convolution(float *u, float *v, int width, int height, float sigma);
void gaussian_convolution(float *u, float *v, int width, int height, float sigma, int ksize);
void convol(float *u, float *v, int width, int height, float *kernel, int kwidth, int kheight); /// Convolution with a kernel, No padding applied to the image
void heat(float *u, float *v, float step, int niter, float sigma, int width, int height);
#endif // _FILTER_H_

86
asift_match/src/flimage.cpp Executable file
View file

@ -0,0 +1,86 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#include "flimage.h"
//////////////////////////////////////////////// Class flimage
//// Construction
flimage::flimage() : width(0), height(0), p(0)
{
}
flimage::flimage(int w, int h) : width(w), height(h), p(new float[w*h])
{
for (int j=width*height-1; j>=0 ; j--) p[j] = 0.0;
}
flimage::flimage(int w, int h, float v) : width(w), height(h), p(new float[w*h])
{
for (int j=width*height-1; j>=0 ; j--) p[j] = v;
}
flimage::flimage(int w, int h, float* v) : width(w), height(h), p(new float[w*h])
{
for (int j=width*height-1; j>=0 ; j--) p[j] = v[j];
}
void flimage::create(int w, int h)
{
erase();
width = w; height = h;
p = new float[w*h];
for (int j=width*height-1; j>=0 ; j--) p[j] = 0.0;
}
void flimage::create(int w, int h, float* v)
{
erase();
width = w; height = h; p = new float[w*h];
for (int j=width*height-1; j>=0 ; j--) p[j] = v[j];
}
flimage::flimage(const flimage& im) : width(im.width), height(im.height), p(new float[im.width*im.height])
{
for (int j=width*height-1; j>=0 ; j--) p[j] = im.p[j];
}
flimage& flimage::operator= (const flimage& im)
{
if (&im == this) {
return *this;
}
if (width != im.width || height != im.height)
{
erase();
width = im.width; height=im.height; p = new float[width*height];
}
for (int j=width*height-1; j>=0 ; j--) p[j] = im.p[j];
return *this;
}
//// Destruction
void flimage::erase()
{
width = height = 0;
if (p) delete[] p;
p=0;
}
flimage::~flimage()
{
erase();
}

53
asift_match/src/flimage.h Executable file
View file

@ -0,0 +1,53 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#ifndef _FLIMAGE_H_
#define _FLIMAGE_H_
#include <iostream>
#include <string>
class flimage {
private:
int width, height; // image size
float* p; // array of color levels: level of pixel (x,y) is p[y*width+x]
public:
//// Construction
flimage();
flimage(int w, int h);
flimage(int w, int h, float v);
flimage(int w, int h, float* v);
flimage(const flimage& im);
flimage& operator= (const flimage& im);
void create(int w, int h);
void create(int w, int h, float *v);
//// Destruction
void erase();
~flimage();
//// Get Basic Data
int nwidth() const {return width;} // image size
int nheight() const {return height;}
/// Access values
float* getPlane() {return p;} // return the adress of the array of values
float operator()(int x, int y) const {return p[ y*width + x ];} // acces to the (x,y) value
float& operator()(int x, int y) {return p[ y*width + x ];} // by value (for const images) and by reference
};
#endif

186
asift_match/src/fproj.cpp Executable file
View file

@ -0,0 +1,186 @@
// Copyright (c) 2007 Lionel Moisan <Lionel.Moisan@parisdescartes.fr>
#include <stdio.h>
#include <math.h>
#include "splines.h"
#include "fproj.h"
/*------------------------ MAIN MODULE ---------------------------------*/
//void fproj(float *in, float *out, int nx, int ny, int *sx, int *sy, float *bg, int *o, float *p, char *i, float X1, float Y1, float X2, float Y2, float X3, float Y3, float *x4, float *y4)
void fproj(vector<float>& in, vector<float>& out, int nx, int ny, int *sx, int *sy, float *bg, int *o, float *p, char *i, float X1, float Y1, float X2, float Y2, float X3, float Y3, float *x4, float *y4)
/* Fimage in,out;
int *sx,*sy,*o;
char *i;
float *bg,*p,X1,Y1,X2,Y2,X3,Y3,*x4,*y4; */
{
/* int n1,n2,nx,ny,x,y,xi,yi,adr,dx,dy;*/
int n1,n2,x,y,xi,yi,adr,dx,dy;
float res,xx,yy,xp,yp,ux,uy,a,b,d,fx,fy,x12,x13,y12,y13;
float cx[12],cy[12],ak[13];
/* Fimage ref,coeffs; */
// float *ref, *coeffs;
vector<float> ref, coeffs;
/* CHECK ORDER */
if (*o!=0 && *o!=1 && *o!=-3 &&
*o!=3 && *o!=5 && *o!=7 && *o!=9 && *o!=11)
/* mwerror(FATAL,1,"unrecognized interpolation order.\n"); */
{
printf("unrecognized interpolation order.\n");
exit(-1);
}
/* ALLOCATE NEW IMAGE */
/* nx = in->ncol; ny = in->nrow; */
/* out = mw_change_fimage(out,*sy,*sx);
if (!out) mwerror(FATAL,1,"not enough memory\n"); */
if (*o>=3) {
/* coeffs = mw_new_fimage();
finvspline(in,*o,coeffs); */
// coeffs = new float[nx*ny];
coeffs = vector<float>(nx*ny);
finvspline(in,*o,coeffs,nx,ny);
ref = coeffs;
if (*o>3) init_splinen(ak,*o);
} else {
// coeffs = NULL;
ref = in;
}
/* COMPUTE NEW BASIS */
if (i) {
x12 = (X2-X1)/(float)nx;
y12 = (Y2-Y1)/(float)nx;
x13 = (X3-X1)/(float)ny;
y13 = (Y3-Y1)/(float)ny;
} else {
x12 = (X2-X1)/(float)(*sx);
y12 = (Y2-Y1)/(float)(*sx);
x13 = (X3-X1)/(float)(*sy);
y13 = (Y3-Y1)/(float)(*sy);
}
if (y4) {
xx=((*x4-X1)*(Y3-Y1)-(*y4-Y1)*(X3-X1))/((X2-X1)*(Y3-Y1)-(Y2-Y1)*(X3-X1));
yy=((*x4-X1)*(Y2-Y1)-(*y4-Y1)*(X2-X1))/((X3-X1)*(Y2-Y1)-(Y3-Y1)*(X2-X1));
a = (yy-1.0)/(1.0-xx-yy);
b = (xx-1.0)/(1.0-xx-yy);
}
else
{
a=b=0.0;
}
/********** MAIN LOOP **********/
for (x=0;x<*sx;x++)
for (y=0;y<*sy;y++) {
/* COMPUTE LOCATION IN INPUT IMAGE */
if (i) {
xx = 0.5+(((float)x-X1)*y13-((float)y-Y1)*x13)/(x12*y13-y12*x13);
yy = 0.5-(((float)x-X1)*y12-((float)y-Y1)*x12)/(x12*y13-y12*x13);
d = 1.0-(a/(a+1.0))*xx/(float)nx-(b/(b+1.0))*yy/(float)ny;
xp = xx/((a+1.0)*d);
yp = yy/((b+1.0)*d);
} else {
fx = (float)x + 0.5;
fy = (float)y + 0.5;
d = a*fx/(float)(*sx)+b*fy/(float)(*sy)+1.0;
xx = (a+1.0)*fx/d;
yy = (b+1.0)*fy/d;
xp = X1 + xx*x12 + yy*x13;
yp = Y1 + xx*y12 + yy*y13;
}
/* INTERPOLATION */
if (*o==0) {
/* zero order interpolation (pixel replication) */
xi = (int)floor((double)xp);
yi = (int)floor((double)yp);
/* if (xi<0 || xi>=in->ncol || yi<0 || yi>=in->nrow)*/
if (xi<0 || xi>=nx || yi<0 || yi>=ny)
res = *bg;
else
/* res = in->gray[yi*in->ncol+xi]; */
res = in[yi*nx+xi];
} else {
/* higher order interpolations */
if (xp<0. || xp>(float)nx || yp<0. || yp>(float)ny) res=*bg;
else {
xp -= 0.5; yp -= 0.5;
xi = (int)floor((double)xp);
yi = (int)floor((double)yp);
ux = xp-(float)xi;
uy = yp-(float)yi;
switch (*o)
{
case 1: /* first order interpolation (bilinear) */
n2 = 1;
cx[0]=ux; cx[1]=1.-ux;
cy[0]=uy; cy[1]=1.-uy;
break;
case -3: /* third order interpolation (bicubic Keys' function) */
n2 = 2;
keys(cx,ux,*p);
keys(cy,uy,*p);
break;
case 3: /* spline of order 3 */
n2 = 2;
spline3(cx,ux);
spline3(cy,uy);
break;
default: /* spline of order >3 */
n2 = (1+*o)/2;
splinen(cx,ux,ak,*o);
splinen(cy,uy,ak,*o);
break;
}
res = 0.; n1 = 1-n2;
/* this test saves computation time */
if (xi+n1>=0 && xi+n2<nx && yi+n1>=0 && yi+n2<ny) {
adr = yi*nx+xi;
for (dy=n1;dy<=n2;dy++)
for (dx=n1;dx<=n2;dx++)
/* res += cy[n2-dy]*cx[n2-dx]*ref->gray[adr+nx*dy+dx];*/
res += cy[n2-dy]*cx[n2-dx]*ref[adr+nx*dy+dx];
} else
for (dy=n1;dy<=n2;dy++)
for (dx=n1;dx<=n2;dx++)
/* res += cy[n2-dy]*cx[n2-dx]*v(ref,xi+dx,yi+dy,*bg); */
res += cy[n2-dy]*cx[n2-dx]*v(ref,xi+dx,yi+dy,*bg,nx,ny);
}
}
/* out->gray[y*(*sx)+x] = res; */
out[y*(*sx)+x] = res;
}
//if (coeffs)
/* mw_delete_fimage(coeffs); */
// delete[] coeffs;
}

9
asift_match/src/fproj.h Executable file
View file

@ -0,0 +1,9 @@
// Copyright (c) 2007 Lionel Moisan <Lionel.Moisan@parisdescartes.fr>
#include "library.h"
#include <vector>
using namespace std;
//void fproj(float *in, float *out, int nx, int ny, int *sx, int *sy, float *bg, int *o, float *p, char *i, float X1, float Y1, float X2, float Y2, float X3, float Y3, float *x4, float *y4);
void fproj(vector<float>& in, vector<float>& out, int nx, int ny, int *sx, int *sy, float *bg, int *o, float *p, char *i, float X1, float Y1, float X2, float Y2, float X3, float Y3, float *x4, float *y4);

116
asift_match/src/frot.cpp Executable file
View file

@ -0,0 +1,116 @@
// Copyright (c) 2007 Lionel Moisan <Lionel.Moisan@parisdescartes.fr>
#include "frot.h"
#ifndef M_PI
#define M_PI 3.14159265358979323846
#endif
void bound(int x, int y, float ca, float sa, int *xmin, int *xmax, int *ymin, int *ymax);
/* NB : calling this module with out=in is nonsense */
/* void frot(in,out,a,b,k_flag)
Fimage in,out;
float *a,*b;
char *k_flag; */
void frot(vector<float>& in, vector<float>& out, int nx, int ny, int *nx_out, int *ny_out, float *a, float *b, char *k_flag)
//void frot(float *in, float *out, int nx, int ny, int *nx_out, int *ny_out, float *a, float *b, char *k_flag)
{
/* int nx,ny,x,y,x1,y1,adr; */
int x,y,x1,y1,adr;
float ca,sa,xp,yp,a11,a12,a21,a22,ux,uy,xtrans,ytrans;
int tx1,ty1,tx2,ty2,xmin,xmax,ymin,ymax,sx,sy;
/* nx = in->ncol;
ny = in->nrow; */
ca = (float)cos((double)(*a)*M_PI/180.0);
sa = (float)sin((double)(*a)*M_PI/180.0);
/********** Compute new image location **********/
if (k_flag) {
/* crop image and fix center */
xmin = ymin = 0;
xmax = nx-1;
ymax = ny-1;
xtrans = 0.5*( (float)(nx-1)*(1.0-ca)+(float)(ny-1)*sa );
ytrans = 0.5*( (float)(ny-1)*(1.0-ca)-(float)(nx-1)*sa );
} else {
/* extend image size to include the whole input image */
xmin = xmax = ymin = ymax = 0;
bound(nx-1,0,ca,sa,&xmin,&xmax,&ymin,&ymax);
bound(0,ny-1,ca,sa,&xmin,&xmax,&ymin,&ymax);
bound(nx-1,ny-1,ca,sa,&xmin,&xmax,&ymin,&ymax);
xtrans = ytrans = 0.0;
}
sx = xmax-xmin+1;
sy = ymax-ymin+1;
/* out = mw_change_fimage(out,sy,sx);
if (!out) mwerror(FATAL,1,"not enough memory\n"); */
*nx_out = sx;
*ny_out = sy;
// printf("Hello sx=%d, sy=%d\n", sx, sy);
// out = new float[sy*sx];
out = std::vector<float>(sx*sy);
/********** Rotate image **********/
for (x=xmin;x<=xmax;x++)
for (y=ymin;y<=ymax;y++) {
xp = ca*(float)x-sa*(float)y + xtrans;
yp = sa*(float)x+ca*(float)y + ytrans;
x1 = (int)floor(xp);
y1 = (int)floor(yp);
ux = xp-(float)x1;
uy = yp-(float)y1;
adr = y1*nx+x1;
tx1 = (x1>=0 && x1<nx);
tx2 = (x1+1>=0 && x1+1<nx);
ty1 = (y1>=0 && y1<ny);
ty2 = (y1+1>=0 && y1+1<ny);
/* a11 = (tx1 && ty1? in->gray[adr]:*b);
a12 = (tx1 && ty2? in->gray[adr+nx]:*b);
a21 = (tx2 && ty1? in->gray[adr+1]:*b);
a22 = (tx2 && ty2? in->gray[adr+nx+1]:*b); */
a11 = (tx1 && ty1? in[adr]:*b);
a12 = (tx1 && ty2? in[adr+nx]:*b);
a21 = (tx2 && ty1? in[adr+1]:*b);
a22 = (tx2 && ty2? in[adr+nx+1]:*b);
/* out->gray[(y-ymin)*sx+x-xmin] =
(1.0-uy)*((1.0-ux)*a11+ux*a21)+uy*((1.0-ux)*a12+ux*a22);*/
out[(y-ymin)*sx+x-xmin] =
(1.0-uy)*((1.0-ux)*a11+ux*a21)+uy*((1.0-ux)*a12+ux*a22);
}
}
void bound(int x, int y, float ca, float sa, int *xmin, int *xmax, int *ymin, int *ymax)
/* int x,y;
float ca,sa;
int *xmin,*xmax,*ymin,*ymax;*/
{
int rx,ry;
rx = (int)floor(ca*(float)x+sa*(float)y);
ry = (int)floor(-sa*(float)x+ca*(float)y);
if (rx<*xmin) *xmin=rx; if (rx>*xmax) *xmax=rx;
if (ry<*ymin) *ymin=ry; if (ry>*ymax) *ymax=ry;
}

10
asift_match/src/frot.h Executable file
View file

@ -0,0 +1,10 @@
// Copyright (c) 2007 Lionel Moisan <Lionel.Moisan@parisdescartes.fr>
#include "library.h"
#include <vector>
using namespace std;
/*void frot(float *in, float *out, int nx, int ny, int *nx_out, int *ny_out, float *a, float *b, char *k_flag)*/
//void frot(float *, float (*)[], int, int, int *, int *, float *, float *, char *);
void frot(vector<float>&, vector<float>&, int, int, int *, int *, float *, float *, char *);

View file

@ -0,0 +1,16 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 2.8
# Relative path conversion top directories.
SET(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src")
SET(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src")
# Force unix paths in dependencies.
SET(CMAKE_FORCE_UNIX_PATHS 1)
# The C and CXX include file regular expressions for this directory.
SET(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$")
SET(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$")
SET(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN})
SET(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN})

View file

@ -0,0 +1,20 @@
#IncludeRegexLine: ^[ ]*#[ ]*(include|import)[ ]*[<"]([^">]+)([">])
#IncludeRegexScan: ^.*$
#IncludeRegexComplain: ^$
#IncludeRegexTransform:
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch/match.cpp
match.h
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch/match.h
fstream
-
sstream
-
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch/match.h
vector
-

View file

@ -0,0 +1,20 @@
# The set of languages for which implicit dependencies are needed:
SET(CMAKE_DEPENDS_LANGUAGES
"CXX"
)
# The set of files for implicit dependencies of each language:
SET(CMAKE_DEPENDS_CHECK_CXX
"/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch/match.cpp" "/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch/CMakeFiles/Match.dir/match.cpp.o"
)
SET(CMAKE_CXX_COMPILER_ID "GNU")
# Targets to which this target links.
SET(CMAKE_TARGET_LINKED_INFO_FILES
)
# The include file search paths:
SET(CMAKE_C_TARGET_INCLUDE_PATH
)
SET(CMAKE_CXX_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH})
SET(CMAKE_Fortran_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH})
SET(CMAKE_ASM_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH})

View file

@ -0,0 +1,103 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 2.8
#=============================================================================
# Special targets provided by cmake.
# Disable implicit rules so canonical targets will work.
.SUFFIXES:
# Remove some rules from gmake that .SUFFIXES does not remove.
SUFFIXES =
.SUFFIXES: .hpux_make_needs_suffix_list
# Suppress display of executed commands.
$(VERBOSE).SILENT:
# A target that is always out of date.
cmake_force:
.PHONY : cmake_force
#=============================================================================
# Set environment variables for the build.
# The shell in which to execute make rules.
SHELL = /bin/sh
# The CMake executable.
CMAKE_COMMAND = /usr/bin/cmake
# The command to remove a file.
RM = /usr/bin/cmake -E remove -f
# Escaping for special characters.
EQUALS = =
# The top-level source directory on which CMake was run.
CMAKE_SOURCE_DIR = /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src
# The top-level build directory on which CMake was run.
CMAKE_BINARY_DIR = /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src
# Include any dependencies generated for this target.
include libMatch/CMakeFiles/Match.dir/depend.make
# Include the progress variables for this target.
include libMatch/CMakeFiles/Match.dir/progress.make
# Include the compile flags for this target's objects.
include libMatch/CMakeFiles/Match.dir/flags.make
libMatch/CMakeFiles/Match.dir/match.cpp.o: libMatch/CMakeFiles/Match.dir/flags.make
libMatch/CMakeFiles/Match.dir/match.cpp.o: libMatch/match.cpp
$(CMAKE_COMMAND) -E cmake_progress_report /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/CMakeFiles $(CMAKE_PROGRESS_1)
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object libMatch/CMakeFiles/Match.dir/match.cpp.o"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/Match.dir/match.cpp.o -c /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch/match.cpp
libMatch/CMakeFiles/Match.dir/match.cpp.i: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/Match.dir/match.cpp.i"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -E /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch/match.cpp > CMakeFiles/Match.dir/match.cpp.i
libMatch/CMakeFiles/Match.dir/match.cpp.s: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/Match.dir/match.cpp.s"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -S /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch/match.cpp -o CMakeFiles/Match.dir/match.cpp.s
libMatch/CMakeFiles/Match.dir/match.cpp.o.requires:
.PHONY : libMatch/CMakeFiles/Match.dir/match.cpp.o.requires
libMatch/CMakeFiles/Match.dir/match.cpp.o.provides: libMatch/CMakeFiles/Match.dir/match.cpp.o.requires
$(MAKE) -f libMatch/CMakeFiles/Match.dir/build.make libMatch/CMakeFiles/Match.dir/match.cpp.o.provides.build
.PHONY : libMatch/CMakeFiles/Match.dir/match.cpp.o.provides
libMatch/CMakeFiles/Match.dir/match.cpp.o.provides.build: libMatch/CMakeFiles/Match.dir/match.cpp.o
# Object files for target Match
Match_OBJECTS = \
"CMakeFiles/Match.dir/match.cpp.o"
# External object files for target Match
Match_EXTERNAL_OBJECTS =
libMatch/libMatch.a: libMatch/CMakeFiles/Match.dir/match.cpp.o
libMatch/libMatch.a: libMatch/CMakeFiles/Match.dir/build.make
libMatch/libMatch.a: libMatch/CMakeFiles/Match.dir/link.txt
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --red --bold "Linking CXX static library libMatch.a"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch && $(CMAKE_COMMAND) -P CMakeFiles/Match.dir/cmake_clean_target.cmake
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch && $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/Match.dir/link.txt --verbose=$(VERBOSE)
# Rule to build all files generated by this target.
libMatch/CMakeFiles/Match.dir/build: libMatch/libMatch.a
.PHONY : libMatch/CMakeFiles/Match.dir/build
libMatch/CMakeFiles/Match.dir/requires: libMatch/CMakeFiles/Match.dir/match.cpp.o.requires
.PHONY : libMatch/CMakeFiles/Match.dir/requires
libMatch/CMakeFiles/Match.dir/clean:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch && $(CMAKE_COMMAND) -P CMakeFiles/Match.dir/cmake_clean.cmake
.PHONY : libMatch/CMakeFiles/Match.dir/clean
libMatch/CMakeFiles/Match.dir/depend:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch/CMakeFiles/Match.dir/DependInfo.cmake --color=$(COLOR)
.PHONY : libMatch/CMakeFiles/Match.dir/depend

View file

@ -0,0 +1,10 @@
FILE(REMOVE_RECURSE
"CMakeFiles/Match.dir/match.cpp.o"
"libMatch.pdb"
"libMatch.a"
)
# Per-language clean rules from dependency scanning.
FOREACH(lang CXX)
INCLUDE(CMakeFiles/Match.dir/cmake_clean_${lang}.cmake OPTIONAL)
ENDFOREACH(lang)

View file

@ -0,0 +1,3 @@
FILE(REMOVE_RECURSE
"libMatch.a"
)

View file

@ -0,0 +1,6 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 2.8
libMatch/CMakeFiles/Match.dir/match.cpp.o
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch/match.cpp
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch/match.h

View file

@ -0,0 +1,6 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 2.8
libMatch/CMakeFiles/Match.dir/match.cpp.o: libMatch/match.cpp
libMatch/CMakeFiles/Match.dir/match.cpp.o: libMatch/match.h

View file

@ -0,0 +1,8 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 2.8
# compile CXX with /usr/bin/c++
CXX_FLAGS =
CXX_DEFINES =

View file

@ -0,0 +1,2 @@
/usr/bin/ar cr libMatch.a CMakeFiles/Match.dir/match.cpp.o
/usr/bin/ranlib libMatch.a

View file

@ -0,0 +1,2 @@
CMAKE_PROGRESS_1 = 1

View file

@ -0,0 +1 @@
1

View file

@ -0,0 +1,6 @@
CMAKE_MINIMUM_REQUIRED(VERSION 2.6)
PROJECT(libMatch)
ADD_LIBRARY(Match
match.cpp match.h)

View file

@ -0,0 +1,164 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 2.8
# Default target executed when no arguments are given to make.
default_target: all
.PHONY : default_target
#=============================================================================
# Special targets provided by cmake.
# Disable implicit rules so canonical targets will work.
.SUFFIXES:
# Remove some rules from gmake that .SUFFIXES does not remove.
SUFFIXES =
.SUFFIXES: .hpux_make_needs_suffix_list
# Suppress display of executed commands.
$(VERBOSE).SILENT:
# A target that is always out of date.
cmake_force:
.PHONY : cmake_force
#=============================================================================
# Set environment variables for the build.
# The shell in which to execute make rules.
SHELL = /bin/sh
# The CMake executable.
CMAKE_COMMAND = /usr/bin/cmake
# The command to remove a file.
RM = /usr/bin/cmake -E remove -f
# Escaping for special characters.
EQUALS = =
# The top-level source directory on which CMake was run.
CMAKE_SOURCE_DIR = /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src
# The top-level build directory on which CMake was run.
CMAKE_BINARY_DIR = /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src
#=============================================================================
# Targets provided globally by CMake.
# Special rule for the target edit_cache
edit_cache:
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running interactive CMake command-line interface..."
/usr/bin/cmake -i .
.PHONY : edit_cache
# Special rule for the target edit_cache
edit_cache/fast: edit_cache
.PHONY : edit_cache/fast
# Special rule for the target rebuild_cache
rebuild_cache:
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..."
/usr/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR)
.PHONY : rebuild_cache
# Special rule for the target rebuild_cache
rebuild_cache/fast: rebuild_cache
.PHONY : rebuild_cache/fast
# The main all target
all: cmake_check_build_system
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(CMAKE_COMMAND) -E cmake_progress_start /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/CMakeFiles /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch/CMakeFiles/progress.marks
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f CMakeFiles/Makefile2 libMatch/all
$(CMAKE_COMMAND) -E cmake_progress_start /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/CMakeFiles 0
.PHONY : all
# The main clean target
clean:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f CMakeFiles/Makefile2 libMatch/clean
.PHONY : clean
# The main clean target
clean/fast: clean
.PHONY : clean/fast
# Prepare targets for installation.
preinstall: all
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f CMakeFiles/Makefile2 libMatch/preinstall
.PHONY : preinstall
# Prepare targets for installation.
preinstall/fast:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f CMakeFiles/Makefile2 libMatch/preinstall
.PHONY : preinstall/fast
# clear depends
depend:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1
.PHONY : depend
# Convenience name for target.
libMatch/CMakeFiles/Match.dir/rule:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f CMakeFiles/Makefile2 libMatch/CMakeFiles/Match.dir/rule
.PHONY : libMatch/CMakeFiles/Match.dir/rule
# Convenience name for target.
Match: libMatch/CMakeFiles/Match.dir/rule
.PHONY : Match
# fast build rule for target.
Match/fast:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libMatch/CMakeFiles/Match.dir/build.make libMatch/CMakeFiles/Match.dir/build
.PHONY : Match/fast
match.o: match.cpp.o
.PHONY : match.o
# target to build an object file
match.cpp.o:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libMatch/CMakeFiles/Match.dir/build.make libMatch/CMakeFiles/Match.dir/match.cpp.o
.PHONY : match.cpp.o
match.i: match.cpp.i
.PHONY : match.i
# target to preprocess a source file
match.cpp.i:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libMatch/CMakeFiles/Match.dir/build.make libMatch/CMakeFiles/Match.dir/match.cpp.i
.PHONY : match.cpp.i
match.s: match.cpp.s
.PHONY : match.s
# target to generate assembly for a file
match.cpp.s:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libMatch/CMakeFiles/Match.dir/build.make libMatch/CMakeFiles/Match.dir/match.cpp.s
.PHONY : match.cpp.s
# Help Target
help:
@echo "The following are some of the valid targets for this Makefile:"
@echo "... all (the default if no target is provided)"
@echo "... clean"
@echo "... depend"
@echo "... Match"
@echo "... edit_cache"
@echo "... rebuild_cache"
@echo "... match.o"
@echo "... match.i"
@echo "... match.s"
.PHONY : help
#=============================================================================
# Special targets to cleanup operation of make.
# Special rule to run CMake to check the build system integrity.
# No rule that depends on this can have commands that come from listfiles
# because they might be regenerated.
cmake_check_build_system:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0
.PHONY : cmake_check_build_system

View file

@ -0,0 +1,34 @@
# Install script for directory: /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libMatch
# Set the install prefix
IF(NOT DEFINED CMAKE_INSTALL_PREFIX)
SET(CMAKE_INSTALL_PREFIX "/usr/local")
ENDIF(NOT DEFINED CMAKE_INSTALL_PREFIX)
STRING(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}")
# Set the install configuration name.
IF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME)
IF(BUILD_TYPE)
STRING(REGEX REPLACE "^[^A-Za-z0-9_]+" ""
CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}")
ELSE(BUILD_TYPE)
SET(CMAKE_INSTALL_CONFIG_NAME "")
ENDIF(BUILD_TYPE)
MESSAGE(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"")
ENDIF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME)
# Set the component getting installed.
IF(NOT CMAKE_INSTALL_COMPONENT)
IF(COMPONENT)
MESSAGE(STATUS "Install component: \"${COMPONENT}\"")
SET(CMAKE_INSTALL_COMPONENT "${COMPONENT}")
ELSE(COMPONENT)
SET(CMAKE_INSTALL_COMPONENT)
ENDIF(COMPONENT)
ENDIF(NOT CMAKE_INSTALL_COMPONENT)
# Install shared libraries without execute permission?
IF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE)
SET(CMAKE_INSTALL_SO_NO_EXE "1")
ENDIF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE)

Binary file not shown.

View file

@ -0,0 +1,35 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#include "match.h"
#include <fstream>
#include <sstream>
bool loadMatch(const char* nameFile, std::vector<Match>& match) {
match.clear();
std::ifstream f(nameFile);
while( f.good() ) {
std::string str;
std::getline(f, str);
if( f.good() ) {
std::istringstream s(str);
Match m;
s >> m.x1 >> m.y1 >> m.x2 >> m.y2;
if(!s.fail() )
match.push_back(m);
}
}
return !match.empty();
}
bool saveMatch(const char* nameFile, const std::vector<Match>& match) {
std::ofstream f(nameFile);
if( f.is_open() ) {
std::vector<Match>::const_iterator it = match.begin();
for(; it != match.end(); ++it)
f << it->x1 << " " << it->y1 << " "
<< it->x2 << " " << it->y2 << std::endl;
}
return f.is_open();
}

View file

@ -0,0 +1,17 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#ifndef MATCH_H
#define MATCH_H
#include <vector>
struct Match {
float x1, y1, x2, y2;
};
bool loadMatch(const char* nameFile, std::vector<Match>& match);
bool saveMatch(const char* nameFile, const std::vector<Match>& match);
#endif

Binary file not shown.

View file

@ -0,0 +1,16 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 2.8
# Relative path conversion top directories.
SET(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src")
SET(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src")
# Force unix paths in dependencies.
SET(CMAKE_FORCE_UNIX_PATHS 1)
# The C and CXX include file regular expressions for this directory.
SET(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$")
SET(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$")
SET(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN})
SET(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN})

View file

@ -0,0 +1,62 @@
#IncludeRegexLine: ^[ ]*#[ ]*(include|import)[ ]*[<"]([^">]+)([">])
#IncludeRegexScan: ^.*$
#IncludeRegexComplain: ^$
#IncludeRegexTransform:
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/computeH.cpp
homography.h
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/homography.h
numerics.h
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/numerics.h
algorithm
-
math.h
-
string.h
-
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/homography.cpp
homography.h
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/homography.h
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/homography.h
matrix.h
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/matrix.h
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/matrix.cpp
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/matrix.h
iostream
-
cassert
-
matrix.cpp
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/matrix.cpp
vector.cpp
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/vector.cpp
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/numerics.cpp
numerics.h
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/numerics.h
cmath
-
vector
-
limits
-
algorithm
-
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/numerics.h
matrix.h
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/matrix.h
vector
-
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/rodrigues.cpp
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/vector.cpp

View file

@ -0,0 +1,26 @@
# The set of languages for which implicit dependencies are needed:
SET(CMAKE_DEPENDS_LANGUAGES
"CXX"
)
# The set of files for implicit dependencies of each language:
SET(CMAKE_DEPENDS_CHECK_CXX
"/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/computeH.cpp" "/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o"
"/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/homography.cpp" "/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o"
"/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/matrix.cpp" "/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.o"
"/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/numerics.cpp" "/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o"
"/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/rodrigues.cpp" "/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.o"
"/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/vector.cpp" "/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/CMakeFiles/Numerics.dir/vector.cpp.o"
)
SET(CMAKE_CXX_COMPILER_ID "GNU")
# Targets to which this target links.
SET(CMAKE_TARGET_LINKED_INFO_FILES
)
# The include file search paths:
SET(CMAKE_C_TARGET_INCLUDE_PATH
"libNumerics/.."
)
SET(CMAKE_CXX_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH})
SET(CMAKE_Fortran_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH})
SET(CMAKE_ASM_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH})

View file

@ -0,0 +1,233 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 2.8
#=============================================================================
# Special targets provided by cmake.
# Disable implicit rules so canonical targets will work.
.SUFFIXES:
# Remove some rules from gmake that .SUFFIXES does not remove.
SUFFIXES =
.SUFFIXES: .hpux_make_needs_suffix_list
# Suppress display of executed commands.
$(VERBOSE).SILENT:
# A target that is always out of date.
cmake_force:
.PHONY : cmake_force
#=============================================================================
# Set environment variables for the build.
# The shell in which to execute make rules.
SHELL = /bin/sh
# The CMake executable.
CMAKE_COMMAND = /usr/bin/cmake
# The command to remove a file.
RM = /usr/bin/cmake -E remove -f
# Escaping for special characters.
EQUALS = =
# The top-level source directory on which CMake was run.
CMAKE_SOURCE_DIR = /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src
# The top-level build directory on which CMake was run.
CMAKE_BINARY_DIR = /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src
# Include any dependencies generated for this target.
include libNumerics/CMakeFiles/Numerics.dir/depend.make
# Include the progress variables for this target.
include libNumerics/CMakeFiles/Numerics.dir/progress.make
# Include the compile flags for this target's objects.
include libNumerics/CMakeFiles/Numerics.dir/flags.make
libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o: libNumerics/CMakeFiles/Numerics.dir/flags.make
libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o: libNumerics/computeH.cpp
$(CMAKE_COMMAND) -E cmake_progress_report /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/CMakeFiles $(CMAKE_PROGRESS_1)
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/Numerics.dir/computeH.cpp.o -c /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/computeH.cpp
libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.i: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/Numerics.dir/computeH.cpp.i"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -E /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/computeH.cpp > CMakeFiles/Numerics.dir/computeH.cpp.i
libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.s: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/Numerics.dir/computeH.cpp.s"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -S /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/computeH.cpp -o CMakeFiles/Numerics.dir/computeH.cpp.s
libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o.requires:
.PHONY : libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o.requires
libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o.provides: libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o.requires
$(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o.provides.build
.PHONY : libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o.provides
libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o.provides.build: libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o
libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o: libNumerics/CMakeFiles/Numerics.dir/flags.make
libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o: libNumerics/homography.cpp
$(CMAKE_COMMAND) -E cmake_progress_report /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/CMakeFiles $(CMAKE_PROGRESS_2)
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/Numerics.dir/homography.cpp.o -c /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/homography.cpp
libNumerics/CMakeFiles/Numerics.dir/homography.cpp.i: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/Numerics.dir/homography.cpp.i"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -E /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/homography.cpp > CMakeFiles/Numerics.dir/homography.cpp.i
libNumerics/CMakeFiles/Numerics.dir/homography.cpp.s: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/Numerics.dir/homography.cpp.s"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -S /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/homography.cpp -o CMakeFiles/Numerics.dir/homography.cpp.s
libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o.requires:
.PHONY : libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o.requires
libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o.provides: libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o.requires
$(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o.provides.build
.PHONY : libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o.provides
libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o.provides.build: libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o
libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.o: libNumerics/CMakeFiles/Numerics.dir/flags.make
libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.o: libNumerics/matrix.cpp
$(CMAKE_COMMAND) -E cmake_progress_report /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/CMakeFiles $(CMAKE_PROGRESS_3)
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.o"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/Numerics.dir/matrix.cpp.o -c /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/matrix.cpp
libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.i: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/Numerics.dir/matrix.cpp.i"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -E /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/matrix.cpp > CMakeFiles/Numerics.dir/matrix.cpp.i
libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.s: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/Numerics.dir/matrix.cpp.s"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -S /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/matrix.cpp -o CMakeFiles/Numerics.dir/matrix.cpp.s
libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.o.requires:
.PHONY : libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.o.requires
libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.o.provides: libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.o.requires
$(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.o.provides.build
.PHONY : libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.o.provides
libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.o.provides.build: libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.o
libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o: libNumerics/CMakeFiles/Numerics.dir/flags.make
libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o: libNumerics/numerics.cpp
$(CMAKE_COMMAND) -E cmake_progress_report /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/CMakeFiles $(CMAKE_PROGRESS_4)
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/Numerics.dir/numerics.cpp.o -c /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/numerics.cpp
libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.i: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/Numerics.dir/numerics.cpp.i"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -E /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/numerics.cpp > CMakeFiles/Numerics.dir/numerics.cpp.i
libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.s: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/Numerics.dir/numerics.cpp.s"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -S /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/numerics.cpp -o CMakeFiles/Numerics.dir/numerics.cpp.s
libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o.requires:
.PHONY : libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o.requires
libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o.provides: libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o.requires
$(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o.provides.build
.PHONY : libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o.provides
libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o.provides.build: libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o
libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.o: libNumerics/CMakeFiles/Numerics.dir/flags.make
libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.o: libNumerics/rodrigues.cpp
$(CMAKE_COMMAND) -E cmake_progress_report /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/CMakeFiles $(CMAKE_PROGRESS_5)
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.o"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/Numerics.dir/rodrigues.cpp.o -c /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/rodrigues.cpp
libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.i: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/Numerics.dir/rodrigues.cpp.i"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -E /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/rodrigues.cpp > CMakeFiles/Numerics.dir/rodrigues.cpp.i
libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.s: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/Numerics.dir/rodrigues.cpp.s"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -S /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/rodrigues.cpp -o CMakeFiles/Numerics.dir/rodrigues.cpp.s
libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.o.requires:
.PHONY : libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.o.requires
libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.o.provides: libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.o.requires
$(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.o.provides.build
.PHONY : libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.o.provides
libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.o.provides.build: libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.o
libNumerics/CMakeFiles/Numerics.dir/vector.cpp.o: libNumerics/CMakeFiles/Numerics.dir/flags.make
libNumerics/CMakeFiles/Numerics.dir/vector.cpp.o: libNumerics/vector.cpp
$(CMAKE_COMMAND) -E cmake_progress_report /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/CMakeFiles $(CMAKE_PROGRESS_6)
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object libNumerics/CMakeFiles/Numerics.dir/vector.cpp.o"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/Numerics.dir/vector.cpp.o -c /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/vector.cpp
libNumerics/CMakeFiles/Numerics.dir/vector.cpp.i: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/Numerics.dir/vector.cpp.i"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -E /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/vector.cpp > CMakeFiles/Numerics.dir/vector.cpp.i
libNumerics/CMakeFiles/Numerics.dir/vector.cpp.s: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/Numerics.dir/vector.cpp.s"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -S /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/vector.cpp -o CMakeFiles/Numerics.dir/vector.cpp.s
libNumerics/CMakeFiles/Numerics.dir/vector.cpp.o.requires:
.PHONY : libNumerics/CMakeFiles/Numerics.dir/vector.cpp.o.requires
libNumerics/CMakeFiles/Numerics.dir/vector.cpp.o.provides: libNumerics/CMakeFiles/Numerics.dir/vector.cpp.o.requires
$(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/vector.cpp.o.provides.build
.PHONY : libNumerics/CMakeFiles/Numerics.dir/vector.cpp.o.provides
libNumerics/CMakeFiles/Numerics.dir/vector.cpp.o.provides.build: libNumerics/CMakeFiles/Numerics.dir/vector.cpp.o
# Object files for target Numerics
Numerics_OBJECTS = \
"CMakeFiles/Numerics.dir/computeH.cpp.o" \
"CMakeFiles/Numerics.dir/homography.cpp.o" \
"CMakeFiles/Numerics.dir/matrix.cpp.o" \
"CMakeFiles/Numerics.dir/numerics.cpp.o" \
"CMakeFiles/Numerics.dir/rodrigues.cpp.o" \
"CMakeFiles/Numerics.dir/vector.cpp.o"
# External object files for target Numerics
Numerics_EXTERNAL_OBJECTS =
libNumerics/libNumerics.a: libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o
libNumerics/libNumerics.a: libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o
libNumerics/libNumerics.a: libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.o
libNumerics/libNumerics.a: libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o
libNumerics/libNumerics.a: libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.o
libNumerics/libNumerics.a: libNumerics/CMakeFiles/Numerics.dir/vector.cpp.o
libNumerics/libNumerics.a: libNumerics/CMakeFiles/Numerics.dir/build.make
libNumerics/libNumerics.a: libNumerics/CMakeFiles/Numerics.dir/link.txt
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --red --bold "Linking CXX static library libNumerics.a"
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && $(CMAKE_COMMAND) -P CMakeFiles/Numerics.dir/cmake_clean_target.cmake
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/Numerics.dir/link.txt --verbose=$(VERBOSE)
# Rule to build all files generated by this target.
libNumerics/CMakeFiles/Numerics.dir/build: libNumerics/libNumerics.a
.PHONY : libNumerics/CMakeFiles/Numerics.dir/build
libNumerics/CMakeFiles/Numerics.dir/requires: libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o.requires
libNumerics/CMakeFiles/Numerics.dir/requires: libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o.requires
libNumerics/CMakeFiles/Numerics.dir/requires: libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.o.requires
libNumerics/CMakeFiles/Numerics.dir/requires: libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o.requires
libNumerics/CMakeFiles/Numerics.dir/requires: libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.o.requires
libNumerics/CMakeFiles/Numerics.dir/requires: libNumerics/CMakeFiles/Numerics.dir/vector.cpp.o.requires
.PHONY : libNumerics/CMakeFiles/Numerics.dir/requires
libNumerics/CMakeFiles/Numerics.dir/clean:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics && $(CMAKE_COMMAND) -P CMakeFiles/Numerics.dir/cmake_clean.cmake
.PHONY : libNumerics/CMakeFiles/Numerics.dir/clean
libNumerics/CMakeFiles/Numerics.dir/depend:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/CMakeFiles/Numerics.dir/DependInfo.cmake --color=$(COLOR)
.PHONY : libNumerics/CMakeFiles/Numerics.dir/depend

View file

@ -0,0 +1,15 @@
FILE(REMOVE_RECURSE
"CMakeFiles/Numerics.dir/computeH.cpp.o"
"CMakeFiles/Numerics.dir/homography.cpp.o"
"CMakeFiles/Numerics.dir/matrix.cpp.o"
"CMakeFiles/Numerics.dir/numerics.cpp.o"
"CMakeFiles/Numerics.dir/rodrigues.cpp.o"
"CMakeFiles/Numerics.dir/vector.cpp.o"
"libNumerics.pdb"
"libNumerics.a"
)
# Per-language clean rules from dependency scanning.
FOREACH(lang CXX)
INCLUDE(CMakeFiles/Numerics.dir/cmake_clean_${lang}.cmake OPTIONAL)
ENDFOREACH(lang)

View file

@ -0,0 +1,3 @@
FILE(REMOVE_RECURSE
"libNumerics.a"
)

View file

@ -0,0 +1,28 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 2.8
libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/computeH.cpp
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/homography.h
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/matrix.cpp
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/matrix.h
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/numerics.h
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/vector.cpp
libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/homography.cpp
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/homography.h
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/matrix.cpp
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/matrix.h
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/vector.cpp
libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.o
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/matrix.cpp
libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/matrix.cpp
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/matrix.h
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/numerics.cpp
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/numerics.h
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/vector.cpp
libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.o
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/rodrigues.cpp
libNumerics/CMakeFiles/Numerics.dir/vector.cpp.o
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/vector.cpp

View file

@ -0,0 +1,28 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 2.8
libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o: libNumerics/computeH.cpp
libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o: libNumerics/homography.h
libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o: libNumerics/matrix.cpp
libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o: libNumerics/matrix.h
libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o: libNumerics/numerics.h
libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o: libNumerics/vector.cpp
libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o: libNumerics/homography.cpp
libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o: libNumerics/homography.h
libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o: libNumerics/matrix.cpp
libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o: libNumerics/matrix.h
libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o: libNumerics/vector.cpp
libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.o: libNumerics/matrix.cpp
libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o: libNumerics/matrix.cpp
libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o: libNumerics/matrix.h
libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o: libNumerics/numerics.cpp
libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o: libNumerics/numerics.h
libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o: libNumerics/vector.cpp
libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.o: libNumerics/rodrigues.cpp
libNumerics/CMakeFiles/Numerics.dir/vector.cpp.o: libNumerics/vector.cpp

View file

@ -0,0 +1,8 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 2.8
# compile CXX with /usr/bin/c++
CXX_FLAGS = -I/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/..
CXX_DEFINES =

View file

@ -0,0 +1,2 @@
/usr/bin/ar cr libNumerics.a CMakeFiles/Numerics.dir/computeH.cpp.o CMakeFiles/Numerics.dir/homography.cpp.o CMakeFiles/Numerics.dir/matrix.cpp.o CMakeFiles/Numerics.dir/numerics.cpp.o CMakeFiles/Numerics.dir/rodrigues.cpp.o CMakeFiles/Numerics.dir/vector.cpp.o
/usr/bin/ranlib libNumerics.a

View file

@ -0,0 +1,7 @@
CMAKE_PROGRESS_1 = 2
CMAKE_PROGRESS_2 = 3
CMAKE_PROGRESS_3 = 4
CMAKE_PROGRESS_4 = 5
CMAKE_PROGRESS_5 = 6
CMAKE_PROGRESS_6 = 7

View file

@ -0,0 +1 @@
6

View file

@ -0,0 +1,13 @@
CMAKE_MINIMUM_REQUIRED(VERSION 2.6)
PROJECT(libNumerics)
INCLUDE_DIRECTORIES(..)
ADD_LIBRARY(Numerics
computeH.cpp
homography.cpp homography.h
matrix.cpp matrix.h
numerics.cpp numerics.h
rodrigues.cpp rodrigues.h
vector.cpp)

View file

@ -0,0 +1,299 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 2.8
# Default target executed when no arguments are given to make.
default_target: all
.PHONY : default_target
#=============================================================================
# Special targets provided by cmake.
# Disable implicit rules so canonical targets will work.
.SUFFIXES:
# Remove some rules from gmake that .SUFFIXES does not remove.
SUFFIXES =
.SUFFIXES: .hpux_make_needs_suffix_list
# Suppress display of executed commands.
$(VERBOSE).SILENT:
# A target that is always out of date.
cmake_force:
.PHONY : cmake_force
#=============================================================================
# Set environment variables for the build.
# The shell in which to execute make rules.
SHELL = /bin/sh
# The CMake executable.
CMAKE_COMMAND = /usr/bin/cmake
# The command to remove a file.
RM = /usr/bin/cmake -E remove -f
# Escaping for special characters.
EQUALS = =
# The top-level source directory on which CMake was run.
CMAKE_SOURCE_DIR = /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src
# The top-level build directory on which CMake was run.
CMAKE_BINARY_DIR = /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src
#=============================================================================
# Targets provided globally by CMake.
# Special rule for the target edit_cache
edit_cache:
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running interactive CMake command-line interface..."
/usr/bin/cmake -i .
.PHONY : edit_cache
# Special rule for the target edit_cache
edit_cache/fast: edit_cache
.PHONY : edit_cache/fast
# Special rule for the target rebuild_cache
rebuild_cache:
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..."
/usr/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR)
.PHONY : rebuild_cache
# Special rule for the target rebuild_cache
rebuild_cache/fast: rebuild_cache
.PHONY : rebuild_cache/fast
# The main all target
all: cmake_check_build_system
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(CMAKE_COMMAND) -E cmake_progress_start /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/CMakeFiles /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics/CMakeFiles/progress.marks
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f CMakeFiles/Makefile2 libNumerics/all
$(CMAKE_COMMAND) -E cmake_progress_start /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/CMakeFiles 0
.PHONY : all
# The main clean target
clean:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f CMakeFiles/Makefile2 libNumerics/clean
.PHONY : clean
# The main clean target
clean/fast: clean
.PHONY : clean/fast
# Prepare targets for installation.
preinstall: all
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f CMakeFiles/Makefile2 libNumerics/preinstall
.PHONY : preinstall
# Prepare targets for installation.
preinstall/fast:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f CMakeFiles/Makefile2 libNumerics/preinstall
.PHONY : preinstall/fast
# clear depends
depend:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1
.PHONY : depend
# Convenience name for target.
libNumerics/CMakeFiles/Numerics.dir/rule:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f CMakeFiles/Makefile2 libNumerics/CMakeFiles/Numerics.dir/rule
.PHONY : libNumerics/CMakeFiles/Numerics.dir/rule
# Convenience name for target.
Numerics: libNumerics/CMakeFiles/Numerics.dir/rule
.PHONY : Numerics
# fast build rule for target.
Numerics/fast:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/build
.PHONY : Numerics/fast
computeH.o: computeH.cpp.o
.PHONY : computeH.o
# target to build an object file
computeH.cpp.o:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.o
.PHONY : computeH.cpp.o
computeH.i: computeH.cpp.i
.PHONY : computeH.i
# target to preprocess a source file
computeH.cpp.i:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.i
.PHONY : computeH.cpp.i
computeH.s: computeH.cpp.s
.PHONY : computeH.s
# target to generate assembly for a file
computeH.cpp.s:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/computeH.cpp.s
.PHONY : computeH.cpp.s
homography.o: homography.cpp.o
.PHONY : homography.o
# target to build an object file
homography.cpp.o:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/homography.cpp.o
.PHONY : homography.cpp.o
homography.i: homography.cpp.i
.PHONY : homography.i
# target to preprocess a source file
homography.cpp.i:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/homography.cpp.i
.PHONY : homography.cpp.i
homography.s: homography.cpp.s
.PHONY : homography.s
# target to generate assembly for a file
homography.cpp.s:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/homography.cpp.s
.PHONY : homography.cpp.s
matrix.o: matrix.cpp.o
.PHONY : matrix.o
# target to build an object file
matrix.cpp.o:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.o
.PHONY : matrix.cpp.o
matrix.i: matrix.cpp.i
.PHONY : matrix.i
# target to preprocess a source file
matrix.cpp.i:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.i
.PHONY : matrix.cpp.i
matrix.s: matrix.cpp.s
.PHONY : matrix.s
# target to generate assembly for a file
matrix.cpp.s:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/matrix.cpp.s
.PHONY : matrix.cpp.s
numerics.o: numerics.cpp.o
.PHONY : numerics.o
# target to build an object file
numerics.cpp.o:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.o
.PHONY : numerics.cpp.o
numerics.i: numerics.cpp.i
.PHONY : numerics.i
# target to preprocess a source file
numerics.cpp.i:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.i
.PHONY : numerics.cpp.i
numerics.s: numerics.cpp.s
.PHONY : numerics.s
# target to generate assembly for a file
numerics.cpp.s:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/numerics.cpp.s
.PHONY : numerics.cpp.s
rodrigues.o: rodrigues.cpp.o
.PHONY : rodrigues.o
# target to build an object file
rodrigues.cpp.o:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.o
.PHONY : rodrigues.cpp.o
rodrigues.i: rodrigues.cpp.i
.PHONY : rodrigues.i
# target to preprocess a source file
rodrigues.cpp.i:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.i
.PHONY : rodrigues.cpp.i
rodrigues.s: rodrigues.cpp.s
.PHONY : rodrigues.s
# target to generate assembly for a file
rodrigues.cpp.s:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/rodrigues.cpp.s
.PHONY : rodrigues.cpp.s
vector.o: vector.cpp.o
.PHONY : vector.o
# target to build an object file
vector.cpp.o:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/vector.cpp.o
.PHONY : vector.cpp.o
vector.i: vector.cpp.i
.PHONY : vector.i
# target to preprocess a source file
vector.cpp.i:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/vector.cpp.i
.PHONY : vector.cpp.i
vector.s: vector.cpp.s
.PHONY : vector.s
# target to generate assembly for a file
vector.cpp.s:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(MAKE) -f libNumerics/CMakeFiles/Numerics.dir/build.make libNumerics/CMakeFiles/Numerics.dir/vector.cpp.s
.PHONY : vector.cpp.s
# Help Target
help:
@echo "The following are some of the valid targets for this Makefile:"
@echo "... all (the default if no target is provided)"
@echo "... clean"
@echo "... depend"
@echo "... Numerics"
@echo "... edit_cache"
@echo "... rebuild_cache"
@echo "... computeH.o"
@echo "... computeH.i"
@echo "... computeH.s"
@echo "... homography.o"
@echo "... homography.i"
@echo "... homography.s"
@echo "... matrix.o"
@echo "... matrix.i"
@echo "... matrix.s"
@echo "... numerics.o"
@echo "... numerics.i"
@echo "... numerics.s"
@echo "... rodrigues.o"
@echo "... rodrigues.i"
@echo "... rodrigues.s"
@echo "... vector.o"
@echo "... vector.i"
@echo "... vector.s"
.PHONY : help
#=============================================================================
# Special targets to cleanup operation of make.
# Special rule to run CMake to check the build system integrity.
# No rule that depends on this can have commands that come from listfiles
# because they might be regenerated.
cmake_check_build_system:
cd /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0
.PHONY : cmake_check_build_system

View file

@ -0,0 +1,34 @@
# Install script for directory: /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/libNumerics
# Set the install prefix
IF(NOT DEFINED CMAKE_INSTALL_PREFIX)
SET(CMAKE_INSTALL_PREFIX "/usr/local")
ENDIF(NOT DEFINED CMAKE_INSTALL_PREFIX)
STRING(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}")
# Set the install configuration name.
IF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME)
IF(BUILD_TYPE)
STRING(REGEX REPLACE "^[^A-Za-z0-9_]+" ""
CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}")
ELSE(BUILD_TYPE)
SET(CMAKE_INSTALL_CONFIG_NAME "")
ENDIF(BUILD_TYPE)
MESSAGE(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"")
ENDIF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME)
# Set the component getting installed.
IF(NOT CMAKE_INSTALL_COMPONENT)
IF(COMPONENT)
MESSAGE(STATUS "Install component: \"${COMPONENT}\"")
SET(CMAKE_INSTALL_COMPONENT "${COMPONENT}")
ELSE(COMPONENT)
SET(CMAKE_INSTALL_COMPONENT)
ENDIF(COMPONENT)
ENDIF(NOT CMAKE_INSTALL_COMPONENT)
# Install shared libraries without execute permission?
IF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE)
SET(CMAKE_INSTALL_SO_NO_EXE "1")
ENDIF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE)

View file

@ -0,0 +1,651 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#include "homography.h"
#include "numerics.h"
#include <algorithm>
#include <math.h> /* For sqrt */
#include <string.h>
static const float minEigenValue = 1e-3f; // For regular matrix
namespace libNumerics {
/// Constructor. Field `b' used only for error computation.
ComputeH::ComputeH(Type type)
: _type(type), n( size(type) ), b(0)
{
clear();
}
// Destructor
ComputeH::~ComputeH()
{}
// Dimension of matrix w.r.t. type
int ComputeH::size(Type type)
{
switch(type) {
case Translation:
return 2;
case Zoom:
return 3;
case Rotation: // In fact 3, but nonlinear system
case GeneralZoom:
case Similarity:
return 4;
case Affine:
return 6;
case Projective:
return 8;
}
return 8;
}
// Return less general motion
ComputeH::Type ComputeH::restrict(Type t)
{
switch(t) {
case Translation:
return Translation; // Should return identity
case Rotation:
case Zoom:
return Translation;
case Similarity:
return Zoom; // Rotation also correct. Arbitrary choice.
case GeneralZoom:
return Zoom;
case Affine:
return Similarity;
case Projective:
return Affine;
}
return Affine;
}
// Reinitialize
void ComputeH::clear()
{
memset(Ann, 0, n*n*sizeof(double));
memset(Bn, 0, n*sizeof(double));
b = 0;
}
// Add two corresponding points
void ComputeH::add(float x, float y, float X, float Y, float w)
{
if(_type <= Similarity) { // Separate for readability
add_4parameters(x, y, X, Y, w);
return;
}
double x2 = x*x, y2 = y*y, xy = x*y;
double xX = x*X, yX = y*X, xY = x*Y, yY = y*Y;
double *A = Ann, *B = Bn;
*A++ += w* x2; // Equation 1
*A++ += w* xy;
A += 2;
*A++ += w* x;
A++;
if(_type == Projective) {
*A++ -= w* x*xX;
*A++ -= w* x*yX;
}
*B++ += w* x*X;
A++; // Equation 2
*A++ += w* y2;
A += 2;
*A++ += w* y;
A++;
if(_type == Projective) {
*A++ -= w* y*xX;
*A++ -= w* y*yX;
}
*B++ += w* y*X;
A +=2; // Equation 3
*A++ += w* x2;
*A++ += w* xy;
A++;
*A++ += w* x;
if(_type == Projective) {
*A++ -= w* x*xY;
*A++ -= w* x*yY;
}
*B++ += w* x*Y;
A +=3; // Equation 4
*A++ += w* y2;
A++;
*A++ += w* y;
if(_type == Projective) {
*A++ -= w* y*xY;
*A++ -= w* y*yY;
}
*B++ += w* y*Y;
A+= 4; // Equation 5
*A++ += w;
A++;
if(_type == Projective) {
*A++ -= w* xX;
*A++ -= w* yX;
}
*B++ += w* X;
A += 5; // Equation 6
*A++ += w;
*B++ += w* Y;
if(_type == Projective) {
*A++ -= w* xY;
*A++ -= w* yY;
A += 6; // Equation 7
*A++ += w* (xX*xX + xY*xY);
*A++ += w* (xX*yX + xY*yY);
*B++ -= w* (xX*X + xY*Y);
A+= 7; // Equation 8
*A++ += w* (yX*yX + yY*yY);
*B++ -= w* (yX*X + yY*Y);
}
b += w* (X*X + Y*Y);
}
// Add two corresponding points, type involving at most 4 parameters
void ComputeH::add_4parameters(float x, float y, float X, float Y, float w)
{
double *A = Ann, *B = Bn;
if(_type == Translation) {
A[0] += w;
A[3] += w;
B[0] += w* (X - x);
B[1] += w* (Y - y);
b += w* ((X-x)*(X-x) + (Y-y)*(Y-y));
return;
}
b += w* (X*X + Y*Y);
if(_type == GeneralZoom) {
A[0] += w* x*x;
A[2] += w* x;
B[0] += w* x*X;
A[5] += w* y*y;
A[7] += w* y;
B[1] += w* y*Y;
A[10]+= w;
B[2] += w* X;
A[15]+= w;
B[3] += w* Y;
return;
}
*A++ += w* (x*x + y*y); // Equation 1
if(_type != Zoom) // Similarity or Rotation
A++;
*A++ += w* x;
*A++ += w* y;
*B++ += w* (x*X + y*Y);
if(_type != Zoom) { // Similarity or Rotation
A++; // Equation 2
*A++ += w* (x*x + y*y);
*A++ += w* y;
*A++ -= w* x;
*B++ += w* (y*X - x*Y);
A++; // Prepare for next line
}
A++; // Equation 3
*A++ += w;
A++;
*B++ += w* X;
A += n-1; // Equation 4
*A++ += w;
*B++ += w* Y;
}
// Add corresponding lines of equation ux + by + x = 0
void ComputeH::add(float x, float y, float z, float X, float Y, float Z,
float w)
{
float s = 1.0f / (float)sqrt(x*x + y*y);
x *= s;
y *= s;
z *= s;
s = 1.0f / (float)sqrt(X*X + Y*Y);
X *= s;
Y *= s;
Z *= s;
if(_type <= Similarity) { // Separate for readability
add_4parameters(x, y, z, X, Y, Z, w);
return;
}
double x2 = x*x, y2 = y*y, z2 = z*z, xy = x*y, xz = x*z, yz = y*z;
double X2 = X*X, Y2 = Y*Y, Z2 = Z*Z, XY = X*Y, XZ = X*Z, YZ = Y*Z;
double *A = Ann, *B = Bn;
*A++ += w* (y2+z2) * X2; // Equation 1
*A++ -= w* xy * X2;
*A++ += w* (y2+z2) * XY;
*A++ -= w* xy * XY;
*A++ -= w* xz * X2;
*A++ -= w* xz * XY;
if(_type == Projective) {
*A++ += w* (y2+z2) * XZ;
*A++ -= w* xy * XZ;
}
*B++ += w* xz * XZ;
A++; // Equation 2
*A++ += w* (x2+z2) * X2;
*A++ -= w* xy * XY;
*A++ += w* (x2+z2) * XY;
*A++ -= w* yz * X2;
*A++ -= w* yz * XY;
if(_type == Projective) {
*A++ -= w* xy * XZ;
*A++ += w* (x2+z2) * XZ;
}
*B++ -= w* yz * XZ;
A += 2; // Equation 3
*A++ += w* (y2+z2) * Y2;
*A++ -= w* xy * Y2;
*A++ -= w* xz * XY;
*A++ -= w* xz * Y2;
if(_type == Projective) {
*A++ += w* (y2+z2) * YZ;
*A++ -= w* xy * YZ;
}
*B++ += w* xz * YZ;
A += 3; // Equation 4
*A++ += w* (x2+z2) * Y2;
*A++ -= w* yz * XY;
*A++ -= w* yz * Y2;
if(_type == Projective) {
*A++ -= w* xy * YZ;
*A++ += w* (x2+z2) * YZ;
}
*B++ += w* yz * YZ;
A += 4; // Equation 5
*A++ += w* X2; // *(x2+y2=1)
*A++ += w* XY; // *(x2+y2=1)
if(_type == Projective) {
*A++ -= w* xz * XZ;
*A++ -= w* yz * XZ;
}
*B++ -= w* XZ; // *(x2+y2=1)
A += 5; // Equation 6
*A++ += w* Y2; // *(x2+y2=1)
*B++ -= w* YZ; // *(x2+y2=1)
if(_type == Projective) {
*A++ -= w* xz * YZ;
*A++ -= w* yz * YZ;
A += 6; // Equation 7
*A++ += w* (y2+z2) * Y2;
*A++ -= w* xy * Z2;
*B++ += w* xz * Z2;
A += 7; // Equation 8
*A++ += w* (x2+z2) * Z2;
*B++ += w* yz * Z2;
}
b += w* Z2; // *(x2+y2=1)
}
// Add two corresponding lines, type involving at most 4 parameters
void ComputeH::add_4parameters(float x, float y, float z,
float X, float Y, float Z, float w)
{
double x2 = x*x, y2 = y*y, z2 = z*z, xy = x*y, xz = x*z, yz = y*z;
double X2 = X*X, Y2 = Y*Y, Z2 = Z*Z, XY = X*Y, XZ = X*Z, YZ = Y*Z;
double *A = Ann, *B = Bn;
if(_type == Translation) {
*A++ += w* X2; // *(x2+y2=1)
*A++ += w* XY; // *(x2+y2=1)
*B++ += w* (yz*XY + xz*X2 - XZ/* *(x2+y2=1) */);
A++;
*A++ += w* Y2; // *(x2+y2=1)
*B++ += w* (xz*XY + yz*Y2 - YZ/* *(x2+y2=1) */);
b += w* (z2 + Z2 + y2*X2 + x2*Z2 - 2*(xz*XZ + yz*YZ + xy*XZ));
return;
}
b += w* Z2; // *(x2+y2=1)
if(_type == GeneralZoom) {
*A++ += w* (y2+z2) * X2;
*A++ -= w* xy * XY;
*A++ -= w* xz * X2;
*A++ -= w* xz * XY;
*B++ += w* xz * XZ;
A++;
*A++ += w* (x2+z2) * Y2;
*A++ -= w* yz * XY;
*A++ -= w* yz * Y2;
*B++ += w* yz * YZ;
A += 2;
*A++ += w* X2; // *(x2+y2=1)
*A++ += w* XY; // *(x2+y2=1)
*B++ -= w* XZ; // *(x2+y2=1)
A += 3;
*A++ += w* Y2; // *(x2+y2=1)
*B++ -= w* YZ; // *(x2+y2=1)
return;
}
if(_type == Zoom) {
*A++ += w* (z2/* *(X2+Y2=1)*/ + y2*X2 + x2*Y2 - 2*xy*XY);
*A++ -= w* (yz*XY + xz*X2);
*A++ -= w* (yz*Y2 + xz*XY);
*B++ += w* (yz*YZ + xz*X2);
} else { // Similarity or Rotation
*A++ += w* (1 /* =x2+y2*/+ 2*(z2 - xy)) * X2;
*A++ += w* (x2 - y2) * XY;
*A++ -= w* (xz + yz) * X2;
*A++ -= w* (xz + yz) * XY;
*B++ += w* (xz + yz) * XZ;
A++;
*A++ += w* (1 /* =x2+y2*/+ 2*(z2 + xy)) * Y2;
*A++ += w* (xz - yz) * XY;
*A++ += w* (xz - yz) * Y2;
*B++ += w* (yz - xz) * YZ;
A++; // Prepare for next line
}
A++;
*A++ += w* X2; // *(x2+y2=1)
*A++ += w* XY; // *(x2+y2=1)
*B++ -= w* XZ; // *(x2+y2=1)
A += n-1;
*A++ += w* Y2; // *(x2+y2=1)
*B++ -= w* YZ; // *(x2+y2=1)
}
// Wrap vector of unknowns `v' into structure `map'
void ComputeH::wrap(Homography& h, const vector<double>& v) const
{
int i = 0;
h.mat()(0,0) = (_type==Translation)? 1.0f: v(i++);
h.mat()(0,1) = (_type==Translation || _type==Zoom || _type==GeneralZoom) ?
0: v(i++);
if(n >= 6) {
h.mat()(1,0) = v(i++);
h.mat()(1,1) = v(i++);
} else {
h.mat()(1,0) = -h.mat()(0,1);
h.mat()(1,1) = (_type==GeneralZoom)? v(i++): h.mat()(0,0);
}
h.mat()(0,2) = v(i++);
h.mat()(1,2) = v(i++);
if(_type == Projective) {
h.mat()(2,0) = v(i++);
h.mat()(2,1) = v(i++);
} else
h.mat()(2,0) = h.mat()(2,1) = 0;
h.mat()(2,2) = 1.0;
}
/// Unwrap parameters in \a h into vector of unknowns \a v.
void ComputeH::unwrap(const Homography& h, vector<double>& v) const
{
int i = 0;
if(_type != Translation) {
v(i++) = h.mat()(0,0);
if(_type != Zoom) {
if(_type != GeneralZoom) {
v(i++) = h.mat()(0,1); // Rotation or Similarity or...
if(n >= 6) // Affine or Projective
v(i++) = h.mat()(1,0);
}
if(_type==GeneralZoom || _type==Affine || _type==Projective)
v(i++) = h.mat()(1,1);
}
}
v(i++) = h.mat()(0,2);
v(i++) = h.mat()(1,2);
if(_type == Projective) {
v(i++) = h.mat()(2,0);
v(i++) = h.mat()(2,1);
}
}
// Sum of weights (=#correspondences)
float ComputeH::weight() const
{
// Diagonal coefficient affecting translation
int i = (_type == Projective) ? 6 : n;
return static_cast<float>(Ann[(i-1)*(n+1)]); // Element (i-1,i-1)
}
// Return quadratic error when mapping with `motion'
float ComputeH::q_error(const Homography& map) const
{
vector<double> v(n);
unwrap(map, v);
return q_error(v);
}
// Idem, with arguments in a vector
float ComputeH::q_error(const vector<double>& v) const
{
double e = b;
// Diagonal terms
const double* A = Ann + n*n-1;
for(int i = n-1; i >= 0; i--, A -= n+1)
e += *A * v(i) * v(i);
// Cross terms
A = Ann + (n-1)*n; // Last row
for(int i = n-1; i >= 0; i--, A -= n) {
double vi = v(i);
e -= 2.0 * Bn[i] * vi;
for(int j = n-1; j > i; j--)
e += 2.0 * A[j] * vi * v(j);
}
return static_cast<float>(e);
}
// LSE for rotation: solve linear system under quadratic constraint
bool ComputeH::compute_rotation(vector<double>& B) const
{
if(Ann[15] <= 0) // No point added or absurd value
return false;
B(0) = Ann[15] * Bn[0] - Ann[2] * Bn[2] - Ann[3] * Bn[3];
B(1) = Ann[15] * Bn[1] - Ann[3] * Bn[2] + Ann[2] * Bn[3];
double root = sqrt(B(0)*B(0) + B(1)*B(1));
if(root < minEigenValue)
return false;
// Test first solution
double lambda1 = (Ann[2]*Ann[2] + Ann[3]*Ann[3] + root) / Ann[15];
B(0) /= root;
B(1) /= root;
B(2) = (-Ann[2]*Bn[0] - Ann[3]*Bn[1] + lambda1 * Bn[2]) / root;
B(3) = (-Ann[3]*Bn[0] + Ann[2]*Bn[1] + lambda1 * Bn[3]) / root;
float v1 = q_error(B);
// Test second solution
vector<double> C(4);
double lambda2 = (Ann[2]*Ann[2] + Ann[3]*Ann[3] - root) / Ann[15];
C(0) = -B(0);
C(1) = -B(1);
C(2) = -(-Ann[2]*Bn[0] - Ann[3]*Bn[1] + lambda2 * Bn[2]) / root;
C(3) = -(-Ann[3]*Bn[0] + Ann[2]*Bn[1] + lambda2 * Bn[3]) / root;
if(v1 > q_error(C)) // Keep second solution
B = C;
return true;
}
// Return LSE motion and the sum of weights
float ComputeH::compute(Homography& map) const
{
vector<double> B(n);
B.read(Bn);
if(_type == Rotation) {
if(! compute_rotation(B))
return 0;
} else {
matrix<double> A(n,n);
A.read(Ann);
Normalization left, right;
if(_type == Projective && !normalize(left, A, B, right))
return 0;
A.symUpper();
vector<double> oldB(B);
if(! solveLU(A, B))
return 0;
if(_type == Projective && ! de_normalize(left, B, right))
return 0;
}
wrap(map, B);
return weight();
}
// Normalize independently original and final points so that the new
// origin is their centroid and their mean square distance (to it) is 2
bool ComputeH::normalize(Normalization& left,
matrix<double>& A, vector<double>& B,
Normalization& right) const
{
double w = A(5,5); // Total weight
if(w < minEigenValue)
return false;
double invW = 1.0 / w;
// Find normalizations (zoom-translation)
right.s = (A(0,0) + A(1,1)) - (A(0,4)*A(0,4) + A(1,4)*A(1,4))*invW;
if(right.s < minEigenValue)
return false;
right.s = sqrt(2.0*w / right.s);
right.x = - invW * right.s * A(0,4);
right.y = - invW * right.s * A(1,4);
left.s = b - (B(4)*B(4) + B(5)*B(5))*invW;
if(left.s < minEigenValue)
return false;
left.s = sqrt(2.0*w / left.s);
left.x = - invW * left.s * B(4);
left.y = - invW * left.s * B(5);
double norm = left.x*left.x + left.y*left.y;
double s2 = right.s*right.s, sS = right.s*left.s, S2 = left.s*left.s;
// Normalization of vector B
double b0 = B(0), b1 = B(1), b2 = B(2), b3 = B(3);
B(0) = sS * B(0) - w*right.x*left.x;
B(1) = sS * B(1) - w*right.y*left.x;
B(2) = sS * B(2) - w*right.x*left.y;
B(3) = sS * B(3) - w*right.y*left.y;
B(4) = B(5) = 0;
B(6) = sS*(left.s*B(6) - 2*(left.x*b0 + left.y*b2)) +
w*right.x*(norm - 2.0);
B(7) = sS*(left.s*B(7) - 2*(left.x*b1 + left.y*b3)) +
w*right.y*(norm - 2.0);
// Normalization of matrix A
double a0 = A(0,0), a1 = A(0,1), a6 = A(0,6), a7 = A(0,7), a9 = A(1,1);
double a15 = A(1,7), a22 = A(2,6), a23 = A(2,7), a31 = A(3,7);
A(0,0) = s2 * A(0,0) - w*right.x*right.x;
A(0,1) = s2 * A(0,1) - w*right.x*right.y;
A(0,4) = 0;
A(0,6) = right.s*(sS*A(0,6) - right.s*left.x*a0 - left.s*right.x*b0) +
w*right.x*left.x*right.x - right.x * B(0);
A(0,7) = right.s*(sS*A(0,7) - right.s*left.x*a1 - left.s*right.x*b1) +
w*right.x*left.x*right.y - right.y * B(0);
A(1,1) = s2 * A(1,1) - w*right.y*right.y;
A(1,4) = 0;
A(1,6) = A(0,7);
A(1,7) = right.s*(sS*A(1,7) - right.s*left.x*a9 - left.s*right.y*b1) +
w*right.y*left.x*right.y - right.y * B(1);
A(2,2) = A(0,0);
A(2,3) = A(0,1);
A(2,5) = 0;
A(2,6) = right.s*(sS*A(2,6) - right.s*left.y*a0 - left.s*right.x*b2) +
w*right.x*left.y*right.x - right.x * B(2);
A(2,7) = right.s*(sS*A(2,7) - right.s*left.y*a1 - left.s*right.x*b3) +
w*right.x*left.y*right.y - right.y * B(2);
A(3,3) = A(1,1);
A(3,5) = 0;
A(3,6) = A(2,7);
A(3,7) = right.s*(sS*A(3,7) - right.s*left.y*a9 - left.s*right.y*b3) +
w*right.y*left.y*right.y - right.y * B(3);
A(4,6) = -B(0);
A(4,7) = -B(1);
A(5,6) = -B(2);
A(5,7) = -B(3);
A(6,6) = s2*(S2*A(6,6) - 2*left.s*(left.x*a6+left.y*a22) + a0*norm) -
2*right.x*(B(6) + w*right.x);
A(6,7) = s2*(S2*A(6,7) - 2*left.s*(left.x*a7+left.y*a23) + a1*norm) -
right.x*B(7) - right.y*B(6) - 2*w*right.x*right.y;
A(7,7) = s2*(S2*A(7,7) - 2*left.s*(left.x*a15+left.y*a31) + a9*norm) -
2*right.y*(B(7) + w*right.y);
return true;
}
// `l' (left) and 'r' (right) representing zoom-translation normalizations,
// and `B' the parameters of a projective motion,
// compute l^-1 B r
bool ComputeH::de_normalize(const Normalization& l,
vector<double>& B,
const Normalization& r)
{
// B := B r
B(4) += r.x * B(0) + r.y * B(1); // Line 1
B(0) *= r.s;
B(1) *= r.s;
B(5) += r.x * B(2) + r.y * B(3); // Line 2
B(2) *= r.s;
B(3) *= r.s;
double f = r.x * B(6) + r.y * B(7) + 1.0; // Line 3
if(-minEigenValue < f && f < minEigenValue)
return false; // Origin of right normalization on line at infinity
B(6) *= r.s;
B(7) *= r.s;
// B := l^-1 B
double s = 1.0 / (l.s * f);
B(0) = (B(0) - l.x*B(6)) * s; // Line 1
B(1) = (B(1) - l.x*B(7)) * s;
B(4) = (B(4) - l.x* f ) * s;
B(2) = (B(2) - l.y*B(6)) * s; // Line 2
B(3) = (B(3) - l.y*B(7)) * s;
B(5) = (B(5) - l.y* f ) * s;
B(6) /= f; // Line 3
B(7) /= f;
return true;
}
} // libNumerics

View file

@ -0,0 +1,73 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#include "homography.h"
namespace libNumerics {
/// Constructor.
Homography::Homography()
: m_H( matrix<double>::eye(3) )
{}
/// Put to identity.
void Homography::setId()
{
m_H = matrix<double>::eye(3);
}
/// Set to translation.
void Homography::setTrans(double dx, double dy)
{
setId();
m_H(0,2) = dx;
m_H(1,2) = dy;
}
/// Set to zoom.
void Homography::setZoom(double zx, double zy)
{
setId();
m_H(0,0) = zx;
m_H(1,1) = zy;
}
/// Apply homography.
void Homography::operator()(double& x, double& y) const
{
vector<double> m(3);
m(0) = x;
m(1) = y;
m(2) = 1.0f;
m = m_H * m;
double z_1 = 1.0 / m(2);
x = m(0) * z_1;
y = m(1) * z_1;
}
/// Compose homographies.
Homography Homography::operator*(const Homography& rhs) const
{
Homography h;
h.m_H = m_H * rhs.m_H;
h.normalize();
return h;
}
/// Inverse homography.
Homography Homography::inverse() const
{
Homography h;
h.m_H = m_H.inv();
h.normalize();
return h;
}
/// Put coef(2,2) to 1.
void Homography::normalize()
{
m_H /= m_H(2,2);
}
} // libNumerics

View file

@ -0,0 +1,83 @@
#ifndef HOMOGRAPHY_H
#define HOMOGRAPHY_H
#include "matrix.h"
namespace libNumerics {
/// 2-D homography transform.
class Homography {
public:
Homography();
void setId();
void setTrans(double dx, double dy);
void setZoom(double zx, double zy);
matrix<double>& mat() { return m_H; }
const matrix<double>& mat() const { return m_H; }
void operator()(double& x, double& y) const;
Homography operator*(const Homography& rhs) const;
Homography inverse() const;
private:
matrix<double> m_H;
void normalize();
};
/// Homography (and more restricted transforms) estimation.
class ComputeH {
public:
enum Type { Translation, // (2 parameters)
Rotation, // Rotation/Translation (3 parameters)
Zoom, // Zoom/Translation (3 parameters)
GeneralZoom, // Non uniform zoom/Translation (4 parameters)
Similarity, // Zoom/Rotation/Translation (4 parameters)
Affine, // (6 parameters)
Projective // (8 parameters)
};
static Type restrict(Type t); // Return less general motion
public:
ComputeH(Type type);
~ComputeH();
Type type() const { return _type; }
void clear();
/// Add corresponding points (x1,y1) and (x2,y2)
void add(float x1, float y1, float x2, float y2, float w = 1.0f);
/// Add corresponding lines of equation u x + v y + w = 0
void add(float a1, float b1, float c1,
float a2, float b2, float c2, float w = 1.0f);
float weight() const; ///< Sum of weights (=#correspondences)
float q_error(const Homography& map) const; ///< Quadratic error
float compute(Homography& map) const; ///< LSE motion, return support weight
private:
Type _type;
int n; ///< Dimension of matrix = # unknown parameters
double Ann[64], Bn[8], b; // Min (X 1) (A B) (X 1)^T is X^T = Ann^-1 Bn
static int size(Type type);
void add_4parameters(float x1, float y1, float x2, float y2, float w);
void add_4parameters(float a1, float b1, float c1,
float a2, float b2, float c2, float w);
void wrap(Homography& map, const vector<double>& v) const;
void unwrap(const Homography& map, vector<double>& v) const;
float q_error(const vector<double>& v) const; // Quadratic error
bool compute_rotation(vector<double>& B) const;
/// For Projective, data normalization is required
class Normalization { public: double x, y, s; };
bool normalize(Normalization& left,
matrix<double>& A, vector<double>& B,
Normalization& right) const;
static bool de_normalize(const Normalization& left,
vector<double>& B,
const Normalization& right);
};
} // libNumerics
#endif

Binary file not shown.

View file

@ -0,0 +1,565 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#ifdef MATRIX_H // Do nothing if not included from matrix.h
#define INDEX(i,j) ((i) * m_cols + (j))
namespace libNumerics {
/// Constructor for \a m*\a n matrix.
/// \param m number of rows.
/// \param n number of columns.
template <typename T>
matrix<T>::matrix(int m, int n)
{
alloc(m, n);
}
/// Copy constructor.
template <typename T>
matrix<T>::matrix(const matrix<T>& m)
{
alloc(m.m_rows, m.m_cols);
for(int i = nElements()-1; i >= 0; i--)
p[i] = m.p[i];
}
/// Destructor.
template <typename T>
matrix<T>::~matrix()
{
free();
}
/// Assignment operator.
template <typename T>
matrix<T>& matrix<T>::operator=(const matrix<T>& m)
{
if(&m == this) return *this;
if(m.nElements() != nElements()){
free();
alloc(m.m_rows, m.m_cols);
} else {
m_rows = m.m_rows;
m_cols = m.m_cols;
}
for(int i = nElements()-1; i >= 0; i--)
p[i] = m.p[i];
return *this;
}
/// Access the coefficient on the \a i-th row, \a j-th column.
template <typename T>
inline T matrix<T>::operator() (int i, int j) const
{
assert(i >= 0 && i < m_rows && j >= 0 && j < m_cols);
return p[INDEX(i,j)];
}
/// Access the coefficient on the \a i-th row, \a j-th column.
template <typename T>
inline T& matrix<T>::operator() (int i, int j)
{
assert(i >= 0 && i < m_rows && j >= 0 && j < m_cols);
return p[INDEX(i,j)];
}
template <typename T>
inline T matrix<T>::operator() (int i) const
{
assert(i >= 0 && i < nElements());
return p[i];
}
template <typename T>
inline T& matrix<T>::operator() (int i)
{
assert(i >= 0 && i < nElements());
return p[i];
}
/// Set matrix at constant value.
///
/// Assign all coefficients to the value \a a.
template <typename T>
inline void matrix<T>::operator=(T a)
{
for(int i = nElements()-1; i >= 0; i--)
p[i] = a;
}
/// Multiply a matrix by scalar.
/// \param a a scalar.
template <typename T>
matrix<T> matrix<T>::operator*(T a) const
{
matrix<T> prod(m_rows, m_cols);
for(int i = nElements()-1; i >= 0; i--)
prod.p[i] = a * p[i];
return prod;
}
/// Multiply a matrix by scalar.
/// \param a a scalar.
template <typename T>
void matrix<T>::operator*=(T a)
{
for(int i = nElements()-1; i >= 0; i--)
p[i] *= a;
}
/// Divide a matrix by scalar.
/// \param a a scalar.
template <typename T>
matrix<T> matrix<T>::operator/(T a) const
{
return (*this) * ((T)1/a);
}
/// Divide a matrix by scalar.
/// \param a a scalar.
template <typename T>
void matrix<T>::operator/=(T a)
{
*this *= (T)1 / a;
}
/// Matrix sum.
template <typename T>
matrix<T> matrix<T>::operator+(const matrix<T>& m) const
{
assert(m.m_rows == m_rows && m.m_cols == m_cols);
matrix<T> sum(m_rows,m_cols);
for(int i = nElements()-1; i >= 0; i--)
sum.p[i] = p[i] + m.p[i];
return sum;
}
/// Matrix sum.
template <typename T>
void matrix<T>::operator+=(const matrix<T>& m)
{
assert(m.m_rows == m_rows && m.m_cols == m_cols);
for(int i = nElements()-1; i >= 0; i--)
p[i] += m.p[i];
}
/// Matrix subtraction.
template <typename T>
matrix<T> matrix<T>::operator-(const matrix<T>& m) const
{
assert(m.m_rows == m_rows && m.m_cols == m_cols);
matrix<T> sub(m_rows,m_cols);
for(int i = nElements()-1; i >= 0; i--)
sub.p[i] = p[i] - m.p[i];
return sub;
}
/// Matrix subtraction.
template <typename T>
void matrix<T>::operator-=(const matrix<T>& m)
{
assert(m.m_rows == m_rows && m.m_cols == m_cols);
for(int i = nElements()-1; i >= 0; i--)
p[i] -= m.p[i];
}
template <typename T>
matrix<T> matrix<T>::operator-() const
{
matrix<T> opp(m_rows, m_cols);
for(int i = nElements()-1; i >= 0; i--)
opp.p[i] = -p[i];
return opp;
}
/// Matrix multiplication.
template <typename T>
matrix<T> matrix<T>::operator*(const matrix<T>& m) const
{
assert(m_cols == m.m_rows);
matrix<T> prod(m_rows, m.m_cols);
T* out = prod.p;
for(int i = 0; i < prod.m_rows; i++) {
const T* left = p + i*m_cols;
for(int j = 0; j < prod.m_cols; j++, out++) {
const T* right = m.p + j;
*out = 0;
for(int k = 0; k < m_cols; k++) {
*out += left[k] * *right;
right += m.m_cols;
}
}
}
return prod;
}
/// Matrix-vector multiplication.
template <typename T>
vector<T> matrix<T>::operator*(const vector<T>& m) const
{
assert(m_cols == m.m_rows);
vector<T> prod(m_rows);
T* out = prod.p;
for(int i = 0; i < prod.m_rows; i++, out++) {
const T* left = p + i*m_cols;
const T* right = m.p;
*out = 0;
for(int k = 0; k < m_cols; k++)
*out += left[k] * right[k];
}
return prod;
}
/// Tranposed of matrix.
template <typename T>
matrix<T> matrix<T>::t() const
{
matrix<T> t(ncol(), nrow());
T* out = t.p;
for(int i = 0; i < t.nrow(); i++) {
const T* in = p + i;
for(int j = 0; j < t.ncol(); j++) {
*out++ = *in;
in += ncol();
}
}
return t;
}
/// Symmetrize upper part of matrix.
template <typename T>
void matrix<T>::symUpper()
{
assert(m_rows == m_cols);
for(int i = 1; i < m_rows; i++) {
const T* in = p + i;
T* out = p + m_cols*i;
for(int j = 0; j < i; j++) {
*out++ = *in;
in += m_cols;
}
}
}
/// Symmetrize lower part of matrix.
template <typename T>
void matrix<T>::symLower()
{
assert(m_rows == m_cols);
for(int i = 1; i < m_rows; i++) {
const T* in = p + m_cols*i;
T* out = p + i;
for(int j = 0; j < i; j++) {
*out = *in++;
out += m_cols;
}
}
}
template <typename T>
vector<T> matrix<T>::diag() const
{
assert(m_rows == m_cols);
vector<T> t(m_rows);
for(int i = 0; i < m_rows; i++)
t.p[i] = p[i*(m_cols+1)];
return t;
}
/// Matrix made of zeros.
template <typename T>
matrix<T> matrix<T>::zeros(int m, int n)
{
matrix<T> M(m,n);
for(int i = M.nElements()-1; i >= 0; i--)
M.p[i] = (T)0;
return M;
}
/// Matrix made of ones.
template <typename T>
matrix<T> matrix<T>::ones(int m, int n)
{
matrix<T> M(m,n);
for(int i = M.nElements()-1; i >= 0; i--)
M.p[i] = (T)1;
return M;
}
/// Identity matrix.
template <typename T>
matrix<T> matrix<T>::eye(int n)
{
matrix<T> M(n,n);
for(int i = M.nElements()-1; i >= 0; i--)
M.p[i] = (T)0;
for(int i = n-1; i >= 0; i--)
M.p[i*(n+1)] = (T)1;
return M;
}
/// Extract the submatrix [i0,i1]x[j0,j1].
/// \param i0 first row
/// \param i1 last row
/// \param j0 first column
/// \param j1 last column
template <typename T>
matrix<T> matrix<T>::copy(int i0, int i1, int j0, int j1) const
{
assert(0 <= i0 && i0 <= i1 && i1 <= m_rows &&
0 <= j0 && j0 <= j1 && j1 <= m_cols);
matrix<T> sub(i1-i0+1,j1-j0+1);
T* out = sub.p;
for(int i = i0; i <= i1; i++) {
const T* in = p + INDEX(i, j0);
for(int j = j0; j <= j1; j++)
*out++ = *in++;
}
return sub;
}
/// Extract the columns of index in [j0,j1].
/// \param j0 first column
/// \param j1 last column
template <typename T>
matrix<T> matrix<T>::copyCols(int j0, int j1) const
{
return copy(0, lastRow(), j0, j1);
}
/// Extract the rows of index in [i0,i1].
/// \param i0 first row
/// \param i1 last row
template <typename T>
matrix<T> matrix<T>::copyRows(int i0, int i1) const
{
return copy(i0, i1, 0, lastCol());
}
/// Paste a matrix in another one, at position (\a i0,\a j0)
/// \param i0 first row where to paste in
/// \param j0 first column where to paste in
/// \param matrix to paste
template <typename T>
void matrix<T>::paste(int i0, int j0, const matrix<T>& m)
{
assert(i0 >= 0 && i0+m.m_rows <= m_rows &&
j0 >= 0 && j0+m.m_cols <= m_cols);
const T* in = m.p;
for(int i = 0; i < m.m_rows; i++) {
T* out = p + INDEX(i0+i, j0);
for(int j = 0; j < m.m_cols; j++)
*out++ = *in++;
}
}
/// Concatenate matrices.
template <typename T>
matrix<T> cat(const matrix<T>& m1, const matrix<T>& m2)
{
assert(m1.m_rows == m2.m_rows);
matrix<T> m(m1.m_rows, m1.m_cols+m2.m_cols);
m.paste(0, 0, m1);
m.paste(0, m1.m_cols, m2);
return m;
}
/// Copy column number \a j.
template <typename T>
vector<T> matrix<T>::col(int j) const
{
assert(j >= 0 && j < m_cols);
vector<T> c(m_rows);
const T* in = p + j;
for(int i = 0; i < m_rows; i++) {
c(i) = *in;
in += m_cols;
}
return c;
}
/// Copy row number \a i.
template <typename T>
inline matrix<T> matrix<T>::row(int i) const
{
return copy(i, i, 0, lastCol());
}
template <class T>
void swap(matrix<T>& A, matrix<T>& B)
{
int i=A.m_rows;
A.m_rows = B.m_rows;
B.m_rows = i;
i = A.m_cols;
A.m_cols = B.m_cols;
B.m_cols = i;
T* p = A.p;
A.p = B.p;
B.p = p;
}
template <typename T>
void matrix<T>::swapRows(int i0, int i1)
{
assert(0 <= i0 && i0 < m_rows &&
0 <= i1 && i1 < m_rows);
T* row0 = p + i0*m_cols;
T* row1 = p + i1*m_cols;
for(int j = m_cols-1; j >= 0; j--) {
T tmp = *row0; *row0++ = *row1; *row1++ = tmp;
}
}
template <typename T>
void matrix<T>::swapCols(int j0, int j1)
{
assert(0 <= j0 && j0 < m_cols &&
0 <= j1 && j1 < m_cols);
T* col0 = p + j0;
T* col1 = p + j1;
for(int i = m_rows-1; i >= 0; i--) {
T tmp = *col0; *col0 = *col1; *col1 = tmp;
col0 += m_cols;
col1 += m_cols;
}
}
/// Copy the array values in a matrix, row by row.
/// \param m number of rows
/// \param n number of columns
/// \param v an array of scalar of size m*n
template <typename T> template <typename U>
void matrix<T>::read(const U* v)
{
for(int i = nElements()-1; i >= 0; i--)
p[i] = (T)v[i];
}
/// Read the coefficients from \a m.
template <typename T>
inline void matrix<T>::read(const matrix<T>& m)
{
assert(m.nElements() == nElements());
read(m.p);
}
/// Copy the matrix coefficients in an array.
///
/// The matrix is scanned row by row.
template <typename T>
void matrix<T>::write(T* vect) const
{
for(int i = nElements()-1; i >= 0; i--)
vect[i] = p[i];
}
template <typename T>
void matrix<T>::alloc(int m, int n)
{
assert(m > 0 && n > 0);
m_rows = m;
m_cols = n;
p = new T[m*n];
}
template <typename T>
inline void matrix<T>::free()
{
delete [] p;
p = NULL;
}
template <typename T>
inline int matrix<T>::nElements() const
{
return m_rows*m_cols;
}
/// Submatrix without row \a i0 and col \a j0.
template <typename T>
matrix<T>& matrix<T>::sub(matrix<T>& s, int i0, int j0) const
{
const T* in = p;
T* out = s.p;
for(int i = 0; i < i0; i++) {
for(int j = 0; j < j0; j++)
*out++ = *in++;
++in; // Skip col j0
for(int j = j0+1; j < m_cols; j++)
*out++ = *in++;
}
in += m_cols; // Skip row i0
for(int i = i0+1; i < m_rows; i++) {
for(int j = 0; j < j0; j++)
*out++ = *in++;
++in; // Skip col j0
for(int j = j0+1; j < m_cols; j++)
*out++ = *in++;
}
return s;
}
/// Trace.
template <typename T>
T matrix<T>::tr() const
{
assert(m_rows == m_cols);
T res = (T)0;
for(int i = 0; i < m_rows; i++)
res += p[i*(m_cols+1)];
return res;
}
/// Determinant. Slow, use only for small matrices.
template <typename T>
T matrix<T>::det() const
{
assert(m_rows == m_cols);
if(m_rows == 1)
return p[0];
if(m_rows == 2)
return (p[0]*p[3]-p[1]*p[2]);
T res = (T)0;
T sign = (T)1;
matrix<T> s(m_rows-1, m_cols-1);
for(int j = 0; j < m_cols; j++) {
res += sign*p[j]*sub(s,0,j).det();
sign = -sign;
}
return res;
}
/// Inverse. Slow, use only for small matrices.
template <typename T>
matrix<T> matrix<T>::inv() const
{
assert(m_rows == m_cols);
matrix<T> res(m_rows, m_cols);
if(m_rows == 1)
res.p[0] = (T)1/p[0];
else {
T d = (T)1 / det();
T signi = (T)1;
T* out = res.p;
matrix<T> s(m_rows-1, m_cols-1);
for(int i = 0; i < m_rows; i++) {
T signj = signi;
for(int j = 0; j < m_cols; j++) {
*out++ = signj*d*sub(s,j,i).det();
signj = -signj;
}
signi = -signi;
}
}
return res;
}
} // namespace libNumerics
#undef INDEX
#endif // MATRIX_H

View file

@ -0,0 +1,175 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#ifndef MATRIX_H
#define MATRIX_H
#include <iostream>
#include <cassert>
namespace libNumerics {
// Forward declaration, definition below
template <typename T> class vector;
template <typename T> class matrix;
template <typename T> matrix<T> cat(const matrix<T>&, const matrix<T>&);
template <typename T> void swap(matrix<T>&, matrix<T>&);
/// Matrix class
template <typename T>
class matrix
{
public:
static matrix<T> zeros(int m) { return zeros(m,m); }
static matrix<T> zeros(int m, int n);
static matrix<T> ones(int m) { return ones(m,m); }
static matrix<T> ones(int m, int n);
static matrix<T> eye(int n); ///< Identity matrix.
public:
matrix(int m, int n);
matrix(const matrix<T>& m);
virtual ~matrix();
matrix<T>& operator=(const matrix<T>& m);
int nrow() const { return m_rows; } ///< The number of rows.
int ncol() const { return m_cols; } ///< The number of columns.
T operator() (int i, int j) const;
T& operator() (int i, int j);
T operator() (int i) const;
T& operator() (int i);
void operator=(T a);
matrix<T> operator*(T a) const;
matrix<T> operator/(T a) const;
void operator*=(T a);
void operator/=(T a);
/// Product by scalar.
friend matrix<T> operator*(T a, const matrix<T>& m)
{ return m * a; }
matrix<T> operator+(const matrix<T>& m) const;
matrix<T> operator-(const matrix<T>& m) const;
matrix<T> operator-() const; ///< Matrix opposite.
matrix<T> operator*(const matrix<T>& m) const;
vector<T> operator*(const vector<T>& m) const;
void operator+=(const matrix<T>& m);
void operator-=(const matrix<T>& m);
matrix<T> t() const; ///< Transpose.
vector<T> diag() const; ///< Diagonal of matrix.
T tr() const;
T det() const;
matrix<T> inv() const;
void symUpper();
void symLower();
matrix<T> copy(int i0, int i1, int j0, int j1) const;
matrix<T> copyCols(int j0, int j1) const;
matrix<T> copyRows(int i0, int i1) const;
void paste(int i0, int j0, const matrix<T>& block);
friend matrix<T> cat<T>(const matrix<T>& left, const matrix<T>& right);
vector<T> col(int j) const; ///< Copy column.
matrix<T> row(int i) const; ///< Copy row.
int lastCol() const {return m_cols-1;} ///< Index of last column.
int lastRow() const {return m_rows-1;} ///< Index of last row.
friend void swap<T>(matrix<T>&, matrix<T>&);
void swapRows(int i0, int i1);
void swapCols(int j0, int j1);
template <typename U>
void read(const U* v);
void read(const matrix<T>& v);
void write(T* vect) const;
protected:
int m_rows; ///< Number of rows.
int m_cols; ///< Number of columns.
T* p; ///< 1-D array of coefficients.
void alloc(int m, int n); ///< Allocate the array value.
void free(); ///< Free the array value.
int nElements() const; ///< Number of elements in the matrix.
matrix<T>& sub(matrix<T>& s, int i, int j) const;
}; // class matrix
/// Column vector class (template)
template <typename T>
class vector : public matrix<T>
{
public:
explicit vector(int m);
vector(T x);
vector(T x, T y);
vector(T x, T y, T z);
vector(const vector<T>& v);
virtual ~vector() {}
using matrix<T>::operator=;
vector<T>& operator=(const vector<T>& v);
// void operator=(T a);
vector<T> operator*(T a) const;
vector<T> operator/(T a) const;
/// Product of a vector by a scalar.
friend vector<T> operator*(T a, const vector<T>& v)
{ return v * a; }
vector<T> operator+(const vector<T>& v) const;
vector<T> operator-(const vector<T>& v) const;
vector<T> operator-() const; ///< Vector opposite.
matrix<T> operator*(const matrix<T>& m) const;
matrix<T> diag() const;
T qnorm() const;
vector<T> copy(int i0, int i1) const;
void paste(int i0, const vector<T>& v);
};
} // namespace libNumerics
/// Output matrix coefficients.
template <typename T>
inline std::ostream& operator<<(std::ostream& out,
const libNumerics::matrix<T>& m)
{
for(int i = 0; i < m.nrow(); ++i) {
out << ((i==0)? "[": ";");
for (int j = 0; j < m.ncol(); ++j)
out << " " << m(i,j);
}
out << " ]";
return out;
}
/// Input matrix. Need to know the dimensions in advance...
template <class T>
inline std::istream& operator>>(std::istream& in,
libNumerics::matrix<T>& m)
{
char c;
for(int i=0; i < m.nrow(); ++i) {
in >> c;
for(int j=0; j < m.ncol(); ++j)
in >> m(i,j);
}
in >> c;
return in;
}
template <typename T>
T dot(const libNumerics::vector<T>& u, const libNumerics::vector<T>& v);
template <typename T>
libNumerics::vector<T> cross(const libNumerics::vector<T>& u,
const libNumerics::vector<T>& v);
// Need to see definitions for templates...
#include "matrix.cpp"
#include "vector.cpp"
#endif

View file

@ -0,0 +1,487 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#include "numerics.h"
#include <cmath>
#include <vector>
#include <limits>
#include <algorithm>
namespace libNumerics {
const flnum MinLM::DEFAULT_RELATIVE_TOL = 1E-3;
const flnum MinLM::DEFAULT_LAMBDA_INIT = 1E-3;
const flnum MinLM::DEFAULT_LAMBDA_FACT = 10.0;
const flnum MinLM::EPSILON_KERNEL = 1E-9;
inline flnum ABS(flnum x)
{ return (x >= 0)? x: -x; }
/// Resolution by LU decomposition with pivot.
bool solveLU(const matrix<flnum>& A, const vector<flnum>& B, vector<flnum>& X)
{
X = B;
return solveLU(A, X);
}
/// Replace X by A^{-1}X, by LU solver.
bool solveLU(matrix<flnum> A, vector<flnum>& X)
{
assert(A.nrow() == A.ncol());
int n = A.nrow();
vector<flnum> rowscale(n); // Implicit scaling of each row
std::vector<int> permut(n,0); // Permutation of rows
// Get the implicit scaling information of each row
for(int i=0; i< n; i++) {
flnum max = 0.0;
for(int j=0; j< n; j++) {
flnum tmp = ABS(A(i,j));
if (tmp> max)
max = tmp;
}
if(max == 0.0)
return false;
rowscale(i) = 1.0/max;
}
// Perform the decomposition
for(int k=0; k < n; k++) {
// Search for largest pivot element
flnum max = rowscale(k)*ABS(A(k,k));
int imax = k;
for(int i=k+1; i < n; i++) {
flnum tmp = rowscale(i)*ABS(A(i,k));
if(tmp > max) {
max = tmp;
imax = i;
}
}
if(max == 0.0)
return false;
// Interchange rows if needed
if(k != imax) {
A.swapRows(k, imax);
rowscale(imax) = rowscale(k); // Scale of row k no longer needed
}
permut[k] = imax; // permut(k) was not initialized before
flnum Akk = 1/A(k,k);
for(int i=k+1; i < n; i++) {
flnum tmp = A(i,k) *= Akk; // Divide by pivot
for (int j=k+1;j < n; j++) // Reduce the row
A(i,j) -= tmp*A(k,j);
}
}
// Forward substitution
for (int k=0; k < n; k++) {
flnum sum = X(permut[k]);
X(permut[k]) = X(k);
for(int j = 0; j < k; j++)
sum -= A(k,j)*X(j);
X(k) = sum;
}
// Backward substitution
for(int k=n-1; k >= 0; k--) {
flnum sum = X(k);
for(int j=k+1; j < n; j++)
sum -= A(k,j)*X(j);
X(k) = sum/A(k,k);
}
return true;
}
/// Decompose A into U diag(W) V^T with U(m,n) and V(n,n) having orthonormal
/// vectors.
SVD::SVD(const matrix<flnum>& A)
: m_U(A), m_V(A.ncol(),A.ncol()), m_W(A.ncol())
{
compute();
sort();
}
/// SVD computation. Initial matrix stored in m_U as input.
void SVD::compute()
{
const flnum EPSILON = std::numeric_limits<flnum>::epsilon();
const int SVD_MAX_ITS = 30;
int rows = m_U.nrow();
int cols = m_U.ncol();
flnum g, scale, anorm;
vector<flnum> RV1(cols);
// Householder reduction to bidiagonal form:
anorm = g = scale = 0.0;
for (int i=0; i< cols; i++) {
int l = i + 1;
RV1(i) = scale*g;
g = scale = 0.0;
if(i< rows) {
for (int k=i; k< rows; k++)
scale += ABS(m_U(k,i));
if (scale != 0.0) {
flnum invScale=1.0/scale, s=0.0;
for (int k=i; k< rows; k++) {
m_U(k,i) *= invScale;
s += m_U(k,i) * m_U(k,i);
}
flnum f = m_U(i,i);
g = - withSignOf(std::sqrt(s),f);
flnum h = 1.0 / (f*g - s);
m_U(i,i) = f - g;
for (int j=l; j< cols; j++) {
s = 0.0;
for (int k=i; k< rows; k++)
s += m_U(k,i) * m_U(k,j);
f = s * h;
for (int k=i; k< rows; k++)
m_U(k,j) += f * m_U(k,i);
}
for (int k=i; k< rows; k++)
m_U(k,i) *= scale;
}
}
m_W(i) = scale * g;
g = scale = 0.0;
if ( i< rows && i< cols-1 ) {
for (int k=l; k< cols; k++)
scale += ABS(m_U(i,k));
if (scale != 0.0) {
flnum invScale=1.0/scale, s=0.0;
for (int k=l; k< cols; k++) {
m_U(i,k) *= invScale;
s += m_U(i,k) * m_U(i,k);
}
flnum f = m_U(i,l);
g = - withSignOf(std::sqrt(s),f);
flnum h = 1.0 / (f*g - s);
m_U(i,l) = f - g;
for (int k=l; k< cols; k++)
RV1(k) = m_U(i,k) * h;
for (int j=l; j< rows; j++) {
s = 0.0;
for (int k=l; k< cols; k++)
s += m_U(j,k) * m_U(i,k);
for (int k=l; k< cols; k++)
m_U(j,k) += s * RV1(k);
}
for (int k=l; k< cols; k++)
m_U(i,k) *= scale;
}
}
anorm = std::max(anorm, ABS(m_W(i)) + ABS(RV1(i)) );
}
// Accumulation of right-hand transformations:
m_V(cols-1,cols-1) = 1.0;
for (int i= cols-2; i>=0; i--) {
m_V(i,i) = 1.0;
int l = i+1;
g = RV1(l);
if (g != 0.0) {
flnum invgUil = 1.0 / (m_U(i,l)*g);
for (int j=l; j< cols; j++)
m_V(j,i) = m_U(i,j) * invgUil;
for (int j=l; j< cols; j++){
flnum s = 0.0;
for (int k=l; k< cols; k++)
s += m_U(i,k) * m_V(k,j);
for (int k=l; k< cols; k++)
m_V(k,j) += s * m_V(k,i);
}
}
for (int j=l; j< cols; j++)
m_V(i,j) = m_V(j,i) = 0.0;
}
// Accumulation of left-hand transformations:
for (int i=std::min(rows,cols)-1; i>=0; i--) {
int l = i+1;
g = m_W(i);
for (int j=l; j< cols; j++)
m_U(i,j) = 0.0;
if (g != 0.0) {
g = 1.0 / g;
flnum invUii = 1.0 / m_U(i,i);
for (int j=l; j< cols; j++) {
flnum s = 0.0;
for (int k=l; k< rows; k++)
s += m_U(k,i) * m_U(k,j);
flnum f = (s * invUii) * g;
for (int k=i; k< rows; k++)
m_U(k,j) += f * m_U(k,i);
}
for (int j=i; j< rows; j++)
m_U(j,i) *= g;
} else
for (int j=i; j< rows; j++)
m_U(j,i) = 0.0;
m_U(i,i) = m_U(i,i) + 1.0;
}
// Diagonalization of the bidiagonal form:
for (int k=cols-1; k>=0; k--) { // Loop over singular values
for (int its=1; its<=SVD_MAX_ITS; its++) {
bool flag = false;
int l = k;
int nm = k-1;
while(l>0 && ABS(RV1(l)) > EPSILON*anorm) { // Test for splitting
if(ABS(m_W(nm)) <= EPSILON*anorm) {
flag = true;
break;
}
l--;
nm--;
}
if (flag) { // Cancellation of RV1(l), if l > 0
flnum c=0.0, s=1.0;
for (int i=l; i< k+1; i++) {
flnum f = s * RV1(i);
RV1(i) = c * RV1(i);
if (ABS(f)<=EPSILON*anorm)
break;
g = m_W(i);
flnum h = SVD::hypot(f,g);
m_W(i) = h;
h = 1.0 / h;
c = g * h;
s = - f * h;
for (int j=0; j< rows; j++)
rotate(m_U(j,nm),m_U(j,i), c,s);
}
}
flnum z = m_W(k);
if (l==k) { // Convergence of the singular value
if (z< 0.0) { // Singular value is made nonnegative
m_W(k) = -z;
for (int j=0; j< cols; j++)
m_V(j,k) = - m_V(j,k);
}
break;
}
// Exception if convergence to the singular value not reached:
if(its==SVD_MAX_ITS) throw SvdConvergenceError();
flnum x = m_W(l); // Get QR shift value from bottom 2x2 minor
nm = k-1;
flnum y = m_W(nm);
g = RV1(nm);
flnum h = RV1(k);
flnum f = ( (y-z)*(y+z) + (g-h)*(g+h) ) / ( 2.0*h*y );
g = SVD::hypot(f,1.0);
f = ( (x-z)*(x+z) + h*(y/(f+withSignOf(g,f)) - h) ) / x;
// Next QR transformation (through Givens reflections)
flnum c=1.0, s=1.0;
for (int j=l; j<=nm; j++) {
int i = j+1;
g = RV1(i);
y = m_W(i);
h = s * g;
g = c * g;
z = SVD::hypot(f,h);
RV1(j) = z;
z = 1.0 / z;
c = f * z;
s = h * z;
f = x*c + g*s;
g = g*c - x*s;
h = y * s;
y *= c;
for(int jj=0; jj < cols; jj++)
rotate(m_V(jj,j),m_V(jj,i), c,s);
z = SVD::hypot(f,h);
m_W(j) = z;
if (z!=0.0) { // Rotation can be arbitrary if z = 0.0
z = 1.0 / z;
c = f * z;
s = h * z;
}
f = c*g + s*y;
x = c*y - s*g;
for(int jj=0; jj < rows; jj++)
rotate(m_U(jj,j),m_U(jj,i), c,s);
}
RV1(l) = 0.0;
RV1(k) = f;
m_W(k) = x;
}
}
}
/// Recompose from SVD. This should be the initial matrix.
matrix<flnum> SVD::compose() const
{
return m_U * m_W.diag() * m_V.t();
}
flnum SVD::withSignOf(flnum a, flnum b)
{ return b >= 0 ? (a >= 0 ? a : -a) : (a >= 0 ? -a : a); }
/// Replace hypot of math.h by robust numeric implementation.
flnum SVD::hypot(flnum a, flnum b)
{
a = ABS(a);
b = ABS(b);
if(a > b) {
b /= a;
return a*std::sqrt(1.0 + b*b);
} else if(b) {
a /= b;
return b*std::sqrt(1.0 + a*a);
}
return 0.0;
}
/// Utility function used while computing SVD.
void SVD::rotate(flnum& a, flnum& b, flnum c, flnum s)
{
flnum d = a;
a = +d*c +b*s;
b = -d*s +b*c;
}
class SVDElement {
public:
SVDElement(const vector<flnum>& W, int i)
: m_val(W(i)), m_i(i) {}
bool operator<(const SVDElement& e) const
{ return (m_val>e.m_val); }
flnum m_val;
int m_i;
};
/// Sort SVD by decreasing order of singular value.
void SVD::sort()
{
std::vector<SVDElement> vec;
for(int i=0; i < m_U.ncol(); i++)
vec.push_back( SVDElement(m_W, i) );
std::sort(vec.begin(), vec.end());
// Apply permutation
for(int i=m_U.ncol()-1; i >=0; i--)
if(vec[i].m_i != i) { // Find cycle of i
const vector<flnum> colU = m_U.col(i);
const vector<flnum> colV = m_V.col(i);
const flnum w = m_W(i);
int j = i;
while(vec[j].m_i != i) {
m_U.paste(0,j, m_U.col(vec[j].m_i));
m_V.paste(0,j, m_V.col(vec[j].m_i));
m_W(j) = m_W(vec[j].m_i);
std::swap(j,vec[j].m_i);
}
vec[j].m_i = j;
m_U.paste(0,j, colU);
m_V.paste(0,j, colV);
m_W(j) = w;
}
}
/// Constructor.
MinLM::MinLM()
: iterations(0), relativeTol(DEFAULT_RELATIVE_TOL),
lambdaInit(DEFAULT_LAMBDA_INIT), lambdaFact(DEFAULT_LAMBDA_FACT)
{}
/// In equation JtJ X = B, remove columns of J close to 0, so that JtJ can be
/// invertible
void MinLM::compress(matrix<flnum>& JtJ, vector<flnum>& B)
{
flnum max=0;
for(int i=0; i < JtJ.nrow(); i++)
if(JtJ(i,i) > max)
max = JtJ(i,i);
max *= EPSILON_KERNEL;
m_nullCols.clear();
for(int i=0; i < JtJ.nrow(); i++)
if(JtJ(i,i) <= max)
m_nullCols.push_back(i);
if( m_nullCols.empty() )
return;
int n=(int)m_nullCols.size();
matrix<flnum> JtJ2(JtJ.nrow()-m_nullCols.size(),
JtJ.ncol()-m_nullCols.size());
vector<flnum> B2(B.nrow()-(int)m_nullCols.size());
for(int i=0,i2=0; i < JtJ.nrow(); i++) {
if(i-i2 < n && m_nullCols[i-i2]==i)
continue;
for(int j=0,j2=0; j < JtJ.ncol(); j++) {
if(j-j2 < n && m_nullCols[j-j2]==j)
continue;
JtJ2(i2,j2) = JtJ(i,j);
j2++;
}
B2(i2) = B(i);
i2++;
}
swap(JtJ,JtJ2);
swap(B,B2);
}
/// Insert 0 in rows of B that were removed by \c compress()
void MinLM::uncompress(vector<flnum>& B)
{
if(m_nullCols.empty())
return;
int n=(int)m_nullCols.size();
vector<flnum> B2(B.nrow()+(int)m_nullCols.size());
for(int i=0,i2=0; i2 < B2.nrow(); i2++)
if(i2-i < n && m_nullCols[i2-i]==i2)
B2(i2)=0;
else
B2(i2) = B(i++);
swap(B,B2);
}
/// Perform minimization.
/// \a targetRMSE is the root mean square error aimed at.
/// Return the reached RMSE. Since the class does not know the dimension, the
/// real RMSE should be this value multiplied by sqrt(dim). For example, for 2-D
/// points this would be sqrt(2) times the returned value.
flnum MinLM::minimize(vector<flnum>& P, const vector<flnum>& yData,
flnum targetRMSE, int maxIters)
{
flnum errorMax = targetRMSE*targetRMSE*yData.nrow();
vector<flnum> yModel( yData.nrow() );
modelData(P, yModel);
vector<flnum> E( yData-yModel );
flnum error = E.qnorm();
matrix<flnum> J( yData.nrow(), P.nrow() );
modelJacobian(P, J);
matrix<flnum> Jt = J.t();
matrix<flnum> JtJ = Jt*J;
vector<flnum> B = Jt*E;
compress(JtJ, B);
flnum lambda = lambdaInit;
for(iterations=0; iterations < maxIters && error > errorMax; iterations++) {
matrix<flnum> H(JtJ);
for(int i = 0; i < H.nrow(); i++)
H(i,i) *= 1+lambda;
vector<flnum> dP( P.nrow() );
solveLU(H, B, dP);
uncompress(dP);
vector<flnum> tryP = P + dP;
modelData(tryP, yModel);
E = yData - yModel;
flnum tryError = E.qnorm();
if(ABS(tryError-error) <= relativeTol*error)
break;
if(tryError > error)
lambda *= lambdaFact;
else {
lambda /= lambdaFact;
error = tryError;
P = tryP;
modelJacobian(P, J);
Jt = J.t();
JtJ = Jt*J;
B = Jt*E;
compress(JtJ, B);
}
}
return sqrt(error/yData.nrow());
}
} // namespace libNumerics

View file

@ -0,0 +1,66 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#ifndef NUMERICS_H
#define NUMERICS_H
#include "matrix.h"
#include <vector>
namespace libNumerics {
class NumericsException {};
class SvdConvergenceError : public NumericsException {};
typedef double flnum;
/// Solve system AX = B.
bool solveLU(const matrix<flnum>& A, const vector<flnum>& B,
vector<flnum>& X);
bool solveLU(matrix<flnum> A, vector<flnum>& B);
/// Singular Value Decomposition
class SVD {
public:
SVD(const matrix<flnum>& A);
matrix<flnum>& U() { return m_U; }
vector<flnum>& W() { return m_W; }
matrix<flnum>& V() { return m_V; }
matrix<flnum> compose() const;
private:
matrix<flnum> m_U, m_V;
vector<flnum> m_W;
static flnum withSignOf(flnum a, flnum b);
static flnum hypot(flnum a, flnum b);
static void rotate(flnum& a, flnum& b, flnum c, flnum s);
void compute();
void sort();
};
/// Levenberg-Marquardt minimization.
class MinLM {
static const flnum DEFAULT_RELATIVE_TOL;
static const flnum DEFAULT_LAMBDA_INIT;
static const flnum DEFAULT_LAMBDA_FACT;
static const flnum EPSILON_KERNEL;
public:
MinLM();
flnum minimize(vector<flnum>& P, const vector<flnum>& ydata,
flnum targetRMSE=0.1, int maxIters=300);
virtual void modelData(const vector<flnum>& P,
vector<flnum>& ymodel) const = 0;
virtual void modelJacobian(const vector<flnum>& P,
matrix<flnum>& J) const = 0;
int iterations;
flnum relativeTol;
flnum lambdaInit;
flnum lambdaFact;
private:
std::vector<int> m_nullCols;
void compress(matrix<flnum>& JtJ, vector<flnum>& B);
void uncompress(vector<flnum>& B);
};
} // namespace libNumerics
#endif

Binary file not shown.

View file

@ -0,0 +1,55 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#ifdef RODRIGUES_H
namespace libNumerics {
template <class T>
matrix<T> skew(const vector<T>& v)
{
assert(v.nrow() == 3);
matrix<T> M(3,3);
M(0,0) = M(1,1) = M(2,2) = 0;
M(1,2) = -(M(2,1)=v(0));
M(2,0) = -(M(0,2)=v(1));
M(0,1) = -(M(1,0)=v(2));
return M;
}
template <class T>
matrix<T> rotation(vector<T> w)
{
assert(w.nrow() == 3);
T n = sqrt(w.qnorm());
T c = cos(n);
matrix<T> R = c*matrix<T>::eye(3);
if(n) {
w /= n;
R += skew(sin(n)*w);
R += (1-c)*w*w.t();
}
return R;
}
template <class T>
vector<T> rotationAxis(const matrix<T>& R)
{
assert(R.nrow() == 3 && R.ncol() == 3);
vector<T> w(3);
T n = acos(0.5*(R.tr()-1));
if(n == 0)
w = 0;
else {
w(0) = R(2,1)-R(1,2);
w(1) = R(0,2)-R(2,0);
w(2) = R(1,0)-R(0,1);
w *= n/(2*sin(n));
}
return w;
}
} // libNumerics
#endif // RODRIGUES_H

View file

@ -0,0 +1,24 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#ifndef RODRIGUES_H
#define RODRIGUES_H
#include "matrix.h"
#include <math.h>
namespace libNumerics {
/// Skew-symmetric matrix of 3-vector v.
template <class T> matrix<T> skew(const vector<T>& v);
/// Rodrigues's rotation: exp(w_x).
template <class T> matrix<T> rotation(vector<T> w);
/// Inverse Rodrigues's formula: w s.t. R=exp(w_x).
template <class T> vector<T> rotationAxis(const matrix<T>& R);
} // libNumerics
#include "rodrigues.cpp"
#endif

View file

@ -0,0 +1,179 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#ifdef MATRIX_H // Do nothing if not included from matrix.h
namespace libNumerics {
/// Constructor
template <typename T>
vector<T>::vector(int m)
: matrix<T>(m, 1)
{}
/// 1-vector constructor.
template <typename T>
vector<T>::vector(T x)
: matrix<T>(1,1)
{
this->p[0] = x;
}
/// 2-vector constructor.
template <typename T>
vector<T>::vector(T x, T y)
: matrix<T>(2,1)
{
this->p[0] = x;
this->p[1] = y;
}
/// 3-vector constructor.
template <typename T>
vector<T>::vector(T x, T y, T z)
: matrix<T>(3,1)
{
this->p[0] = x;
this->p[1] = y;
this->p[2] = z;
}
/// Copy constructor
template <typename T>
vector<T>::vector(const vector<T>& v)
: matrix<T>(v)
{}
/// Assignment operator
template <typename T>
vector<T>& vector<T>::operator=(const vector<T>& v)
{
matrix<T>::operator=(v);
return *this;
}
/// Multiply a vector by scalar.
/// \param a a scalar.
template <typename T>
vector<T> vector<T>::operator*(T a) const
{
vector<T> v(this->m_rows);
for(int i = this->m_rows-1; i >= 0; i--)
v.p[i] = a*this->p[i];
return v;
}
/// Divide a vector by scalar.
/// \param a a scalar.
template <typename T>
inline vector<T> vector<T>::operator/(T a) const
{
return operator*( (T)1/a );
}
/// Addition of vectors.
template <typename T>
vector<T> vector<T>::operator+(const vector<T>& v) const
{
assert(this->m_rows == v.m_rows);
vector<T> sum(this->m_rows);
for(int i = this->m_rows-1; i >= 0; i--)
sum.p[i] = this->p[i] + v.p[i];
return sum;
}
/// Subtraction of vectors.
template <typename T>
vector<T> vector<T>::operator-(const vector<T>& v) const
{
assert(this->m_rows == v.m_rows);
vector<T> sub(this->m_rows);
for(int i = this->m_rows-1; i >= 0; i--)
sub.p[i] = this->p[i] - v.p[i];
return sub;
}
/// Opposite of vector.
template <typename T>
vector<T> vector<T>::operator-() const
{
vector<T> v(this->m_rows);
for(int i = this->m_rows-1; i >= 0; i--)
v.p[i] = -this->p[i];
return v;
}
/// Vector times matrix.
template <typename T>
matrix<T> vector<T>::operator*(const matrix<T>& m) const
{
return matrix<T>::operator*(m);
}
/// Diagonal matrix defined by its diagonal vector.
template <typename T>
matrix<T> vector<T>::diag() const
{
matrix<T> d(this->m_rows, this->m_rows);
d = (T)0;
for(int i = this->m_rows-1; i >= 0; i--)
d(i,i) = this->p[i];
return d;
}
/// Square L^2 norm of vector.
template <typename T>
T vector<T>::qnorm() const
{
T q = (T)0;
for(int i = this->m_rows-1; i >= 0; i--)
q += this->p[i]*this->p[i];
return q;
}
/// Subvector from \a i0 to \a i1.
template <typename T>
vector<T> vector<T>::copy(int i0, int i1) const
{
assert(0 <= i0 && i0 <= i1 && i1 <= this->m_rows);
vector<T> v(i1-i0+1);
for(int i=i0; i <= i1; i++)
v.p[i-i0] = this->p[i];
return v;
}
/// Paste vector \a v from row i0.
template <typename T>
void vector<T>::paste(int i0, const vector<T>& v)
{
matrix<T>::paste(i0, 0, v);
}
} // namespace libNumerics
/// Scalar product.
template <typename T>
T dot(const libNumerics::vector<T>& u, const libNumerics::vector<T>& v)
{
assert(u.nrow() == v.nrow());
T d = (T)0;
for(int i = u.nrow()-1; i >= 0; i--)
d += u(i)*v(i);
return d;
}
/// Cross product.
template <typename T>
libNumerics::vector<T> cross(const libNumerics::vector<T>& u,
const libNumerics::vector<T>& v)
{
assert(u.nrow() == 3 && v.nrow() == 3);
libNumerics::vector<T> w(3);
w(0) = u(1)*v(2) - u(2)*v(1);
w(1) = u(2)*v(0) - u(0)*v(2);
w(2) = u(0)*v(1) - u(1)*v(0);
return w;
}
#endif // MATRIX_H

945
asift_match/src/library.cpp Executable file
View file

@ -0,0 +1,945 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#include "library.h"
void wxwarning(const char * message, const char *function,const char *file)
{
printf("warning :: %s :: %s :: %s\n", file, function, message);
}
void wxerror(const char * message, const char *function, const char *file)
{
printf("error :: %s :: %s :: %s\n", file, function, message);
exit(-1);
}
double fsqr(double a) { return a*a; }
void fill_exp_lut(float *lut, int size)
{
for(int i=0; i< size;i++) lut[i]=expf( - (float) i / LUTPRECISION);
}
/* Looks for f(dif) in the lut */
float slut(float dif,float *lut)
{
if (dif >= (float) LUTMAX) return 0.0;
int x= (int) floor(dif*LUTPRECISION);
float y1=lut[x];
float y2=lut[x+1];
return y1 + (y2-y1)*(dif*LUTPRECISION - (float) x);
}
float max(float *u,int *pos, int size)
{
float max=u[0];
if (pos) *pos=0;
for(int i=1; i<size; i++) if(u[i]>max){ max=u[i]; if (pos) *pos=i; }
return max;
}
float min(float *u,int *pos,int size)
{
float min=u[0];
if (pos) *pos=0;
for(int i=1;i<size;i++) if(u[i]<min){ min=u[i]; if (pos) *pos=i; }
return min;
}
void max_u_v(float *u,float *v,int size) { for(int i=0;i<size;i++) u[i]=MAX(u[i],v[i]);}
void max_u_k(float *u, float k, int size) { for(int i=0;i<size;i++) u[i]=MAX(u[i],k);}
void min_u_v(float *u, float *v,int size) { for(int i=0;i<size;i++) u[i]=MIN(u[i],v[i]);}
void min_u_k(float *u,float k,int size) { int i=0; for(i=0;i<size;i++) u[i]=MIN(u[i],k);}
void abs(float *u,float *v,int size){ for(int i=0;i<size ;i++) v[i] = fabsf(u[i]); }
void copy(float *u,float *v,int size) { for(int i=0; i<size ;i++) v[i]=u[i]; }
void clear(float *u,float value,int size) { for(int i=0; i<size; i++) u[i]=value; }
void combine(float *u,float a,float *v,float b, float *w, int size) { for(int i=0;i<size ;i++) w[i]= a*u[i] + b*v[i]; }
void multiple(float *u,float multiplier,int size) { for(int i=0;i<size;i++) u[i]=multiplier*u[i]; }
float scalar_product(float *u, float *v, int n)
{
float aux = 0.0f;
for(int i=0; i < n; i++)
aux += u[i] * v[i];
return aux;
}
float var(float *u,int size)
{
float *ptru=&u[0];
float mean=0.0;
float mean2 = 0.0;
for(int i=0;i<size;i++,ptru++) { mean += *ptru; mean2 += *ptru * (*ptru);}
mean/=(float) size; mean2/=(float) size;
float var = mean2- mean*mean;
return var;
}
float mean(float *u,int size)
{
float *ptru=&u[0];
float mean=0.0;
for(int i=0; i<size; i++,ptru++) mean += *ptru;
mean/=(float) size;
return mean;
}
float median(float *u,int size)
{
float *vector = new float[size];
float *index = new float[size];
float *ptru=&u[0];
for(int i=0; i<size; i++,ptru++) { vector[i] = *ptru; index[i] = (float) i;}
quick_sort(vector,index,size);
float median;
if (size%2==1) median = vector[size/2];
else median = (vector[size/2] + vector[(size/2) - 1])/2;
delete[] vector; delete[] index;
return median;
}
int normalize(float *u,int size)
{
float some = 0.0;
for(int i=0;i<size;i++) some+=u[i];
if (some != 0.0) { for(int i=0;i<size;i++) u[i]/=some; return 1;}
else return 0;
}
float nearest(float *u,float value,int *pos,int size)
{
float mindif = fabsf(value - u[0]);
float minvalue = u[0];
if (pos) *pos = 0;
for(int i=0;i<size;i++){
float dif = fabsf(value - u[i]);
if (dif < mindif) { mindif=dif; minvalue=u[i]; if (pos!=NULL) *pos=i;}
}
return minvalue;
}
void binarize(float *u, float *v,float value, int inverse, int size)
{
for(int i=0;i<size;i++){
if (u[i] >= value && !inverse) v[i]= 255.0;
else if (u[i] <= value && inverse) v[i]= 255.0;
else v[i]= 0.0;
}
}
float * gauss(int sflag,float std,int *size)
{
float *u,prec = 4.0,shift;
double v;
// int n,i,flag;
int n,i;
int flag = 1; //Guoshen Yu
if (sflag) n=*size;
else
n = 1+2*(int)ceil((double)std*sqrt(prec*2.*log(10.)));
u =new float[n];
if (n==1)
u[0]=1.0;
else{
shift = 0.5*(float)(n-1);
for (i=(n+1)/2;i--;) {
v = ((double)i - (double) shift)/(double)std;
u[i] = u[n-1-i] = (float) exp(-0.5*v*v);
}
}
// if (flag = normalize(u,n)) {
if (flag == normalize(u,n))
{
*size=n;
return u;
}
else
{
printf("ERROR: _gauss: _normalize: normalization equals zero.\n");
delete[] u; /*memcheck*/
return 0; // Guoshen Yu
}
}
/* Quicksort, values in arr are set in increasing order and brr elements are switched at the same time*/
void FSWAP(float *x,float *y)
{
float aux;
aux=*x;
*x=*y;
*y=aux;
}
void quick_sort(float *arr,float *brr,int n)
{
int M=7,NSTACK=50;
int i,ir,j,k,jstack=-1,l=0;
float a,b;
int istack[50];
ir=n-1;
for(;;){
if(ir-l<M){
for(j=l+1;j<=ir;j++){
a=arr[j];
b=brr[j];
for(i=j-1;i>=l;i--){
if (arr[i]<=a) break;
arr[i+1]=arr[i];
brr[i+1]=brr[i];
}
arr[i+1]=a;
brr[i+1]=b;
}
if (jstack<0) break;
ir=istack[jstack--];
l=istack[jstack--];
} else {
k=(l+ir) >> 1;
FSWAP(&arr[k],&arr[l+1]);
FSWAP(&brr[k],&brr[l+1]);
if (arr[l]>arr[ir]){
FSWAP(&arr[l],&arr[ir]);
FSWAP(&brr[l],&brr[ir]);
}
if (arr[l+1]>arr[ir]){
FSWAP(&arr[l+1],&arr[ir]);
FSWAP(&brr[l+1],&brr[ir]);
}
if (arr[l]>arr[l+1]){
FSWAP(&arr[l],&arr[l+1]);
FSWAP(&brr[l],&brr[l+1]);
}
i=l+1;
j=ir;
a=arr[l+1];
b=brr[l+1];
for(;;){
do i++; while (arr[i]<a);
do j--; while (arr[j]>a);
if (j<i) break;
FSWAP(&arr[i],&arr[j]);
FSWAP(&brr[i],&brr[j]);
}
arr[l+1]=arr[j];
arr[j]=a;
brr[l+1]=brr[j];
brr[j]=b;
jstack+=2;
if (jstack>=NSTACK) { printf("Stack too small\n"); exit(-1);}
if (ir-i+1>=j-l){
istack[jstack]=ir;
istack[jstack-1]=i;
ir=j-1;
} else {
istack[jstack]=j-1;
istack[jstack-1]=l;
l=i;
}
}
}
}
/// histogram of values. 'n' (number of bins) or 's' (step) must be selected in flag while the other value is filled
float * histo(float* input, float *iminim, float *imaxim, int *n, float *s, int size, char flag)
{
if (flag != 's' && flag != 'n') { printf("Warning (histo): Please select s or n as flag\n"); return NULL; }
float minim;
if (iminim) minim = *iminim;
else minim = min(input, NULL, size);
float maxim;
if (imaxim) maxim = *imaxim;
else maxim = max(input, NULL, size);
int num;
float step;
if (flag == 'n')
{
num = *n;
step = (maxim-minim)/ (float)num;
*s = step;
} else
{
step = *s;
num = (int)(0.5+(maxim-minim)/step);
*n = num;
}
float *histo = new float[num];
clear(histo,0.0,num);
for(int i=0; i < size; i++)
{
int cell = (int) floorf((input[i]-minim) / step);
if (cell < 0) cell = 0;
if (cell >= num) cell = num - 1;
histo[cell]++;
}
return histo;
}
///////////////////////////////////////////////////////////////////////////////////////////////////// Used and checked image functions
void compute_gradient_orientation(float* igray,float *grad, float *ori, int width, int height)
{
float xgrad, ygrad;
int rows, cols, r, c;
rows = height;
cols = width;
for (r = 0; r < rows; r++)
for (c = 0; c < cols; c++) {
if (c == 0)
xgrad = 2.0 * (igray[r*cols+c+1] - igray[r*cols+c]);
else if (c == cols-1)
xgrad = 2.0 * (igray[r*cols+c] - igray[r*cols+c-1]);
else
xgrad = igray[r*cols+c+1] - igray[r*cols+c-1];
if (r == 0)
ygrad = 2.0 * (igray[r*cols+c] - igray[(r+1)*cols+c]);
else if (r == rows-1)
ygrad = 2.0 * (igray[(r-1)*cols+c] - igray[r*cols+c]);
else
ygrad = igray[(r-1)*cols+c] - igray[(r+1)*cols+c];
if (grad) grad[r*cols+c] = (float)sqrt((double)(xgrad * xgrad + ygrad * ygrad));
if (ori) ori[r*cols+c] = (float)atan2 (-(double)ygrad,(double)xgrad);
}
}
void sample(float *igray,float *ogray, float factor, int width, int height)
{
int swidth = (int)((float) width / factor);
int sheight = (int)((float) height / factor);
for(int j=0; j < sheight; j++)
for(int i=0; i < swidth; i++)
ogray[j*swidth + i] = igray[(int)((float) j * factor) * width + (int) ((float) i*factor)];
}
void sample_aglomeration(float *igray,float *ogray, float factor, int width, int height)
{
int swidth = (int)((float) width / factor);
int sheight = (int)((float) height / factor);
int ssize = swidth * sheight;
clear(ogray,0.0,swidth*sheight);
for(int j=0; j < height; j++)
for(int i=0; i < width; i++){
int index = (int)((float) j / factor) * swidth + (int) ((float) i / factor);
if (index < ssize) ogray[index] += igray[j*width+i];
}
factor *= factor;
for(int i = 0; i < swidth*sheight; i++)
ogray[i] /= factor;
}
/*
void extract(float *igray,float *ogray, int ax, int ay,int cwidth, int cheight,int width, int height)
{
for(int j=0; j < cheight; j++)
for(int i=0; i < cwidth; i++)
ogray[j*cwidth + i] = igray[(ay+j)*width + ax+i];
}
*/
void gray(float *red, float *green,float *blue, float *out, int width, int height)
{
for(int i=width*height-1; i>0; i--) out[i] = (red[i] + green[i] + blue[i]) /3.0;
}
/*
float l2_distance(float *u0,float *u1,int i0,int j0,int i1,int j1,int radius,int width,int height)
{
int wsize=(2*radius+1)*(2*radius+1);
float dist=0.0;
for (int s=-radius; s<= radius; s++){
int l = (j0+s)*width + (i0-radius);
float *ptr0 = &u0[l];
l = (j1+s)*width + (i1-radius);
float *ptr1 = &u1[l];
for(int r=-radius;r<=radius;r++,ptr0++,ptr1++){ float dif = (*ptr0 - *ptr1); dist += (dif*dif); }
}
dist/=(float) wsize;
return dist;
}
float l2_distance_non_normalized(float *u0,float *u1,int i0,int j0,int i1,int j1,int radius,int width,int height)
{
float dist=0.0;
for (int s=-radius; s<= radius; s++){
int l = (j0+s)*width + (i0-radius);
float *ptr0 = &u0[l];
l = (j1+s)*width + (i1-radius);
float *ptr1 = &u1[l];
for(int r=-radius;r<=radius;r++,ptr0++,ptr1++){ float dif = (*ptr0 - *ptr1); dist += (dif*dif); }
}
return dist;
}
float l2_distance_nsq(float *u0,float *u1,int i0,int j0,int i1,int j1,int xradius, int yradius,int width,int height)
{
int wsize=(2*xradius+1)*(2*yradius+1);
float dist=0.0;
for (int s=-yradius; s <= yradius; s++){
int l = (j0+s)*width + (i0-xradius);
float *ptr0 = &u0[l];
l = (j1+s)*width + (i1-xradius);
float *ptr1 = &u1[l];
for(int r=-xradius;r<=xradius;r++,ptr0++,ptr1++)
{
float dif = (*ptr0 - *ptr1); dist += (dif*dif);
}
}
dist/=(float) wsize;
return dist;
}
float weighted_l2_distance(float *u0,float *u1,int i0,int j0,int i1,int j1,int width,int height,float *kernel,int radius)
{
float *ptrk=&kernel[0];
float dist=0.0;
for (int s=-radius; s<= radius; s++){
int l = (j0+s)*width + (i0-radius);
float *ptr0 = &u0[l];
l = (j1+s)*width + (i1-radius);
float *ptr1 = &u1[l];
for(int r=-radius;r<=radius;r++,ptr0++,ptr1++,ptrk++){ float dif = (*ptr0 - *ptr1); dist += *ptrk*(dif*dif); }
}
return dist;
}
float weighted_l2_distance_nsq(float *u0,float *u1,int i0,int j0,int i1,int j1,int width,int height,float *kernel,int xradius, int yradius)
{
float *ptrk=&kernel[0];
float dist=0.0;
for (int s=-yradius; s<= yradius; s++){
int l = (j0+s)*width + (i0-xradius);
float *ptr0 = &u0[l];
l = (j1+s)*width + (i1-xradius);
float *ptr1 = &u1[l];
for(int r=-xradius;r<=xradius;r++,ptr0++,ptr1++,ptrk++){ float dif = (*ptr0 - *ptr1); dist += *ptrk*(dif*dif); }
}
return dist;
}
*/
/// RGV to YUV conversion
void rgb2yuv(float *r,float *g,float *b,float *y,float *u,float *v,int width,int height)
{
int size=height*width;
for(int i=0;i<size;i++){
y[i] = COEFF_YR * r[i] + COEFF_YG * g[i] + COEFF_YB * b[i];
u[i] = r[i] - y[i];
v[i] = b[i] - y[i];
}
}
void rgb2yuv(float *r,float *g,float *b,float *y,float *u,float *v,float yR, float yG, float yB, int width,int height)
{
int size=height*width;
for(int i=0;i<size;i++){
y[i] = yR * r[i] + yG * g[i] + yB * b[i];
u[i] = r[i] - y[i];
v[i] = b[i] - y[i];
}
}
/// YUV to RGB conversion
void yuv2rgb(float *r,float *g,float *b,float *y,float *u,float *v,int width,int height)
{
int size=height*width;
for(int i=0;i<size;i++){
g[i] = (y[i] - COEFF_YR * (u[i] + y[i]) - COEFF_YB * (v[i] + y[i])) / COEFF_YG;
r[i] = u[i] + y[i];
b[i] = v[i] + y[i];
}
}
void yuv2rgb(float *r,float *g,float *b,float *y,float *u,float *v,float yR, float yG, float yB, int width,int height)
{
int size=height*width;
for(int i=0;i<size;i++){
g[i] = (y[i] - yR * (u[i] + y[i]) - yB * (v[i] + y[i])) / yG;
r[i] = u[i] + y[i];
b[i] = v[i] + y[i];
}
}
void draw_line(float *igray, int a0, int b0, int a1, int b1, float value, int width, int height)
{
int bdx,bdy;
int sx,sy,dx,dy,x,y,z,l;
bdx = width;
bdy = height;
if (a0 < 0) a0=0;
else if (a0>=bdx) a0=bdx-1;
if (a1<0) a1=0;
else if (a1>=bdx) a1=bdx-1;
if (b0<0) b0=0;
else if (b0>=bdy) b0=bdy-1;
if (b1<0) b1=0;
else if (b1>=bdy) b1=bdy-1;
if (a0<a1) { sx = 1; dx = a1-a0; } else { sx = -1; dx = a0-a1; }
if (b0<b1) { sy = 1; dy = b1-b0; } else { sy = -1; dy = b0-b1; }
x=0; y=0;
if (dx>=dy)
{
z = (-dx) / 2;
while (abs(x) <= dx)
{
l = (y+b0)*bdx+x+a0;
igray[l] = value;
x+=sx;
z+=dy;
if (z>0) { y+=sy; z-=dx; }
}
}
else
{
z = (-dy) / 2;
while (abs(y) <= dy) {
l = (y+b0)*bdx+x+a0;
igray[l] = value;
y+=sy;
z+=dx;
if (z>0) { x+=sx; z-=dy; }
}
}
}
void draw_square(float *igray, int a0, int b0, int w0, int h0, float value, int width, int height)
{
draw_line(igray,a0,b0,a0+w0,b0,value,width,height);
draw_line(igray,a0,b0,a0,b0+h0,value,width,height);
draw_line(igray,a0+w0,b0,a0+w0,b0+h0,value,width,height);
draw_line(igray,a0,b0+h0,a0+w0,b0+h0,value,width,height);
}
///////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////
/*
*/
/*
*/
/*
void _sign(float *u,float *v, int size)
{
int i=0;
for(i=0;i<size;i++){
if (u[i]>0) v[i] = 1.0;
else if (u[i]<0) v[i]=-1.0;
else v[i]=0.0;
}
}
void _multiple(float *u,float multiplier,int size)
{
int i=0;
float *ptru;
ptru=&u[0];
for(i=0;i<size;i++,ptru++) *ptru=multiplier*(*ptru);
}
void _product(float *u,float *v,int size)
{
int i;
float *ptru,*ptrv;
ptru=&u[0];
ptrv=&v[0];
for(i=0;i<size;i++,ptru++,ptrv++) *ptru= *ptru*(*ptrv);
}
int _is_increasing(float *u,float tolerance, int size)
{
int i=1;
while (i < size && u[i] > (u[i-1] - tolerance))
{
i++;
}
if (i==size) return 1;
else return 0;
}
void _offset(float *u,float offset,int size)
{
int i=0;
float *ptru;
ptru=&u[0];
for(i=0;i<size;i++,ptru++) *ptru=*ptru + offset;
}
void _threshold(float *u, float *v,float valuem,float valueM, int size)
{
int i;
for(i=0;i<size;i++){
if (u[i] >= valueM) v[i]= valueM;
else if (u[i] <= valuem) v[i]= valuem;
else v[i] = u[i];
}
}
void _absdif(float *u, float *v,int size)
{
int i=0;
for(i=0;i<size;i++) u[i] = (float) fabsf( u[i] - v[i]);
}
float * _diag_gauss(int sflag,float std,int *size) //Create a 1d gauss kernel of standard deviation std (megawave2)
{
float *u,prec = 4.0,shift;
double v;
int n,i,flag;
if (sflag) n=*size;
else
n = 1+2*(int)ceil((double)std*sqrt(prec*2.*log(10.)));
u =(float *) malloc(n*sizeof(float));
if (n==1)
u[0]=1.0;
else{
shift = 0.5*(float)(n-1);
for (i=(n+1)/2;i--;) {
v = ((double)i - (double) shift)/(double)std;
u[i] = u[n-1-i] = (float) exp(-2.0*0.5*v*v); // 2.0 because distances are in the diagonal
}
}
if (flag = _normalize(u,n)) {
*size=n;
return u;
} else {
printf("ERROR: mdSigGaussKernel: mdSigNormalize: normalization equals zero.\n Try to reduce std.\n");
}
}
void _quant(float *u,float *v,float lambda,int size)
{
int i,n;
float a=lambda/2;
for(i=0;i<size;i++){
n = (int) floorf(u[i] / a);
if (n%2==0)
v[i] = (float) n * a;
else
v[i] = (float) (n+1) * a;
}
}
void _projectquant(float *u,float *v,float lambda,int size)
{
int i;
float a=lambda/2;
for(i=0;i<size;i++){
if (v[i] < u[i] - a) v[i]=u[i] - a;
else if (v[i] > u[i] + a) v[i]=u[i] + a;
}
}
*/

202
asift_match/src/library.h Executable file
View file

@ -0,0 +1,202 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#ifndef _LIBRARY_H_
#define _LIBRARY_H_
#include <stdio.h>
#include <stdlib.h>
#include <math.h>
#include <time.h>
// #include <unistd.h>
#include <float.h>
#define MAX(i,j) ( (i)<(j) ? (j):(i) )
#define MIN(i,j) ( (i)<(j) ? (i):(j) )
#define LUTMAX 30
#define LUTPRECISION 1000.0
#define TINY 1.0e-10
//#define MAXFLOAT 10000000.0
#define IRAC8 0.35355339 /* 1/sqrt(8) */
#define IRAC2P2 0.29289322 /* 1/(sqrt(2)+2) */
#define IRAC2 0.70710678 /* 1/sqrt(2) */
#define RAC8P4 6.8284271 /* sqrt(8)+4 */
#define RADIANS_TO_DEGREES (180.0/M_PI)
#define PI 3.14159
#define COEFF_YR 0.299
#define COEFF_YG 0.587
#define COEFF_YB 0.114
///////////////////////////////////////////////////////////////// Errors
void wxwarning(const char * message,const char *function, const char *file);
void wxerror(const char * message, const char *function, const char *file);
///////////////////////////////////////////////////////////////////////////////////////////////////// Used and checked mathematical functions
double fsqr(double a);
void fill_exp_lut(float *lut,int size); /* Fills exp(x) for x great or equal than zero*/
float slut(float dif,float *lut); /* We look for f(dif) in the lut*/
///////////////////////////////////////////////////////////////////////////////////////////////////// Used and checked mxsignal functions
float max(float *u,int *pos, int size); /// Max(u), pos contains the index of the maximum
float min(float *u,int *pos, int size); /// Min(u), pos contains the index of the minimum
void max_u_v(float *u,float *v,int size);
void max_u_k(float *u,float k,int size);
void min_u_v(float *u,float *v,int size);
void min_u_k(float *u,float k,int size);
void abs(float *u,float *v,int size); /// v = abs(u)
void copy(float *u,float *v,int size); /// v = u
void clear(float *u, float value ,int size); /// u = k
void combine(float *u,float a,float *v,float b, float *w, int size); /// w = a*u + b*v
void multiple(float *u,float multiplier,int size); /// u = K * u
float scalar_product(float *u, float *v, int n);
// float lpdist(float *u,float *v,float *mask,int pow,int size);
// float lpnorm(float *u,int fpow,int size);
float mean(float *u,int size);
float var(float *u,int size);
float median(float *u,int size);
float nearest(float *u,float value,int *pos,int size); /// Returns the nearest value in the vector u and its position if selected
void binarize(float *u, float *v,float value, int inverse, int size); /// v = 255 if u > value 0 else
int normalize(float *u,int size); /// u = u / sum_i u(i). Returns 0 if mxsignal sum equals zero
float * gauss(int sflag,float std,int *size); /// Create a 1d gauss kernel of standard deviation std
// void addnoise(float *u,float *v,float std,long int randinit, int size);
// void addnoise_var_afine(float *u,float *v,float a,float b,long int randinit, int size);
void quick_sort(float *arr,float *brr,int n); /// Quicksort
/// histogram of values. 'n' (number of bins) or 's' (step) must be selected in flag while the other value is filled
float * histo ( float* input, float *iminim, float *imaxim, int *n, float *s, int size, char flag );
///////////////////////////////////////////////////////////////////////////////////////////////////// Used and checked image functions
void compute_gradient_orientation(float* igray,float *grad, float *ori, int width, int height);
// void extract ( float *igray,float *ogray, int ax, int ay,int cwidth, int cweight,int width, int height );
void sample ( float *igray,float *ogray, float factor ,int width, int height);
void sample_aglomeration(float *igray,float *ogray, float factor, int width, int height);
void gray ( float *red, float *green,float *blue, float *out, int width, int height );
/*
float l2_distance ( float * u0,float *u1,int i0,int j0,int i1,int j1,int radius,int width,int height);
float l2_distance_non_normalized(float *u0,float *u1,int i0,int j0,int i1,int j1,int radius,int width,int height);
float weighted_l2_distance ( float *u0,float *u1,int i0,int j0,int i1,int j1,int width,int height,float * kernel,int radius );
float l2_distance_nsq(float *u0,float *u1,int i0,int j0,int i1,int j1,int xradius, int yradius,int width,int height);
float weighted_l2_distance_nsq(float *u0,float *u1,int i0,int j0,int i1,int j1,int width,int height,float *kernel,int xradius, int yradius);
*/
void rgb2yuv ( float *r,float *g,float *b,float *y,float *u,float *v,int width,int height );
void yuv2rgb ( float *r,float *g,float *b,float *y,float *u,float *v,int width,int height );
void rgb2yuv(float *r,float *g,float *b,float *y,float *u,float *v,float yR, float yG, float yB, int width,int height);
void yuv2rgb(float *r,float *g,float *b,float *y,float *u,float *v,float yR, float yG, float yB, int width,int height);
void draw_line(float *igray, int a0, int b0, int a1, int b1, float value, int width, int height);
// void draw_circle(float *igray, int pi,int pj,float radius, float value, int width, int height);
void draw_square(float *igray, int a0, int b0, int w0, int h0, float value, int width, int height);
#endif // _LIBRARY_H_
/////////////////////////////////////// Not often used and not checked
//
//
/*
*/
//void md_fsig_absdif(float *u,float *v,int size); /// v = abs(v-u)
//void md_fsig_sign(float *u,float *v, int size); //// ¿¿¿¿¿ ?????
//int md_fsig_is_increasing(float *u,float tolerance, int size); ///// ¿¿¿¿¿ ?????
//void md_fsig_multiple(float *u,float multiplier,int size); // u = K * u
//void md_fsig_product(float *u,float *v,int size); // u = u * v
//void md_fsig_offset(float *u,float offset, int size); // u = u - K
//
//
//void md_fsig_threshold(float *u, float *v,float valuem,float valueM, int size); // threshold into (m,M)
//--- Conversion ---
//void md_fsig_float2char(float min, float max, float *u, float *v, int size); // Linear Conversion between (min,max) and (0,255)
//void md_fsig_addnoise(float *u,float *v,float std,long int randinit, int size); // Add gaussian noise of standard deviation sigma
// v quantified mxmximage u with interval length lambda
// if u \in ( (n - 1/2) l, (n + 1/2 ) l ) - > v = n l
// n= 0 -> (-1/2 * l, 1/2 * l) //
//void md_fsig_quant(float *u, float *v, float lambda, int size);
// v is projected to the space of quantizations of length lambda that gives u
//void md_fsig_projectquant(float *u,float *v,float lambda, int size);

185
asift_match/src/numerics1.cpp Executable file
View file

@ -0,0 +1,185 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#include "numerics1.h"
float **allocate_float_matrix(int nrows, int ncols)
{
float ** matrix;
matrix = new float*[nrows];
for(int i=0; i < nrows; i++) matrix[i] = new float[ncols];
return matrix;
}
void desallocate_float_matrix(float **matrix, int nrows, int ncols)
{
if (matrix == NULL) return;
for(int i=0; i < nrows; i++) { delete[] matrix[i]; matrix[i] = 0;}
matrix = 0;
ncols = ncols; // to remove the warning unused parameter ¡®ncols¡¯
}
// **********************************************
// LU based algorithms
// **********************************************
// Solves Ax=b by using lu decomposition
int lusolve(float **a, float *x, float *b, int n)
{
float d;
int *indx = new int[n];
if (ludcmp(a,n,indx,&d))
{
for(int i=0; i < n; i++) x[i] = b[i];
lubksb(a,n,indx,x);
delete[] indx; /*memcheck*/
return 1;
} else
{
printf("lusolve::lu decomposition failed\n");
delete[] indx; /*memcheck*/
return 0;
}
delete[] indx; // Guoshen Yu
}
int ludcmp(float **a, int n, int *indx, float *d)
{
int i,imax=0,j,k,aux;
float big,dum,sum,temp;
float *vv;
vv=(float *) malloc(n*sizeof(float));
*d=1.0;
for(i=0;i<n;i++) indx[i]=i;
/**** Look for the largest value of every line and store 1/this value****/
for(i=0;i<n;i++){
big=0.0;
for(j=0;j<n;j++)
if ( (temp=fabs(a[i][j]))>big ) big=temp;
if (big==0.0) { return 0; printf("LU Decomposition failed\n");}
vv[i]=1.0/big;
}
for(j=0;j<n;j++){
for(i=0;i<j;i++){
sum=a[i][j];
for(k=0;k<i;k++) sum-= a[i][k]*a[k][j];
a[i][j]=sum;
}
big=0.0;
for(i=j;i<n;i++){
sum=a[i][j];
for(k=0;k<j;k++)
sum -=a[i][k]*a[k][j];
a[i][j]=sum;
if ( (dum=vv[i]*fabs(sum))>=big){
big=dum;
imax=i;
}
}
if (j != imax){
for(k=0;k<n;k++){
dum=a[imax][k];
a[imax][k]=a[j][k];
a[j][k]=dum;
}
*d=-(*d);
vv[imax]=vv[j];
aux=indx[j];
indx[j]=indx[imax];
indx[imax]=aux;
}
if (a[j][j]==0.0) a[j][j]=NRTINY;
if (j!=n-1 ){
dum=1.0 / a[j][j];
for(i=j+1;i<n;i++) a[i][j]*=dum;
}
}
free(vv);
return 1;
}
/* Solves the set of n linear equations Ax=b. Here a[0..n-1][0..n-1] as input, not as the matrix A but rather as its LU decomposition,*/
/* determined by the routine ludcmp. indx[0..n-1] is input as the permutation vector returned by ludcmp. b[0..n-1] is input as the */
/* right hand side vector and returns with the solution vector x. */
void lubksb(float **a, int n, int *indx, float *b)
{
int i,ii=0,j;
float sum,*aux;
aux= (float *) malloc(n*sizeof(float));
for(i=0;i<n;i++)
aux[i]=b[indx[i]];
for(i=0;i<n;i++){
sum=aux[i];
if (ii)
for(j=ii-1;j<i;j++) sum-=a[i][j]*aux[j];
else if (sum) ii=i+1;
aux[i]=sum;
}
for(i=n-1;i>=0;i--){
sum=aux[i];
for(j=i+1;j<n;j++) sum-=a[i][j]*aux[j];
aux[i]=sum/a[i][i];
b[i]=sum/a[i][i];
}
free(aux);
}

57
asift_match/src/numerics1.h Executable file
View file

@ -0,0 +1,57 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#ifndef _NUMERICS_H_
#define _NUMERICS_H_
#include <stdio.h>
#include <stdlib.h>
#include <math.h>
#include <fstream>
#include <iostream>
#include "library.h"
#define NRMAX(i,j) ( (i)<(j) ? (j):(i) )
#define NRMIN(i,j) ( (i)<(j) ? (i):(j) )
#define NRTINY 1.0e-10
// **********************************************
// float ** basic functions
// **********************************************
float ** allocate_float_matrix(int nrows, int ncols);
void desallocate_float_matrix(float **matrix, int nrows, int ncols);
// **********************************************
// LU based algorithms
// **********************************************
// Solves Ax=b by using lu decomposition
// a matrix a[1..n][1..n] is replaced by the LU decompositions of a rowwise permutation of itself
// b[1..n] and x[1..n]
int lusolve(float **a, float *x, float *b, int n);
/*-- LU decomposition */
/* Given a matrix a[1..n][1..n] this routine replacess it by the LU decompositions of a rowwise permutation of itself. */
/* a and n are input, a is output, arranged as in equation (2.3.14) above; indx[1..n] in an output vector that records */
/* the row permutation effected by the partial pivoting; d is output as +-1 depending on whether the number of row */
/* interchanges was even or odd respectively. */
int ludcmp(float **a, int n, int *indx, float *d); /* LU decomposition */
/* Solves the set of n linear equations Ax=b. Here a[0..n-1][0..n-1] as input, not as the matrix A but rather as its LU decomposition,*/
/* determined by the routine ludcmp. indx[0..n-1] is input as the permutation vector returned by ludcmp. b[0..n-1] is input as the */
/* right hand side vector and returns with the solution vector x. */
void lubksb(float **a, int n, int *indx, float *b); /* LU linear solution */
#endif

599
asift_match/src/orsa.cpp Executable file
View file

@ -0,0 +1,599 @@
//
// C++ Implementation: stereomatch
//
// Description: eliminate the false matches with epipolar geometry constraint.
// See http://www.math-info.univ-paris5.fr/~moisan/epipolar/
//
// Copyright (c) 2007 Lionel Moisan <Lionel.Moisan@parisdescartes.fr>
// Changelog : 2011 Use Eigen SVD <Pierre Moulon>
//
// Copyright: See COPYING file that comes with this distribution
//
//
#include <assert.h>
#include <stdio.h>
#include <stdlib.h>
#include <math.h>
#include <time.h>
#include "orsa.h"
// #include <third_party/Eigen/Cholesky>
// #include <third_party/Eigen/Core>
// #include <third_party/Eigen/Eigenvalues>
// #include <third_party/Eigen/LU>
// #include <third_party/Eigen/QR>
// #include <third_party/Eigen/SVD>
#include <Eigen/Cholesky>
#include <Eigen/Core>
#include <Eigen/Eigenvalues>
#include <Eigen/LU>
#include <Eigen/QR>
#include <Eigen/SVD>
#ifndef M_PI
#define M_PI 3.14159265358979323846
#endif
/*-------------------- GENERAL PURPOSE ROUTINES --------------------*/
/* routines for vectors and matrices */
float *vector(int nl, int nh)
{
float *v;
v=(float *)malloc((unsigned) (nh-nl+1)*sizeof(float));
if (!v) {
// mwerror(FATAL,1,"allocation failure in vector()");
fprintf(stderr, "allocation failure in vector()\n");
exit(EXIT_FAILURE); /* indicate failure.*/
}
return v-nl;
}
float **matrix(int nrl, int nrh, int ncl, int nch)
{
int i;
float **m;
m=(float **) malloc((unsigned) (nrh-nrl+1)*sizeof(float*));
if (!m) {
// mwerror(FATAL,1,"allocation failure 1 in matrix()");
fprintf(stderr, "allocation failure 1 in matrix()\n");
exit(EXIT_FAILURE); /* indicate failure.*/
}
m -= nrl;
for(i=nrl;i<=nrh;i++) {
m[i]=(float *) malloc((unsigned) (nch-ncl+1)*sizeof(float));
if (!m[i]) {
// mwerror(FATAL,1,"allocation failure 2 in matrix()");
fprintf(stderr, "allocation failure 2 in matrix()\n");
exit(EXIT_FAILURE); /* indicate failure.*/
}
m[i] -= ncl;
}
return m;
}
void free_vector(float *v, int nl, int nh)
{
free((char*) (v+nl));
nh = nh; // to remove the warning "unused parameter nh"
}
void free_matrix(float **m, int nrl, int nrh, int ncl, int nch)
{
int i;
for(i=nrh;i>=nrl;i--) free((char*) (m[i]+ncl));
free((char*) (m+nrl));
nch = nch; // to remove the warning "unused parameter nh"
}
/* Compute the real roots of a third order polynomial */
/* returns 1 or 3, the number of roots found */
int FindCubicRoots(float coeff[4], float x[3])
{
float a1 = coeff[2] / coeff[3];
float a2 = coeff[1] / coeff[3];
float a3 = coeff[0] / coeff[3];
double Q = (a1 * a1 - 3 * a2) / 9;
double R = (2 * a1 * a1 * a1 - 9 * a1 * a2 + 27 * a3) / 54;
double Qcubed = Q * Q * Q;
double d = Qcubed - R * R;
/* Three real roots */
if (d >= 0) {
double theta = acos(R / sqrt(Qcubed));
double sqrtQ = sqrt(Q);
x[0] = -2 * sqrtQ * cos( theta / 3) - a1 / 3;
x[1] = -2 * sqrtQ * cos((theta + 2 * M_PI) / 3) - a1 / 3;
x[2] = -2 * sqrtQ * cos((theta + 4 * M_PI) / 3) - a1 / 3;
return (3);
}
/* One real root */
else {
double e = pow(sqrt(-d) + fabs(R), 1. / 3.);
if (R > 0)
e = -e;
x[0] = (e + Q / e) - a1 / 3.;
return (1);
}
}
/* logarithm (base 10) of binomial coefficient */
float logcombi(int k, int n)
{
double r;
int i;
if (k>=n || k<=0) return(0.);
if (n-k<k) k=n-k;
r = 0.;
for (i=1;i<=k;i++)
r += log10((double)(n-i+1))-log10((double)i);
return((float)r);
}
/* tabulate logcombi(.,n) */
float *makelogcombi_n(int n)
{
float *l;
int k;
l = (float *)malloc((n+1)*sizeof(float));
for (k=0;k<=n;k++) l[k]=logcombi(k,n);
return(l);
}
/* tabulate logcombi(k,.) */
float *makelogcombi_k(int k, int nmax)
{
float *l;
int n;
l = (float *)malloc((nmax+1)*sizeof(float));
for (n=0;n<=nmax;n++) l[n]=logcombi(k,n);
return(l);
}
/* get a (sorted) random 7-uple of 0..n-1 */
void random_p7(int *k, int n)
{
int i,j,j0,r;
for (i=0;i<7;i++) {
r = (rand()>>3)%(n-i);
for (j=0;j<i && r>=k[j];j++) r++;
j0 = j;
for (j=i;j>j0;j--) k[j]=k[j-1];
k[j0]=r;
}
}
/*-------------------- END OF GENERAL PURPOSE ROUTINES --------------------*/
/* float comparison for qsort() */
//According to http://www.cplusplus.com/reference/clibrary/cstdlib/qsort/,
//we should have: void qsort ( void * base, size_t num, size_t size, int ( * comparator ) ( const void *, const void * ) ); that means, for "qsort", the "comparator" has two constant void* type input parameters
// static int compf(void *i, void *j)
int compf(const void *i, const void *j)
{
float a,b;
a = *((float *)i);
b = *((float *)j);
return(a<b?-1:(a>b?1:0));
}
/* find the increasing sequence of squared distances to epipolar lines */
/* e[n*2] = distances, e[n*2+1] = indexes (to cast into an int) */
//void matcherrorn(float **F, Flist p1, Flist p2, float *e)
void matcherrorn(float **F, const std::vector<float>& p1, const std::vector<float>& p2, float *e)
{
int i;
double x,y,a,b,c,d; // Guoshen Yu, double precision is needed. When the two images are identical, the error under float precision is 0 => log(error)=-inf.
int pt_size = (p1.size())/2;
for (i = 0; i < pt_size; i++) {
x = (double) p1[i*2];
y = (double) p1[i*2+1];
a = (double) F[1][1]*x+(double) F[1][2]*y+(double) F[1][3];
b = (double) F[2][1]*x+(double) F[2][2]*y+(double) F[2][3];
c = (double) F[3][1]*x+(double) F[3][2]*y+(double) F[3][3];
d = (a*(double) p2[i*2]+b*(double) p2[i*2+1]+c);
e[i*2] = (d*d)/(a*a+b*b);
e[i*2+1] = (float)i;
}
qsort(e, pt_size, 2*sizeof(float), compf);
}
/*---------- compute the epipolar geometry associated to 7 pairs ----------*/
/* */
/* INPUT: the points are (m1[k[i]*2],m1[k[i]*2+1]), m2... 0<i<7 */
/* */
/* OUTPUT: */
/* return the number of roots found, stored in z[] */
/* the epipolar matrices are F1[i][j]+z[k]*F2[i][j], 1<=i,j<=3, 0<=k<m */
// int epipolar(float *m1, float *m2, int *k, float *z, float **F1, float **F2)
int epipolar(std::vector<float>& m1, std::vector<float>& m2, int *k, float *z, float **F1, float **F2)
{
float a[4];
int i,j,i2,i3;
typedef Eigen::MatrixXf Mat;
Mat c(7,9);
/* build 9xn matrix from point matches */
for (i=0;i<7;i++) {
c(i,0) = m1[k[i]*2 ]*m2[k[i]*2 ];
c(i,1) = m1[k[i]*2+1]*m2[k[i]*2 ];
c(i,2) = m2[k[i]*2 ];
c(i,3) = m1[k[i]*2 ]*m2[k[i]*2+1];
c(i,4) = m1[k[i]*2+1]*m2[k[i]*2+1];
c(i,5) = m2[k[i]*2+1];
c(i,6) = m1[k[i]*2 ];
c(i,7) = m1[k[i]*2+1];
c(i,8) = 1.;
}
// SVD
Eigen::JacobiSVD<Mat> svd(c, Eigen::ComputeFullV);
// look for the two smallest eigenvalue of c'c
typedef Eigen::Matrix<float, 9, 1> Vec9;
Vec9 F1Vec = svd.matrixV().col(c.cols()-1);
Vec9 F2Vec = svd.matrixV().col(c.cols()-2);
/* build basis of solutions */
int cpt = 0;
for (i=1;i<=3;i++)
for (j=1;j<=3;j++)
{
F1[i][j] = F1Vec(cpt);
F2[i][j] = F2Vec(cpt);
cpt++;
}
/* build cubic polynomial P(x)=det(F1+xF2) */
a[0] = a[1] = a[2] = a[3] = 0.;
for (i=1;i<=3;i++) {
i2 = i%3+1;
i3 = i2%3+1;
a[0] += F1[i][1]*F1[i2][2]*F1[i3][3];
a[1] +=
F2[i][1]*F1[i2][2]*F1[i3][3]+
F1[i][1]*F2[i2][2]*F1[i3][3]+
F1[i][1]*F1[i2][2]*F2[i3][3];
a[2] +=
F1[i][1]*F2[i2][2]*F2[i3][3]+
F2[i][1]*F1[i2][2]*F2[i3][3]+
F2[i][1]*F2[i2][2]*F1[i3][3];
a[3] += F2[i][1]*F2[i2][2]*F2[i3][3];
}
for (i=1;i<=3;i++) {
i2 = (i+1)%3+1;
i3 = (i2+1)%3+1;
a[0] -= F1[i][1]*F1[i2][2]*F1[i3][3];
a[1] -=
F2[i][1]*F1[i2][2]*F1[i3][3]+
F1[i][1]*F2[i2][2]*F1[i3][3]+
F1[i][1]*F1[i2][2]*F2[i3][3];
a[2] -=
F1[i][1]*F2[i2][2]*F2[i3][3]+
F2[i][1]*F1[i2][2]*F2[i3][3]+
F2[i][1]*F2[i2][2]*F1[i3][3];
a[3] -= F2[i][1]*F2[i2][2]*F2[i3][3];
}
return(FindCubicRoots(a,z));
}
void divide_match(const std::vector<Match>& matches, std::vector<float>& p1, std::vector<float>& p2)
{
float x1, y1, x2, y2;
p1.clear();
p2.clear();
p1.reserve(2 * matches.size());
p2.reserve(2 * matches.size());
std::vector<Match>::const_iterator it=matches.begin();
for(; it != matches.end(); ++it) {
x1 = (*it).x1; y1 = (*it).y1;
x2 = (*it).x2; y2 = (*it).y2;
p1.push_back(x1); p1.push_back(y1);
p2.push_back(x2); p2.push_back(y2);
}
}
// float stereomatch(int img_x, int img_y, int size_pt, float* p1, float* p2, float** f, float* index, int* t, int* verb, int* n_flag, int* mode, int* stop)
// float stereomatch(const wxImage& u1, std::vector<float>& p1, std::vector<float>& p2, std::vector<SmallVector<float,3> >& f, std::vector<float>& index, int* t, int* verb, int* n_flag, int* mode, int* stop)
//int main(int argc, char** argv)
float orsa(int width, int height, std::vector<Match>& match, std::vector<float>& index, int t_value, int verb_value, int n_flag_value, int mode_value, int stop_value)
{
// int width = 0, height = 0;
// int t_value, verb_value, n_flag_value, mode_value, stop_value;
int *t, *verb, *n_flag, *mode, *stop;
t = (int*)malloc(sizeof(int)); // maximum number of ransac trials
verb = (int*)malloc(sizeof(int)); //verbose
n_flag = (int*)malloc(sizeof(int)); // in order NOT to reinitialize the random seed
mode = (int*)malloc(sizeof(int)); // mode: 0=deterministic 1=ransac 2=optimized ransac (ORSA) 3=automatic
stop = (int*)malloc(sizeof(int)); // stop as soon as the first meaningful correspondence is found
if(width <=0 || height <= 0) {
std::cerr << "Wrong dimensions of image" << std::endl;
return 1;
}
std::vector<float> p1(2*match.size()), p2(2*match.size()), p1_backup(2*match.size()), p2_backup(2*match.size());
divide_match(match, p1, p2);
p1_backup = p1;
p2_backup = p2;
libNumerics::matrix<libNumerics::flnum> f(3, 3);
f = 0;
index = std::vector<float>(match.size());
// Guoshen Yu, 2010.09.23
// index.clear();
if(t_value <= 0) {
std::cerr << "t should be greater than 0" << std::endl;
return 1;
}
*t = t_value;
if(verb_value == 0) {
free(verb);
verb = NULL;
}
else
*verb = verb_value;
if(verb_value != 1 && verb_value != 0) {
std::cerr << "verb can only be 0 or 1" << std::endl;
return 1;
}
if(n_flag_value == 0) {
free(n_flag);
n_flag = NULL;
}
else
*n_flag = n_flag_value;
if(n_flag_value != 1 && n_flag_value != 0) {
std::cerr << "n_flag can only be 0 or 1" << std::endl;
return 1;
}
if(mode_value != 0 && mode_value != 1 && mode_value != 2 && mode_value != 3) {
std::cerr << "mode can only be 0 or 1 or 2 or 3" << std::endl;
return 1;
}
*mode = mode_value;
if(stop_value == 0) {
free(stop);
stop = NULL;
}
else
*stop = stop_value;
if(stop_value != 1 && stop_value != 0) {
std::cerr << "stop can only be 0 or 1" << std::endl;
return 1;
}
int i,j,i0,k[8],idk[8],*id,m,n,l,minicur=0,miniall=0,delete_index,nid;
int niter,maxniter,better,cont,optimization;
float **F1,**F2,**F,nx,ny,z[3],minepscur,minepsall,nfa;
float norm,minlogalphacur,minlogalphaall,logalpha,logalpha0;
float *e,*logcn,*logc7,loge0;
/* initialize random seed if necessary */
// if (!n_flag) srand48( (long int) time (NULL) + (long int) getpid() );
// if (!n_flag) srand( (long int) time (NULL) + (long int) getpid() );
// Guoshen Yu, 2010.09.21: remove getpid which does not exist under Windows
if (!n_flag) srand( (long int) time (NULL) );
/* check sizes */
if (p1.size() != p2.size() || p1.size() < 14) {
fprintf(stderr, "Inconsistent sizes.\n");
exit(EXIT_FAILURE); /* indicate failure.*/
}
n = p1.size()/2;
/* tabulate logcombi */
loge0 = (float)log10(3.*(double)(n-7));
logcn = makelogcombi_n(n);
logc7 = makelogcombi_k(7,n);
/* choose mode */
if (*mode==3) {
if (logcn[7]<=(float)log10((double)(*t)))
*mode=0;
else *mode=2;
}
if (verb)
switch(*mode) {
case 0:
// i = (int)(0.5+pow(10.,logc7[n]));
// Guoshen Yu, 2010.09.22, Windows version
i = (int)(0.5+pow(10., (double)(logc7[n])));
printf("I will use deterministic mode (systematic search).\n");
printf("I have to test %d bases\n",i);
break;
case 1:
printf("I will use pure stochastic mode with no optimization.\n");
break;
case 2:
printf("I will use optimized stochastic mode (ORSA).\n");
}
/* normalize coordinates */
nx = (float)width;
ny = (float)height;
norm = 1./(float)sqrt((double)(nx*ny));
logalpha0 = (float)(log10(2.)+0.5*log10((double)((nx*nx+ny*ny)*norm*norm)));
for (i=0;i<n;i++) {
p1[i*2 ] = (p1[i*2 ]-0.5*nx)*norm;
p1[i*2+1] = (p1[i*2+1]-0.5*ny)*norm;
p2[i*2 ] = (p2[i*2 ]-0.5*nx)*norm;
p2[i*2+1] = (p2[i*2+1]-0.5*ny)*norm;
}
/* allocate and initialize memory */
F = matrix(1,3,1,3);
F1 = matrix(1,3,1,3);
F2 = matrix(1,3,1,3);
//delete_index = (index?0:1);
delete_index = 0;
e = (float *)malloc(2*n*sizeof(float));
id = (int *)malloc(n*sizeof(int));
for (i=0;i<n;i++) id[i]=i;
nid = n;
maxniter = (*mode==0?*t:*t-(*t)/10);
minlogalphaall = minepsall = 10000.;
niter = optimization = 0;
i0=0; k[0]=-1; k[7]=n;
/********** MAIN LOOP **********/
do {
niter++;
/* build next list of points */
if (*mode) random_p7(k,nid);
else {
k[i0]++;
for (i=i0+1;i<=6;i++) k[i]=k[i-1]+1;
}
for (i=0;i<7;i++) idk[i]=id[k[i]];
/* find epipolar transform */
m = epipolar(p1,p2,idk,z,F1,F2);
/* loop on roots */
for (;m--;) {
for (i=1;i<=3;i++)
for (j=1;j<=3;j++)
F[i][j] = F1[i][j]+z[m]*F2[i][j];
/* sort errors */
matcherrorn(F,p1,p2,e);
/* find most meaningful subset */
minepscur = minlogalphacur = 10000.;
for (i=7;i<n;i++) {
logalpha = logalpha0+0.5*(float)log10((double)e[i*2]);
nfa = loge0+logalpha*(float)(i-6)+logcn[i+1]+logc7[i+1];
if (nfa<minepscur) {
minepscur = nfa;
minicur = i;
minlogalphacur = logalpha;
}
}
if (minepscur<minepsall) {
/* store best result so far */
better = 1;
minepsall = minepscur;
minlogalphaall = minlogalphacur;
miniall = minicur;
// if (f)
for (l=1;l<=3;l++)
for (j=1;j<=3;j++)
f(l-1, j-1) = F[l][j];
// Guoshen Yu, 2010.09.22
// for (i=0;i<=minicur;i++)
for (i=0;i<minicur;i++)
{
index[i] = e[i*2+1];
}
} else better=0;
if (*mode==2 && ((better && minepsall<0.) ||
(niter==maxniter && !optimization))) {
if (!optimization) maxniter = niter + (*t)/10;
optimization = 1;
/* final optimization */
if (verb) {
printf(" nfa=%f size=%d (niter=%d)\n",minepsall,miniall+1,niter);
printf("optimization...\n");
}
nid = miniall+1;
// Guoshen Yu, 2010.09.22
// for (j=0;j<=miniall;j++)
for (j=0;j<miniall;j++)
id[j] = (int)(index[j]);
}
}
/* prepare next list of points */
if (*mode==0)
for(i0=6;i0>=0 && k[i0]==k[i0+1]-1;i0--){};
if (stop && minepsall<0.) cont=0;
else if (*mode==0) cont=(i0>=0?1:0);
else cont=(niter<maxniter?1:0);
} while (cont);
//erase "index", only get the index of the meaningful matchings
index.erase(index.begin()+miniall+1, index.end());
if (verb)
printf("best matching found: %d points log(alpha)=%f (%d iterations)\n",
miniall+1,minlogalphaall,niter);
/* free memory */
free(id);
free(e);
// if (delete_index) mw_delete_flist(index);
free_matrix(F2,1,3,1,3);
free_matrix(F1,1,3,1,3);
free_matrix(F,1,3,1,3);
free(logc7);
free(logcn);
if(t) free(t);
if(verb) free(verb);
if(n_flag) free(n_flag);
if(mode) free(mode);
if(stop) free(stop);
// return 0;
return(minepsall);
}

77
asift_match/src/orsa.h Executable file
View file

@ -0,0 +1,77 @@
//
// C++ Implementation: stereomatch
//
// Description: eliminate the false matches with epipolar geometry constraint.
// See http://www.math-info.univ-paris5.fr/~moisan/epipolar/
//
// Copyright (c) 2007 Lionel Moisan <Lionel.Moisan@parisdescartes.fr>
// Changelog : 2011 Use Eigen SVD <Pierre Moulon>
//
// Copyright: See COPYING file that comes with this distribution
//
//
#ifndef STEREOMATCH_H
#define STEREOMATCH_H
#include <vector>
#include "libNumerics/numerics.h"
#include "libMatch/match.h"
#include <sstream>
#include <iostream>
#include <fstream>
#include <cmath>
#include <cstdio>
#include <cmath>
#include <cstdlib>
/*-------------------- GENERAL PURPOSE ROUTINES --------------------*/
/* routines for vectors and matrices */
//float *vector(int nl, int nh);
float **matrix(int nrl, int nrh, int ncl, int nch);
void free_vector(float *v, int nl, int nh);
void free_matrix(float **m, int nrl, int nrh, int ncl, int nch);
/* Singular Value Decomposition routine */
void svdcmp(float **a, int m, int n, float *w, float **v);
/* Compute the real roots of a third order polynomial */
/* returns 1 or 3, the number of roots found */
int FindCubicRoots(float coeff[4], float x[3]);
/* logarithm (base 10) of binomial coefficient */
float logcombi(int k, int n);
/* tabulate logcombi(.,n) */
float *makelogcombi_n(int n);
/* tabulate logcombi(k,.) */
float *makelogcombi_k(int k, int nmax);
/* get a (sorted) random 7-uple of 0..n-1 */
void random_p7(int *k, int n);
/*-------------------- END OF GENERAL PURPOSE ROUTINES --------------------*/
/* float comparison for qsort() */
//According to http://www.cplusplus.com/reference/clibrary/cstdlib/qsort/,
//we should have: void qsort ( void * base, size_t num, size_t size, int ( * comparator ) ( const void *, const void * ) ); that means, for "qsort", the "comparator" has two constant void* type input parameters
int compf(const void *i, const void *j);
void matcherrorn(float **F, const std::vector<float>& p1, const std::vector<float>& p2, float *e);
int epipolar(std::vector<float>& m1, std::vector<float>& m2, int *k, float *z, float **F1, float **F2);
float orsa(int width, int height, std::vector<Match>& match, std::vector<float>& index, int t_value, int verb_value, int n_flag_value, int mode_value, int stop_value);
#endif

217
asift_match/src/splines.cpp Executable file
View file

@ -0,0 +1,217 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#include "splines.h"
double initcausal(double *c,int n,double z)
{
double zk,z2k,iz,sum;
int k;
zk = z; iz = 1./z;
z2k = pow(z,(double)n-1.);
sum = c[0] + z2k * c[n-1];
z2k = z2k*z2k*iz;
for (k=1;k<=n-2;k++) {
sum += (zk+z2k)*c[k];
zk *= z;
z2k *= iz;
}
return (sum/(1.-zk*zk));
}
double initanticausal(double *c,int n,double z)
{
return((z/(z*z-1.))*(z*c[n-2]+c[n-1]));
}
void invspline1D(double *c,int size,double *z,int npoles)
{
double lambda;
int n,k;
/* normalization */
for (k=npoles,lambda=1.;k--;) lambda *= (1.-z[k])*(1.-1./z[k]);
for (n=size;n--;) c[n] *= lambda;
/*----- Loop on poles -----*/
for (k=0;k<npoles;k++) {
/* forward recursion */
c[0] = initcausal(c,size,z[k]);
for (n=1;n<size;n++)
c[n] += z[k]*c[n-1];
/* backwards recursion */
c[size-1] = initanticausal(c,size,z[k]);
for (n=size-1;n--;)
c[n] = z[k]*(c[n+1]-c[n]);
}
}
/*------------------------------ MAIN MODULE ------------------------------*/
// void finvspline(float *in,int order,float *out, int width, int height)
// Guoshen Yu, 2010.09.21, Windows version
void finvspline(vector<float> &in,int order,vector<float>& out, int width, int height)
// void finvspline(float *in,int order,float *out, int width, int height)
{
double *c,*d,z[5];
int npoles,nx,ny,x,y;
ny = height; nx = width;
/* initialize poles of associated z-filter */
switch (order)
{
case 2: z[0]=-0.17157288; /* sqrt(8)-3 */
break;
case 3: z[0]=-0.26794919; /* sqrt(3)-2 */
break;
case 4: z[0]=-0.361341; z[1]=-0.0137254;
break;
case 5: z[0]=-0.430575; z[1]=-0.0430963;
break;
case 6: z[0]=-0.488295; z[1]=-0.0816793; z[2]=-0.00141415;
break;
case 7: z[0]=-0.53528; z[1]=-0.122555; z[2]=-0.00914869;
break;
case 8: z[0]=-0.574687; z[1]=-0.163035; z[2]=-0.0236323; z[3]=-0.000153821;
break;
case 9: z[0]=-0.607997; z[1]=-0.201751; z[2]=-0.0432226; z[3]=-0.00212131;
break;
case 10: z[0]=-0.636551; z[1]=-0.238183; z[2]=-0.065727; z[3]=-0.00752819;
z[4]=-0.0000169828;
break;
case 11: z[0]=-0.661266; z[1]=-0.27218; z[2]=-0.0897596; z[3]=-0.0166696;
z[4]=-0.000510558;
break;
default:
printf("finvspline: order should be in 2..11.\n");
exit(-1);
}
npoles = order/2;
/* initialize double array containing image */
c = (double *)malloc(nx*ny*sizeof(double));
d = (double *)malloc(nx*ny*sizeof(double));
for (x=nx*ny;x--;)
c[x] = (double)in[x];
/* apply filter on lines */
for (y=0;y<ny;y++)
invspline1D(c+y*nx,nx,z,npoles);
/* transpose */
for (x=0;x<nx;x++)
for (y=0;y<ny;y++)
d[x*ny+y] = c[y*nx+x];
/* apply filter on columns */
for (x=0;x<nx;x++)
invspline1D(d+x*ny,ny,z,npoles);
/* transpose directy into image */
for (x=0;x<nx;x++)
for (y=0;y<ny;y++)
out[y*nx+x] = (float)(d[x*ny+y]);
/* free array */
free(d);
free(c);
}
/* extract image value (even outside image domain) */
//float v(float *in,int x,int y,float bg, int width, int height)
// Guoshen Yu, 2010.09.21, Windows version
float v(vector<float>& in,int x,int y,float bg, int width, int height)
// float v(float *in, int x,int y,float bg, int width, int height)
{
if (x<0 || x>=width || y<0 || y>=height)
return(bg); else return(in[y*width+x]);
}
/* c[] = values of interpolation function at ...,t-2,t-1,t,t+1,... */
/* coefficients for cubic interpolant (Keys' function) */
void keys(float *c,float t,float a)
{
float t2,at;
t2 = t*t;
at = a*t;
c[0] = a*t2*(1.0-t);
c[1] = (2.0*a+3.0 - (a+2.0)*t)*t2 - at;
c[2] = ((a+2.0)*t - a-3.0)*t2 + 1.0;
c[3] = a*(t-2.0)*t2 + at;
}
/* coefficients for cubic spline */
void spline3(float *c,float t)
{
float tmp;
tmp = 1.-t;
c[0] = 0.1666666666*t*t*t;
c[1] = 0.6666666666-0.5*tmp*tmp*(1.+t);
c[2] = 0.6666666666-0.5*t*t*(2.-t);
c[3] = 0.1666666666*tmp*tmp*tmp;
}
/* pre-computation for spline of order >3 */
void init_splinen(float *a,int n)
{
int k;
a[0] = 1.;
for (k=2;k<=n;k++) a[0]/=(float)k;
for (k=1;k<=n+1;k++)
a[k] = - a[k-1] *(float)(n+2-k)/(float)k;
}
/* fast integral power function */
float ipow(float x,int n)
{
float res;
for (res=1.;n;n>>=1) {
if (n&1) res*=x;
x*=x;
}
return(res);
}
/* coefficients for spline of order >3 */
void splinen(float *c,float t,float *a,int n)
{
int i,k;
float xn;
memset((void *)c,0,(n+1)*sizeof(float));
for (k=0;k<=n+1;k++) {
xn = ipow(t+(float)k,n);
for (i=k;i<=n;i++)
c[i] += a[i-k]*xn;
}
}

34
asift_match/src/splines.h Executable file
View file

@ -0,0 +1,34 @@
// Authors: Unknown. Please, if you are the author of this file, or if you
// know who are the authors of this file, let us know, so we can give the
// adequate credits and/or get the adequate authorizations.
#ifndef _SPLINES_H_
#define _SPLINES_H_
#include "numerics1.h"
#include "library.h"
#include "string.h"
#include <vector>
using namespace std;
//float v(float *in,int x,int y,float bg, int width, int height);
// Guoshen Yu, 2010.09.21, Windows version
float v(vector<float>& in,int x,int y,float bg, int width, int height);
//float v(float *in, int x,int y,float bg, int width, int height);
void keys(float *c,float t,float a);
void spline3(float *c,float t);
void init_splinen(float *a,int n);
void splinen(float *c,float t,float *a,int n);
//void finvspline(float *in,int order,float *out, int width, int height);
// Guoshen Yu, 2010.09.22, Windows versions
void finvspline(vector<float>& in,int order,vector<float>& out, int width, int height);
// void finvspline(float *in,int order,float *out, int width, int height);
#endif

11
asift_match/src/third_party/Eigen/Array vendored Executable file
View file

@ -0,0 +1,11 @@
#ifndef EIGEN_ARRAY_MODULE_H
#define EIGEN_ARRAY_MODULE_H
// include Core first to handle Eigen2 support macros
#include "Core"
#ifndef EIGEN2_SUPPORT
#error The Eigen/Array header does no longer exist in Eigen3. All that functionality has moved to Eigen/Core.
#endif
#endif // EIGEN_ARRAY_MODULE_H

View file

@ -0,0 +1,19 @@
include(RegexUtils)
test_escape_string_as_regex()
file(GLOB Eigen_directory_files "*")
escape_string_as_regex(ESCAPED_CMAKE_CURRENT_SOURCE_DIR "${CMAKE_CURRENT_SOURCE_DIR}")
foreach(f ${Eigen_directory_files})
if(NOT f MATCHES "\\.txt" AND NOT f MATCHES "${ESCAPED_CMAKE_CURRENT_SOURCE_DIR}/[.].+" AND NOT f MATCHES "${ESCAPED_CMAKE_CURRENT_SOURCE_DIR}/src")
list(APPEND Eigen_directory_files_to_install ${f})
endif()
endforeach(f ${Eigen_directory_files})
install(FILES
${Eigen_directory_files_to_install}
DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen COMPONENT Devel
)
add_subdirectory(src)

674
asift_match/src/third_party/Eigen/COPYING.GPL vendored Executable file
View file

@ -0,0 +1,674 @@
GNU GENERAL PUBLIC LICENSE
Version 3, 29 June 2007
Copyright (C) 2007 Free Software Foundation, Inc. <http://fsf.org/>
Everyone is permitted to copy and distribute verbatim copies
of this license document, but changing it is not allowed.
Preamble
The GNU General Public License is a free, copyleft license for
software and other kinds of works.
The licenses for most software and other practical works are designed
to take away your freedom to share and change the works. By contrast,
the GNU General Public License is intended to guarantee your freedom to
share and change all versions of a program--to make sure it remains free
software for all its users. We, the Free Software Foundation, use the
GNU General Public License for most of our software; it applies also to
any other work released this way by its authors. You can apply it to
your programs, too.
When we speak of free software, we are referring to freedom, not
price. Our General Public Licenses are designed to make sure that you
have the freedom to distribute copies of free software (and charge for
them if you wish), that you receive source code or can get it if you
want it, that you can change the software or use pieces of it in new
free programs, and that you know you can do these things.
To protect your rights, we need to prevent others from denying you
these rights or asking you to surrender the rights. Therefore, you have
certain responsibilities if you distribute copies of the software, or if
you modify it: responsibilities to respect the freedom of others.
For example, if you distribute copies of such a program, whether
gratis or for a fee, you must pass on to the recipients the same
freedoms that you received. You must make sure that they, too, receive
or can get the source code. And you must show them these terms so they
know their rights.
Developers that use the GNU GPL protect your rights with two steps:
(1) assert copyright on the software, and (2) offer you this License
giving you legal permission to copy, distribute and/or modify it.
For the developers' and authors' protection, the GPL clearly explains
that there is no warranty for this free software. For both users' and
authors' sake, the GPL requires that modified versions be marked as
changed, so that their problems will not be attributed erroneously to
authors of previous versions.
Some devices are designed to deny users access to install or run
modified versions of the software inside them, although the manufacturer
can do so. This is fundamentally incompatible with the aim of
protecting users' freedom to change the software. The systematic
pattern of such abuse occurs in the area of products for individuals to
use, which is precisely where it is most unacceptable. Therefore, we
have designed this version of the GPL to prohibit the practice for those
products. If such problems arise substantially in other domains, we
stand ready to extend this provision to those domains in future versions
of the GPL, as needed to protect the freedom of users.
Finally, every program is threatened constantly by software patents.
States should not allow patents to restrict development and use of
software on general-purpose computers, but in those that do, we wish to
avoid the special danger that patents applied to a free program could
make it effectively proprietary. To prevent this, the GPL assures that
patents cannot be used to render the program non-free.
The precise terms and conditions for copying, distribution and
modification follow.
TERMS AND CONDITIONS
0. Definitions.
"This License" refers to version 3 of the GNU General Public License.
"Copyright" also means copyright-like laws that apply to other kinds of
works, such as semiconductor masks.
"The Program" refers to any copyrightable work licensed under this
License. Each licensee is addressed as "you". "Licensees" and
"recipients" may be individuals or organizations.
To "modify" a work means to copy from or adapt all or part of the work
in a fashion requiring copyright permission, other than the making of an
exact copy. The resulting work is called a "modified version" of the
earlier work or a work "based on" the earlier work.
A "covered work" means either the unmodified Program or a work based
on the Program.
To "propagate" a work means to do anything with it that, without
permission, would make you directly or secondarily liable for
infringement under applicable copyright law, except executing it on a
computer or modifying a private copy. Propagation includes copying,
distribution (with or without modification), making available to the
public, and in some countries other activities as well.
To "convey" a work means any kind of propagation that enables other
parties to make or receive copies. Mere interaction with a user through
a computer network, with no transfer of a copy, is not conveying.
An interactive user interface displays "Appropriate Legal Notices"
to the extent that it includes a convenient and prominently visible
feature that (1) displays an appropriate copyright notice, and (2)
tells the user that there is no warranty for the work (except to the
extent that warranties are provided), that licensees may convey the
work under this License, and how to view a copy of this License. If
the interface presents a list of user commands or options, such as a
menu, a prominent item in the list meets this criterion.
1. Source Code.
The "source code" for a work means the preferred form of the work
for making modifications to it. "Object code" means any non-source
form of a work.
A "Standard Interface" means an interface that either is an official
standard defined by a recognized standards body, or, in the case of
interfaces specified for a particular programming language, one that
is widely used among developers working in that language.
The "System Libraries" of an executable work include anything, other
than the work as a whole, that (a) is included in the normal form of
packaging a Major Component, but which is not part of that Major
Component, and (b) serves only to enable use of the work with that
Major Component, or to implement a Standard Interface for which an
implementation is available to the public in source code form. A
"Major Component", in this context, means a major essential component
(kernel, window system, and so on) of the specific operating system
(if any) on which the executable work runs, or a compiler used to
produce the work, or an object code interpreter used to run it.
The "Corresponding Source" for a work in object code form means all
the source code needed to generate, install, and (for an executable
work) run the object code and to modify the work, including scripts to
control those activities. However, it does not include the work's
System Libraries, or general-purpose tools or generally available free
programs which are used unmodified in performing those activities but
which are not part of the work. For example, Corresponding Source
includes interface definition files associated with source files for
the work, and the source code for shared libraries and dynamically
linked subprograms that the work is specifically designed to require,
such as by intimate data communication or control flow between those
subprograms and other parts of the work.
The Corresponding Source need not include anything that users
can regenerate automatically from other parts of the Corresponding
Source.
The Corresponding Source for a work in source code form is that
same work.
2. Basic Permissions.
All rights granted under this License are granted for the term of
copyright on the Program, and are irrevocable provided the stated
conditions are met. This License explicitly affirms your unlimited
permission to run the unmodified Program. The output from running a
covered work is covered by this License only if the output, given its
content, constitutes a covered work. This License acknowledges your
rights of fair use or other equivalent, as provided by copyright law.
You may make, run and propagate covered works that you do not
convey, without conditions so long as your license otherwise remains
in force. You may convey covered works to others for the sole purpose
of having them make modifications exclusively for you, or provide you
with facilities for running those works, provided that you comply with
the terms of this License in conveying all material for which you do
not control copyright. Those thus making or running the covered works
for you must do so exclusively on your behalf, under your direction
and control, on terms that prohibit them from making any copies of
your copyrighted material outside their relationship with you.
Conveying under any other circumstances is permitted solely under
the conditions stated below. Sublicensing is not allowed; section 10
makes it unnecessary.
3. Protecting Users' Legal Rights From Anti-Circumvention Law.
No covered work shall be deemed part of an effective technological
measure under any applicable law fulfilling obligations under article
11 of the WIPO copyright treaty adopted on 20 December 1996, or
similar laws prohibiting or restricting circumvention of such
measures.
When you convey a covered work, you waive any legal power to forbid
circumvention of technological measures to the extent such circumvention
is effected by exercising rights under this License with respect to
the covered work, and you disclaim any intention to limit operation or
modification of the work as a means of enforcing, against the work's
users, your or third parties' legal rights to forbid circumvention of
technological measures.
4. Conveying Verbatim Copies.
You may convey verbatim copies of the Program's source code as you
receive it, in any medium, provided that you conspicuously and
appropriately publish on each copy an appropriate copyright notice;
keep intact all notices stating that this License and any
non-permissive terms added in accord with section 7 apply to the code;
keep intact all notices of the absence of any warranty; and give all
recipients a copy of this License along with the Program.
You may charge any price or no price for each copy that you convey,
and you may offer support or warranty protection for a fee.
5. Conveying Modified Source Versions.
You may convey a work based on the Program, or the modifications to
produce it from the Program, in the form of source code under the
terms of section 4, provided that you also meet all of these conditions:
a) The work must carry prominent notices stating that you modified
it, and giving a relevant date.
b) The work must carry prominent notices stating that it is
released under this License and any conditions added under section
7. This requirement modifies the requirement in section 4 to
"keep intact all notices".
c) You must license the entire work, as a whole, under this
License to anyone who comes into possession of a copy. This
License will therefore apply, along with any applicable section 7
additional terms, to the whole of the work, and all its parts,
regardless of how they are packaged. This License gives no
permission to license the work in any other way, but it does not
invalidate such permission if you have separately received it.
d) If the work has interactive user interfaces, each must display
Appropriate Legal Notices; however, if the Program has interactive
interfaces that do not display Appropriate Legal Notices, your
work need not make them do so.
A compilation of a covered work with other separate and independent
works, which are not by their nature extensions of the covered work,
and which are not combined with it such as to form a larger program,
in or on a volume of a storage or distribution medium, is called an
"aggregate" if the compilation and its resulting copyright are not
used to limit the access or legal rights of the compilation's users
beyond what the individual works permit. Inclusion of a covered work
in an aggregate does not cause this License to apply to the other
parts of the aggregate.
6. Conveying Non-Source Forms.
You may convey a covered work in object code form under the terms
of sections 4 and 5, provided that you also convey the
machine-readable Corresponding Source under the terms of this License,
in one of these ways:
a) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by the
Corresponding Source fixed on a durable physical medium
customarily used for software interchange.
b) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by a
written offer, valid for at least three years and valid for as
long as you offer spare parts or customer support for that product
model, to give anyone who possesses the object code either (1) a
copy of the Corresponding Source for all the software in the
product that is covered by this License, on a durable physical
medium customarily used for software interchange, for a price no
more than your reasonable cost of physically performing this
conveying of source, or (2) access to copy the
Corresponding Source from a network server at no charge.
c) Convey individual copies of the object code with a copy of the
written offer to provide the Corresponding Source. This
alternative is allowed only occasionally and noncommercially, and
only if you received the object code with such an offer, in accord
with subsection 6b.
d) Convey the object code by offering access from a designated
place (gratis or for a charge), and offer equivalent access to the
Corresponding Source in the same way through the same place at no
further charge. You need not require recipients to copy the
Corresponding Source along with the object code. If the place to
copy the object code is a network server, the Corresponding Source
may be on a different server (operated by you or a third party)
that supports equivalent copying facilities, provided you maintain
clear directions next to the object code saying where to find the
Corresponding Source. Regardless of what server hosts the
Corresponding Source, you remain obligated to ensure that it is
available for as long as needed to satisfy these requirements.
e) Convey the object code using peer-to-peer transmission, provided
you inform other peers where the object code and Corresponding
Source of the work are being offered to the general public at no
charge under subsection 6d.
A separable portion of the object code, whose source code is excluded
from the Corresponding Source as a System Library, need not be
included in conveying the object code work.
A "User Product" is either (1) a "consumer product", which means any
tangible personal property which is normally used for personal, family,
or household purposes, or (2) anything designed or sold for incorporation
into a dwelling. In determining whether a product is a consumer product,
doubtful cases shall be resolved in favor of coverage. For a particular
product received by a particular user, "normally used" refers to a
typical or common use of that class of product, regardless of the status
of the particular user or of the way in which the particular user
actually uses, or expects or is expected to use, the product. A product
is a consumer product regardless of whether the product has substantial
commercial, industrial or non-consumer uses, unless such uses represent
the only significant mode of use of the product.
"Installation Information" for a User Product means any methods,
procedures, authorization keys, or other information required to install
and execute modified versions of a covered work in that User Product from
a modified version of its Corresponding Source. The information must
suffice to ensure that the continued functioning of the modified object
code is in no case prevented or interfered with solely because
modification has been made.
If you convey an object code work under this section in, or with, or
specifically for use in, a User Product, and the conveying occurs as
part of a transaction in which the right of possession and use of the
User Product is transferred to the recipient in perpetuity or for a
fixed term (regardless of how the transaction is characterized), the
Corresponding Source conveyed under this section must be accompanied
by the Installation Information. But this requirement does not apply
if neither you nor any third party retains the ability to install
modified object code on the User Product (for example, the work has
been installed in ROM).
The requirement to provide Installation Information does not include a
requirement to continue to provide support service, warranty, or updates
for a work that has been modified or installed by the recipient, or for
the User Product in which it has been modified or installed. Access to a
network may be denied when the modification itself materially and
adversely affects the operation of the network or violates the rules and
protocols for communication across the network.
Corresponding Source conveyed, and Installation Information provided,
in accord with this section must be in a format that is publicly
documented (and with an implementation available to the public in
source code form), and must require no special password or key for
unpacking, reading or copying.
7. Additional Terms.
"Additional permissions" are terms that supplement the terms of this
License by making exceptions from one or more of its conditions.
Additional permissions that are applicable to the entire Program shall
be treated as though they were included in this License, to the extent
that they are valid under applicable law. If additional permissions
apply only to part of the Program, that part may be used separately
under those permissions, but the entire Program remains governed by
this License without regard to the additional permissions.
When you convey a copy of a covered work, you may at your option
remove any additional permissions from that copy, or from any part of
it. (Additional permissions may be written to require their own
removal in certain cases when you modify the work.) You may place
additional permissions on material, added by you to a covered work,
for which you have or can give appropriate copyright permission.
Notwithstanding any other provision of this License, for material you
add to a covered work, you may (if authorized by the copyright holders of
that material) supplement the terms of this License with terms:
a) Disclaiming warranty or limiting liability differently from the
terms of sections 15 and 16 of this License; or
b) Requiring preservation of specified reasonable legal notices or
author attributions in that material or in the Appropriate Legal
Notices displayed by works containing it; or
c) Prohibiting misrepresentation of the origin of that material, or
requiring that modified versions of such material be marked in
reasonable ways as different from the original version; or
d) Limiting the use for publicity purposes of names of licensors or
authors of the material; or
e) Declining to grant rights under trademark law for use of some
trade names, trademarks, or service marks; or
f) Requiring indemnification of licensors and authors of that
material by anyone who conveys the material (or modified versions of
it) with contractual assumptions of liability to the recipient, for
any liability that these contractual assumptions directly impose on
those licensors and authors.
All other non-permissive additional terms are considered "further
restrictions" within the meaning of section 10. If the Program as you
received it, or any part of it, contains a notice stating that it is
governed by this License along with a term that is a further
restriction, you may remove that term. If a license document contains
a further restriction but permits relicensing or conveying under this
License, you may add to a covered work material governed by the terms
of that license document, provided that the further restriction does
not survive such relicensing or conveying.
If you add terms to a covered work in accord with this section, you
must place, in the relevant source files, a statement of the
additional terms that apply to those files, or a notice indicating
where to find the applicable terms.
Additional terms, permissive or non-permissive, may be stated in the
form of a separately written license, or stated as exceptions;
the above requirements apply either way.
8. Termination.
You may not propagate or modify a covered work except as expressly
provided under this License. Any attempt otherwise to propagate or
modify it is void, and will automatically terminate your rights under
this License (including any patent licenses granted under the third
paragraph of section 11).
However, if you cease all violation of this License, then your
license from a particular copyright holder is reinstated (a)
provisionally, unless and until the copyright holder explicitly and
finally terminates your license, and (b) permanently, if the copyright
holder fails to notify you of the violation by some reasonable means
prior to 60 days after the cessation.
Moreover, your license from a particular copyright holder is
reinstated permanently if the copyright holder notifies you of the
violation by some reasonable means, this is the first time you have
received notice of violation of this License (for any work) from that
copyright holder, and you cure the violation prior to 30 days after
your receipt of the notice.
Termination of your rights under this section does not terminate the
licenses of parties who have received copies or rights from you under
this License. If your rights have been terminated and not permanently
reinstated, you do not qualify to receive new licenses for the same
material under section 10.
9. Acceptance Not Required for Having Copies.
You are not required to accept this License in order to receive or
run a copy of the Program. Ancillary propagation of a covered work
occurring solely as a consequence of using peer-to-peer transmission
to receive a copy likewise does not require acceptance. However,
nothing other than this License grants you permission to propagate or
modify any covered work. These actions infringe copyright if you do
not accept this License. Therefore, by modifying or propagating a
covered work, you indicate your acceptance of this License to do so.
10. Automatic Licensing of Downstream Recipients.
Each time you convey a covered work, the recipient automatically
receives a license from the original licensors, to run, modify and
propagate that work, subject to this License. You are not responsible
for enforcing compliance by third parties with this License.
An "entity transaction" is a transaction transferring control of an
organization, or substantially all assets of one, or subdividing an
organization, or merging organizations. If propagation of a covered
work results from an entity transaction, each party to that
transaction who receives a copy of the work also receives whatever
licenses to the work the party's predecessor in interest had or could
give under the previous paragraph, plus a right to possession of the
Corresponding Source of the work from the predecessor in interest, if
the predecessor has it or can get it with reasonable efforts.
You may not impose any further restrictions on the exercise of the
rights granted or affirmed under this License. For example, you may
not impose a license fee, royalty, or other charge for exercise of
rights granted under this License, and you may not initiate litigation
(including a cross-claim or counterclaim in a lawsuit) alleging that
any patent claim is infringed by making, using, selling, offering for
sale, or importing the Program or any portion of it.
11. Patents.
A "contributor" is a copyright holder who authorizes use under this
License of the Program or a work on which the Program is based. The
work thus licensed is called the contributor's "contributor version".
A contributor's "essential patent claims" are all patent claims
owned or controlled by the contributor, whether already acquired or
hereafter acquired, that would be infringed by some manner, permitted
by this License, of making, using, or selling its contributor version,
but do not include claims that would be infringed only as a
consequence of further modification of the contributor version. For
purposes of this definition, "control" includes the right to grant
patent sublicenses in a manner consistent with the requirements of
this License.
Each contributor grants you a non-exclusive, worldwide, royalty-free
patent license under the contributor's essential patent claims, to
make, use, sell, offer for sale, import and otherwise run, modify and
propagate the contents of its contributor version.
In the following three paragraphs, a "patent license" is any express
agreement or commitment, however denominated, not to enforce a patent
(such as an express permission to practice a patent or covenant not to
sue for patent infringement). To "grant" such a patent license to a
party means to make such an agreement or commitment not to enforce a
patent against the party.
If you convey a covered work, knowingly relying on a patent license,
and the Corresponding Source of the work is not available for anyone
to copy, free of charge and under the terms of this License, through a
publicly available network server or other readily accessible means,
then you must either (1) cause the Corresponding Source to be so
available, or (2) arrange to deprive yourself of the benefit of the
patent license for this particular work, or (3) arrange, in a manner
consistent with the requirements of this License, to extend the patent
license to downstream recipients. "Knowingly relying" means you have
actual knowledge that, but for the patent license, your conveying the
covered work in a country, or your recipient's use of the covered work
in a country, would infringe one or more identifiable patents in that
country that you have reason to believe are valid.
If, pursuant to or in connection with a single transaction or
arrangement, you convey, or propagate by procuring conveyance of, a
covered work, and grant a patent license to some of the parties
receiving the covered work authorizing them to use, propagate, modify
or convey a specific copy of the covered work, then the patent license
you grant is automatically extended to all recipients of the covered
work and works based on it.
A patent license is "discriminatory" if it does not include within
the scope of its coverage, prohibits the exercise of, or is
conditioned on the non-exercise of one or more of the rights that are
specifically granted under this License. You may not convey a covered
work if you are a party to an arrangement with a third party that is
in the business of distributing software, under which you make payment
to the third party based on the extent of your activity of conveying
the work, and under which the third party grants, to any of the
parties who would receive the covered work from you, a discriminatory
patent license (a) in connection with copies of the covered work
conveyed by you (or copies made from those copies), or (b) primarily
for and in connection with specific products or compilations that
contain the covered work, unless you entered into that arrangement,
or that patent license was granted, prior to 28 March 2007.
Nothing in this License shall be construed as excluding or limiting
any implied license or other defenses to infringement that may
otherwise be available to you under applicable patent law.
12. No Surrender of Others' Freedom.
If conditions are imposed on you (whether by court order, agreement or
otherwise) that contradict the conditions of this License, they do not
excuse you from the conditions of this License. If you cannot convey a
covered work so as to satisfy simultaneously your obligations under this
License and any other pertinent obligations, then as a consequence you may
not convey it at all. For example, if you agree to terms that obligate you
to collect a royalty for further conveying from those to whom you convey
the Program, the only way you could satisfy both those terms and this
License would be to refrain entirely from conveying the Program.
13. Use with the GNU Affero General Public License.
Notwithstanding any other provision of this License, you have
permission to link or combine any covered work with a work licensed
under version 3 of the GNU Affero General Public License into a single
combined work, and to convey the resulting work. The terms of this
License will continue to apply to the part which is the covered work,
but the special requirements of the GNU Affero General Public License,
section 13, concerning interaction through a network will apply to the
combination as such.
14. Revised Versions of this License.
The Free Software Foundation may publish revised and/or new versions of
the GNU General Public License from time to time. Such new versions will
be similar in spirit to the present version, but may differ in detail to
address new problems or concerns.
Each version is given a distinguishing version number. If the
Program specifies that a certain numbered version of the GNU General
Public License "or any later version" applies to it, you have the
option of following the terms and conditions either of that numbered
version or of any later version published by the Free Software
Foundation. If the Program does not specify a version number of the
GNU General Public License, you may choose any version ever published
by the Free Software Foundation.
If the Program specifies that a proxy can decide which future
versions of the GNU General Public License can be used, that proxy's
public statement of acceptance of a version permanently authorizes you
to choose that version for the Program.
Later license versions may give you additional or different
permissions. However, no additional obligations are imposed on any
author or copyright holder as a result of your choosing to follow a
later version.
15. Disclaimer of Warranty.
THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY
APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT
HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY
OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO,
THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM
IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF
ALL NECESSARY SERVICING, REPAIR OR CORRECTION.
16. Limitation of Liability.
IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING
WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS
THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY
GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE
USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF
DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD
PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS),
EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF
SUCH DAMAGES.
17. Interpretation of Sections 15 and 16.
If the disclaimer of warranty and limitation of liability provided
above cannot be given local legal effect according to their terms,
reviewing courts shall apply local law that most closely approximates
an absolute waiver of all civil liability in connection with the
Program, unless a warranty or assumption of liability accompanies a
copy of the Program in return for a fee.
END OF TERMS AND CONDITIONS
How to Apply These Terms to Your New Programs
If you develop a new program, and you want it to be of the greatest
possible use to the public, the best way to achieve this is to make it
free software which everyone can redistribute and change under these terms.
To do so, attach the following notices to the program. It is safest
to attach them to the start of each source file to most effectively
state the exclusion of warranty; and each file should have at least
the "copyright" line and a pointer to where the full notice is found.
<one line to give the program's name and a brief idea of what it does.>
Copyright (C) <year> <name of author>
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
Also add information on how to contact you by electronic and paper mail.
If the program does terminal interaction, make it output a short
notice like this when it starts in an interactive mode:
<program> Copyright (C) <year> <name of author>
This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'.
This is free software, and you are welcome to redistribute it
under certain conditions; type `show c' for details.
The hypothetical commands `show w' and `show c' should show the appropriate
parts of the General Public License. Of course, your program's commands
might be different; for a GUI interface, you would use an "about box".
You should also get your employer (if you work as a programmer) or school,
if any, to sign a "copyright disclaimer" for the program, if necessary.
For more information on this, and how to apply and follow the GNU GPL, see
<http://www.gnu.org/licenses/>.
The GNU General Public License does not permit incorporating your program
into proprietary programs. If your program is a subroutine library, you
may consider it more useful to permit linking proprietary applications with
the library. If this is what you want to do, use the GNU Lesser General
Public License instead of this License. But first, please read
<http://www.gnu.org/philosophy/why-not-lgpl.html>.

165
asift_match/src/third_party/Eigen/COPYING.LGPL vendored Executable file
View file

@ -0,0 +1,165 @@
GNU LESSER GENERAL PUBLIC LICENSE
Version 3, 29 June 2007
Copyright (C) 2007 Free Software Foundation, Inc. <http://fsf.org/>
Everyone is permitted to copy and distribute verbatim copies
of this license document, but changing it is not allowed.
This version of the GNU Lesser General Public License incorporates
the terms and conditions of version 3 of the GNU General Public
License, supplemented by the additional permissions listed below.
0. Additional Definitions.
As used herein, "this License" refers to version 3 of the GNU Lesser
General Public License, and the "GNU GPL" refers to version 3 of the GNU
General Public License.
"The Library" refers to a covered work governed by this License,
other than an Application or a Combined Work as defined below.
An "Application" is any work that makes use of an interface provided
by the Library, but which is not otherwise based on the Library.
Defining a subclass of a class defined by the Library is deemed a mode
of using an interface provided by the Library.
A "Combined Work" is a work produced by combining or linking an
Application with the Library. The particular version of the Library
with which the Combined Work was made is also called the "Linked
Version".
The "Minimal Corresponding Source" for a Combined Work means the
Corresponding Source for the Combined Work, excluding any source code
for portions of the Combined Work that, considered in isolation, are
based on the Application, and not on the Linked Version.
The "Corresponding Application Code" for a Combined Work means the
object code and/or source code for the Application, including any data
and utility programs needed for reproducing the Combined Work from the
Application, but excluding the System Libraries of the Combined Work.
1. Exception to Section 3 of the GNU GPL.
You may convey a covered work under sections 3 and 4 of this License
without being bound by section 3 of the GNU GPL.
2. Conveying Modified Versions.
If you modify a copy of the Library, and, in your modifications, a
facility refers to a function or data to be supplied by an Application
that uses the facility (other than as an argument passed when the
facility is invoked), then you may convey a copy of the modified
version:
a) under this License, provided that you make a good faith effort to
ensure that, in the event an Application does not supply the
function or data, the facility still operates, and performs
whatever part of its purpose remains meaningful, or
b) under the GNU GPL, with none of the additional permissions of
this License applicable to that copy.
3. Object Code Incorporating Material from Library Header Files.
The object code form of an Application may incorporate material from
a header file that is part of the Library. You may convey such object
code under terms of your choice, provided that, if the incorporated
material is not limited to numerical parameters, data structure
layouts and accessors, or small macros, inline functions and templates
(ten or fewer lines in length), you do both of the following:
a) Give prominent notice with each copy of the object code that the
Library is used in it and that the Library and its use are
covered by this License.
b) Accompany the object code with a copy of the GNU GPL and this license
document.
4. Combined Works.
You may convey a Combined Work under terms of your choice that,
taken together, effectively do not restrict modification of the
portions of the Library contained in the Combined Work and reverse
engineering for debugging such modifications, if you also do each of
the following:
a) Give prominent notice with each copy of the Combined Work that
the Library is used in it and that the Library and its use are
covered by this License.
b) Accompany the Combined Work with a copy of the GNU GPL and this license
document.
c) For a Combined Work that displays copyright notices during
execution, include the copyright notice for the Library among
these notices, as well as a reference directing the user to the
copies of the GNU GPL and this license document.
d) Do one of the following:
0) Convey the Minimal Corresponding Source under the terms of this
License, and the Corresponding Application Code in a form
suitable for, and under terms that permit, the user to
recombine or relink the Application with a modified version of
the Linked Version to produce a modified Combined Work, in the
manner specified by section 6 of the GNU GPL for conveying
Corresponding Source.
1) Use a suitable shared library mechanism for linking with the
Library. A suitable mechanism is one that (a) uses at run time
a copy of the Library already present on the user's computer
system, and (b) will operate properly with a modified version
of the Library that is interface-compatible with the Linked
Version.
e) Provide Installation Information, but only if you would otherwise
be required to provide such information under section 6 of the
GNU GPL, and only to the extent that such information is
necessary to install and execute a modified version of the
Combined Work produced by recombining or relinking the
Application with a modified version of the Linked Version. (If
you use option 4d0, the Installation Information must accompany
the Minimal Corresponding Source and Corresponding Application
Code. If you use option 4d1, you must provide the Installation
Information in the manner specified by section 6 of the GNU GPL
for conveying Corresponding Source.)
5. Combined Libraries.
You may place library facilities that are a work based on the
Library side by side in a single library together with other library
facilities that are not Applications and are not covered by this
License, and convey such a combined library under terms of your
choice, if you do both of the following:
a) Accompany the combined library with a copy of the same work based
on the Library, uncombined with any other library facilities,
conveyed under the terms of this License.
b) Give prominent notice with the combined library that part of it
is a work based on the Library, and explaining where to find the
accompanying uncombined form of the same work.
6. Revised Versions of the GNU Lesser General Public License.
The Free Software Foundation may publish revised and/or new versions
of the GNU Lesser General Public License from time to time. Such new
versions will be similar in spirit to the present version, but may
differ in detail to address new problems or concerns.
Each version is given a distinguishing version number. If the
Library as you received it specifies that a certain numbered version
of the GNU Lesser General Public License "or any later version"
applies to it, you have the option of following the terms and
conditions either of that published version or of any later version
published by the Free Software Foundation. If the Library as you
received it does not specify a version number of the GNU Lesser
General Public License, you may choose any version of the GNU Lesser
General Public License ever published by the Free Software Foundation.
If the Library as you received it specifies that a proxy can decide
whether future versions of the GNU Lesser General Public License shall
apply, that proxy's public statement of acceptance of any version is
permanent authorization for you to choose that version for the
Library.

33
asift_match/src/third_party/Eigen/Cholesky vendored Executable file
View file

@ -0,0 +1,33 @@
#ifndef EIGEN_CHOLESKY_MODULE_H
#define EIGEN_CHOLESKY_MODULE_H
#include "Core"
#include "src/Core/util/DisableStupidWarnings.h"
namespace Eigen {
/** \defgroup Cholesky_Module Cholesky module
*
*
*
* This module provides two variants of the Cholesky decomposition for selfadjoint (hermitian) matrices.
* Those decompositions are accessible via the following MatrixBase methods:
* - MatrixBase::llt(),
* - MatrixBase::ldlt()
*
* \code
* #include <Eigen/Cholesky>
* \endcode
*/
#include "src/misc/Solve.h"
#include "src/Cholesky/LLT.h"
#include "src/Cholesky/LDLT.h"
} // namespace Eigen
#include "src/Core/util/ReenableStupidWarnings.h"
#endif // EIGEN_CHOLESKY_MODULE_H
/* vim: set filetype=cpp et sw=2 ts=2 ai: */

363
asift_match/src/third_party/Eigen/Core vendored Executable file
View file

@ -0,0 +1,363 @@
// This file is part of Eigen, a lightweight C++ template library
// for linear algebra.
//
// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>
// Copyright (C) 2007-2011 Benoit Jacob <jacob.benoit.1@gmail.com>
//
// Eigen is free software; you can redistribute it and/or
// modify it under the terms of the GNU Lesser General Public
// License as published by the Free Software Foundation; either
// version 3 of the License, or (at your option) any later version.
//
// Alternatively, you can redistribute it and/or
// modify it under the terms of the GNU General Public License as
// published by the Free Software Foundation; either version 2 of
// the License, or (at your option) any later version.
//
// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY
// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the
// GNU General Public License for more details.
//
// You should have received a copy of the GNU Lesser General Public
// License and a copy of the GNU General Public License along with
// Eigen. If not, see <http://www.gnu.org/licenses/>.
#ifndef EIGEN_CORE_H
#define EIGEN_CORE_H
// first thing Eigen does: stop the compiler from committing suicide
#include "src/Core/util/DisableStupidWarnings.h"
// then include this file where all our macros are defined. It's really important to do it first because
// it's where we do all the alignment settings (platform detection and honoring the user's will if he
// defined e.g. EIGEN_DONT_ALIGN) so it needs to be done before we do anything with vectorization.
#include "src/Core/util/Macros.h"
// if alignment is disabled, then disable vectorization. Note: EIGEN_ALIGN is the proper check, it takes into
// account both the user's will (EIGEN_DONT_ALIGN) and our own platform checks
#if !EIGEN_ALIGN
#ifndef EIGEN_DONT_VECTORIZE
#define EIGEN_DONT_VECTORIZE
#endif
#endif
#ifdef _MSC_VER
#include <malloc.h> // for _aligned_malloc -- need it regardless of whether vectorization is enabled
#if (_MSC_VER >= 1500) // 2008 or later
// Remember that usage of defined() in a #define is undefined by the standard.
// a user reported that in 64-bit mode, MSVC doesn't care to define _M_IX86_FP.
#if (defined(_M_IX86_FP) && (_M_IX86_FP >= 2)) || defined(_M_X64)
#define EIGEN_SSE2_ON_MSVC_2008_OR_LATER
#endif
#endif
#endif
// Remember that usage of defined() in a #define is undefined by the standard
#if (defined __SSE2__) && ( (!defined __GNUC__) || EIGEN_GNUC_AT_LEAST(4,2) )
#define EIGEN_SSE2_BUT_NOT_OLD_GCC
#endif
#ifndef EIGEN_DONT_VECTORIZE
#if defined (EIGEN_SSE2_BUT_NOT_OLD_GCC) || defined(EIGEN_SSE2_ON_MSVC_2008_OR_LATER)
// Defines symbols for compile-time detection of which instructions are
// used.
// EIGEN_VECTORIZE_YY is defined if and only if the instruction set YY is used
#define EIGEN_VECTORIZE
#define EIGEN_VECTORIZE_SSE
#define EIGEN_VECTORIZE_SSE2
// Detect sse3/ssse3/sse4:
// gcc and icc defines __SSE3__, ...
// there is no way to know about this on msvc. You can define EIGEN_VECTORIZE_SSE* if you
// want to force the use of those instructions with msvc.
#ifdef __SSE3__
#define EIGEN_VECTORIZE_SSE3
#endif
#ifdef __SSSE3__
#define EIGEN_VECTORIZE_SSSE3
#endif
#ifdef __SSE4_1__
#define EIGEN_VECTORIZE_SSE4_1
#endif
#ifdef __SSE4_2__
#define EIGEN_VECTORIZE_SSE4_2
#endif
// include files
// This extern "C" works around a MINGW-w64 compilation issue
// https://sourceforge.net/tracker/index.php?func=detail&aid=3018394&group_id=202880&atid=983354
// In essence, intrin.h is included by windows.h and also declares intrinsics (just as emmintrin.h etc. below do).
// However, intrin.h uses an extern "C" declaration, and g++ thus complains of duplicate declarations
// with conflicting linkage. The linkage for intrinsics doesn't matter, but at that stage the compiler doesn't know;
// so, to avoid compile errors when windows.h is included after Eigen/Core, ensure intrinsics are extern "C" here too.
// notice that since these are C headers, the extern "C" is theoretically needed anyways.
extern "C" {
#include <emmintrin.h>
#include <xmmintrin.h>
#ifdef EIGEN_VECTORIZE_SSE3
#include <pmmintrin.h>
#endif
#ifdef EIGEN_VECTORIZE_SSSE3
#include <tmmintrin.h>
#endif
#ifdef EIGEN_VECTORIZE_SSE4_1
#include <smmintrin.h>
#endif
#ifdef EIGEN_VECTORIZE_SSE4_2
#include <nmmintrin.h>
#endif
} // end extern "C"
#elif defined __ALTIVEC__
#define EIGEN_VECTORIZE
#define EIGEN_VECTORIZE_ALTIVEC
#include <altivec.h>
// We need to #undef all these ugly tokens defined in <altivec.h>
// => use __vector instead of vector
#undef bool
#undef vector
#undef pixel
#elif defined __ARM_NEON__
#define EIGEN_VECTORIZE
#define EIGEN_VECTORIZE_NEON
#include <arm_neon.h>
#endif
#endif
#if (defined _OPENMP) && (!defined EIGEN_DONT_PARALLELIZE)
#define EIGEN_HAS_OPENMP
#endif
#ifdef EIGEN_HAS_OPENMP
#include <omp.h>
#endif
// MSVC for windows mobile does not have the errno.h file
#if !(defined(_MSC_VER) && defined(_WIN32_WCE))
#define EIGEN_HAS_ERRNO
#endif
#ifdef EIGEN_HAS_ERRNO
#include <cerrno>
#endif
#include <cstdlib>
#include <cmath>
#include <complex>
#include <cassert>
#include <functional>
#include <iosfwd>
#include <cstring>
#include <string>
#include <limits>
#include <climits> // for CHAR_BIT
// for min/max:
#include <algorithm>
// for outputting debug info
#ifdef EIGEN_DEBUG_ASSIGN
#include <iostream>
#endif
// required for __cpuid, needs to be included after cmath
#if defined(_MSC_VER) && (defined(_M_IX86)||defined(_M_X64))
#include <intrin.h>
#endif
#if (defined(_CPPUNWIND) || defined(__EXCEPTIONS)) && !defined(EIGEN_NO_EXCEPTIONS)
#define EIGEN_EXCEPTIONS
#endif
#ifdef EIGEN_EXCEPTIONS
#include <new>
#endif
// this needs to be done after all possible windows C header includes and before any Eigen source includes
// (system C++ includes are supposed to be able to deal with this already):
// windows.h defines min and max macros which would make Eigen fail to compile.
#if defined(min) || defined(max)
#error The preprocessor symbols 'min' or 'max' are defined. If you are compiling on Windows, do #define NOMINMAX to prevent windows.h from defining these symbols.
#endif
// defined in bits/termios.h
#undef B0
namespace Eigen {
inline static const char *SimdInstructionSetsInUse(void) {
#if defined(EIGEN_VECTORIZE_SSE4_2)
return "SSE, SSE2, SSE3, SSSE3, SSE4.1, SSE4.2";
#elif defined(EIGEN_VECTORIZE_SSE4_1)
return "SSE, SSE2, SSE3, SSSE3, SSE4.1";
#elif defined(EIGEN_VECTORIZE_SSSE3)
return "SSE, SSE2, SSE3, SSSE3";
#elif defined(EIGEN_VECTORIZE_SSE3)
return "SSE, SSE2, SSE3";
#elif defined(EIGEN_VECTORIZE_SSE2)
return "SSE, SSE2";
#elif defined(EIGEN_VECTORIZE_ALTIVEC)
return "AltiVec";
#elif defined(EIGEN_VECTORIZE_NEON)
return "ARM NEON";
#else
return "None";
#endif
}
#define STAGE10_FULL_EIGEN2_API 10
#define STAGE20_RESOLVE_API_CONFLICTS 20
#define STAGE30_FULL_EIGEN3_API 30
#define STAGE40_FULL_EIGEN3_STRICTNESS 40
#define STAGE99_NO_EIGEN2_SUPPORT 99
#if defined EIGEN2_SUPPORT_STAGE40_FULL_EIGEN3_STRICTNESS
#define EIGEN2_SUPPORT
#define EIGEN2_SUPPORT_STAGE STAGE40_FULL_EIGEN3_STRICTNESS
#elif defined EIGEN2_SUPPORT_STAGE30_FULL_EIGEN3_API
#define EIGEN2_SUPPORT
#define EIGEN2_SUPPORT_STAGE STAGE30_FULL_EIGEN3_API
#elif defined EIGEN2_SUPPORT_STAGE20_RESOLVE_API_CONFLICTS
#define EIGEN2_SUPPORT
#define EIGEN2_SUPPORT_STAGE STAGE20_RESOLVE_API_CONFLICTS
#elif defined EIGEN2_SUPPORT_STAGE10_FULL_EIGEN2_API
#define EIGEN2_SUPPORT
#define EIGEN2_SUPPORT_STAGE STAGE10_FULL_EIGEN2_API
#elif defined EIGEN2_SUPPORT
// default to stage 3, that's what it's always meant
#define EIGEN2_SUPPORT_STAGE30_FULL_EIGEN3_API
#define EIGEN2_SUPPORT_STAGE STAGE30_FULL_EIGEN3_API
#else
#define EIGEN2_SUPPORT_STAGE STAGE99_NO_EIGEN2_SUPPORT
#endif
#ifdef EIGEN2_SUPPORT
#undef minor
#endif
// we use size_t frequently and we'll never remember to prepend it with std:: everytime just to
// ensure QNX/QCC support
using std::size_t;
/** \defgroup Core_Module Core module
* This is the main module of Eigen providing dense matrix and vector support
* (both fixed and dynamic size) with all the features corresponding to a BLAS library
* and much more...
*
* \code
* #include <Eigen/Core>
* \endcode
*/
#include "src/Core/util/Constants.h"
#include "src/Core/util/ForwardDeclarations.h"
#include "src/Core/util/Meta.h"
#include "src/Core/util/XprHelper.h"
#include "src/Core/util/StaticAssert.h"
#include "src/Core/util/Memory.h"
#include "src/Core/NumTraits.h"
#include "src/Core/MathFunctions.h"
#include "src/Core/GenericPacketMath.h"
#if defined EIGEN_VECTORIZE_SSE
#include "src/Core/arch/SSE/PacketMath.h"
#include "src/Core/arch/SSE/MathFunctions.h"
#include "src/Core/arch/SSE/Complex.h"
#elif defined EIGEN_VECTORIZE_ALTIVEC
#include "src/Core/arch/AltiVec/PacketMath.h"
#include "src/Core/arch/AltiVec/Complex.h"
#elif defined EIGEN_VECTORIZE_NEON
#include "src/Core/arch/NEON/PacketMath.h"
#include "src/Core/arch/NEON/Complex.h"
#endif
#include "src/Core/arch/Default/Settings.h"
#include "src/Core/Functors.h"
#include "src/Core/DenseCoeffsBase.h"
#include "src/Core/DenseBase.h"
#include "src/Core/MatrixBase.h"
#include "src/Core/EigenBase.h"
#ifndef EIGEN_PARSED_BY_DOXYGEN // work around Doxygen bug triggered by Assign.h r814874
// at least confirmed with Doxygen 1.5.5 and 1.5.6
#include "src/Core/Assign.h"
#endif
#include "src/Core/util/BlasUtil.h"
#include "src/Core/DenseStorage.h"
#include "src/Core/NestByValue.h"
#include "src/Core/ForceAlignedAccess.h"
#include "src/Core/ReturnByValue.h"
#include "src/Core/NoAlias.h"
#include "src/Core/PlainObjectBase.h"
#include "src/Core/Matrix.h"
#include "src/Core/Array.h"
#include "src/Core/CwiseBinaryOp.h"
#include "src/Core/CwiseUnaryOp.h"
#include "src/Core/CwiseNullaryOp.h"
#include "src/Core/CwiseUnaryView.h"
#include "src/Core/SelfCwiseBinaryOp.h"
#include "src/Core/Dot.h"
#include "src/Core/StableNorm.h"
#include "src/Core/MapBase.h"
#include "src/Core/Stride.h"
#include "src/Core/Map.h"
#include "src/Core/Block.h"
#include "src/Core/VectorBlock.h"
#include "src/Core/Transpose.h"
#include "src/Core/DiagonalMatrix.h"
#include "src/Core/Diagonal.h"
#include "src/Core/DiagonalProduct.h"
#include "src/Core/PermutationMatrix.h"
#include "src/Core/Transpositions.h"
#include "src/Core/Redux.h"
#include "src/Core/Visitor.h"
#include "src/Core/Fuzzy.h"
#include "src/Core/IO.h"
#include "src/Core/Swap.h"
#include "src/Core/CommaInitializer.h"
#include "src/Core/Flagged.h"
#include "src/Core/ProductBase.h"
#include "src/Core/Product.h"
#include "src/Core/TriangularMatrix.h"
#include "src/Core/SelfAdjointView.h"
#include "src/Core/SolveTriangular.h"
#include "src/Core/products/Parallelizer.h"
#include "src/Core/products/CoeffBasedProduct.h"
#include "src/Core/products/GeneralBlockPanelKernel.h"
#include "src/Core/products/GeneralMatrixVector.h"
#include "src/Core/products/GeneralMatrixMatrix.h"
#include "src/Core/products/GeneralMatrixMatrixTriangular.h"
#include "src/Core/products/SelfadjointMatrixVector.h"
#include "src/Core/products/SelfadjointMatrixMatrix.h"
#include "src/Core/products/SelfadjointProduct.h"
#include "src/Core/products/SelfadjointRank2Update.h"
#include "src/Core/products/TriangularMatrixVector.h"
#include "src/Core/products/TriangularMatrixMatrix.h"
#include "src/Core/products/TriangularSolverMatrix.h"
#include "src/Core/products/TriangularSolverVector.h"
#include "src/Core/BandMatrix.h"
#include "src/Core/BooleanRedux.h"
#include "src/Core/Select.h"
#include "src/Core/VectorwiseOp.h"
#include "src/Core/Random.h"
#include "src/Core/Replicate.h"
#include "src/Core/Reverse.h"
#include "src/Core/ArrayBase.h"
#include "src/Core/ArrayWrapper.h"
} // namespace Eigen
#include "src/Core/GlobalFunctions.h"
#include "src/Core/util/ReenableStupidWarnings.h"
#ifdef EIGEN2_SUPPORT
#include "Eigen2Support"
#endif
#endif // EIGEN_CORE_H

7
asift_match/src/third_party/Eigen/Dense vendored Executable file
View file

@ -0,0 +1,7 @@
#include "Core"
#include "LU"
#include "Cholesky"
#include "QR"
#include "SVD"
#include "Geometry"
#include "Eigenvalues"

2
asift_match/src/third_party/Eigen/Eigen vendored Executable file
View file

@ -0,0 +1,2 @@
#include "Dense"
//#include "Sparse"

View file

@ -0,0 +1,82 @@
// This file is part of Eigen, a lightweight C++ template library
// for linear algebra.
//
// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>
//
// Eigen is free software; you can redistribute it and/or
// modify it under the terms of the GNU Lesser General Public
// License as published by the Free Software Foundation; either
// version 3 of the License, or (at your option) any later version.
//
// Alternatively, you can redistribute it and/or
// modify it under the terms of the GNU General Public License as
// published by the Free Software Foundation; either version 2 of
// the License, or (at your option) any later version.
//
// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY
// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the
// GNU General Public License for more details.
//
// You should have received a copy of the GNU Lesser General Public
// License and a copy of the GNU General Public License along with
// Eigen. If not, see <http://www.gnu.org/licenses/>.
#ifndef EIGEN2SUPPORT_H
#define EIGEN2SUPPORT_H
#if (!defined(EIGEN2_SUPPORT)) || (!defined(EIGEN_CORE_H))
#error Eigen2 support must be enabled by defining EIGEN2_SUPPORT before including any Eigen header
#endif
#include "src/Core/util/DisableStupidWarnings.h"
namespace Eigen {
/** \defgroup Eigen2Support_Module Eigen2 support module
* This module provides a couple of deprecated functions improving the compatibility with Eigen2.
*
* To use it, define EIGEN2_SUPPORT before including any Eigen header
* \code
* #define EIGEN2_SUPPORT
* \endcode
*
*/
#include "src/Eigen2Support/Macros.h"
#include "src/Eigen2Support/Memory.h"
#include "src/Eigen2Support/Meta.h"
#include "src/Eigen2Support/Lazy.h"
#include "src/Eigen2Support/Cwise.h"
#include "src/Eigen2Support/CwiseOperators.h"
#include "src/Eigen2Support/TriangularSolver.h"
#include "src/Eigen2Support/Block.h"
#include "src/Eigen2Support/VectorBlock.h"
#include "src/Eigen2Support/Minor.h"
#include "src/Eigen2Support/MathFunctions.h"
} // namespace Eigen
#include "src/Core/util/ReenableStupidWarnings.h"
// Eigen2 used to include iostream
#include<iostream>
#define USING_PART_OF_NAMESPACE_EIGEN \
EIGEN_USING_MATRIX_TYPEDEFS \
using Eigen::Matrix; \
using Eigen::MatrixBase; \
using Eigen::ei_random; \
using Eigen::ei_real; \
using Eigen::ei_imag; \
using Eigen::ei_conj; \
using Eigen::ei_abs; \
using Eigen::ei_abs2; \
using Eigen::ei_sqrt; \
using Eigen::ei_exp; \
using Eigen::ei_log; \
using Eigen::ei_sin; \
using Eigen::ei_cos;
#endif // EIGEN2SUPPORT_H

44
asift_match/src/third_party/Eigen/Eigenvalues vendored Executable file
View file

@ -0,0 +1,44 @@
#ifndef EIGEN_EIGENVALUES_MODULE_H
#define EIGEN_EIGENVALUES_MODULE_H
#include "Core"
#include "src/Core/util/DisableStupidWarnings.h"
#include "Cholesky"
#include "Jacobi"
#include "Householder"
#include "LU"
namespace Eigen {
/** \defgroup Eigenvalues_Module Eigenvalues module
*
*
*
* This module mainly provides various eigenvalue solvers.
* This module also provides some MatrixBase methods, including:
* - MatrixBase::eigenvalues(),
* - MatrixBase::operatorNorm()
*
* \code
* #include <Eigen/Eigenvalues>
* \endcode
*/
#include "src/Eigenvalues/Tridiagonalization.h"
#include "src/Eigenvalues/RealSchur.h"
#include "src/Eigenvalues/EigenSolver.h"
#include "src/Eigenvalues/SelfAdjointEigenSolver.h"
#include "src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h"
#include "src/Eigenvalues/HessenbergDecomposition.h"
#include "src/Eigenvalues/ComplexSchur.h"
#include "src/Eigenvalues/ComplexEigenSolver.h"
#include "src/Eigenvalues/MatrixBaseEigenvalues.h"
} // namespace Eigen
#include "src/Core/util/ReenableStupidWarnings.h"
#endif // EIGEN_EIGENVALUES_MODULE_H
/* vim: set filetype=cpp et sw=2 ts=2 ai: */

Some files were not shown because too many files have changed in this diff Show more