Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
git-svn-id: https://code.astraw.com/kookaburra/trunk/MultiCamSelfCal@1070 e6c0db7a-28da-0310-a2fc-f6ab65d9114a
- Loading branch information
astraw
committed
May 29, 2006
0 parents
commit e3c2155
Showing
167 changed files
with
12,073 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,55 @@ | ||
#!/bin/sh | ||
|
||
# convert the *PVI files from on a local discs and copy only the *.jpg files | ||
|
||
echo "Tool to process PVI sequences, Tomas Svoboda, ETHZ, 07/2002" | ||
|
||
# basepath for the selfcalib codes | ||
selfcalib_basepath=/home/svoboda/Work/BlueCCal/BlueCFindingPoints | ||
|
||
####################################################### | ||
### config definitions | ||
### the variables should be specified in .cshrc | ||
### or something like that | ||
####################################################### | ||
# basepath for binaries and auxiliary scripts | ||
basepath=$BlueC_BASEPATH | ||
# image basename | ||
imname=$BlueC_IMNAME | ||
# machine basename | ||
mname=$BlueC_MNAME | ||
workmachine=$BlueC_WORKMACHINE | ||
# working directory on local machines | ||
localdir=$BlueC_LOCALDIR | ||
# for all available indexes | ||
indexes=$BlueC_INDEXES | ||
|
||
# first clean the old local data | ||
for i in $indexes; do | ||
command="ssh ${mname}${i} rm -f ${localdir}/*.dat*" | ||
echo $command | ||
eval $command | ||
done | ||
|
||
for i in $indexes; do | ||
command="ssh ${mname}${i} rm -f ${localdir}/*.tiff" | ||
echo $command | ||
eval $command | ||
done | ||
|
||
wait | ||
|
||
# call the local finding procedure | ||
for i in $indexes; do | ||
command="ssh ${mname}${i} /usr/sepp/bin/matlab -nosplash -nojvm < ${selfcalib_basepath}/im2pointsLocally.m > ${selfcalib_basepath}/im2pointsLocally.out.${i} &" | ||
|
||
echo $command | ||
eval $command | ||
sleep 1 | ||
done | ||
|
||
wait | ||
|
||
# clean output files | ||
rm im2pointsLocally.out.* | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,144 @@ | ||
% im2pointsLocally computes image statistics from several images | ||
% and finds the projections of laser points | ||
% | ||
% The version for local computation on each machine | ||
% | ||
% The computation core is taken from im2points.m | ||
% computes average image and image of standard deviations | ||
% requires configdata.m | ||
% The name of the experiment has to be specified | ||
% it determines the location of files etc ... | ||
% | ||
% the scripts serves as a template for a multiprocessing | ||
% it assumes a vector of camera IDs CamIds to be known | ||
% indexes in the CamIds are supposed to be correct | ||
% | ||
|
||
donefile = '.done'; | ||
|
||
addpath /home/svoboda/Work/BlueCCal/BlueCFindingPoints | ||
|
||
% config = localconfig('BlueCHoengg') | ||
config = localconfig('BlueCRZ') | ||
|
||
STEP4STAT = 5; % step for computing average and std images, if 1 then all images taken | ||
|
||
im.dir = config.paths.data; | ||
im.ext = config.files.imgext; | ||
|
||
% get the information about machine | ||
machinename = getenv('HOST'); | ||
CamsIds = str2num(machinename(find(machinename>47 & machinename<58))); | ||
|
||
NoCams = size(CamsIds,2); | ||
CamsIds | ||
|
||
% load image names | ||
for i=1:NoCams, | ||
seq(i).camId = CamsIds(i); | ||
if seq(i).camId > -1 | ||
seq(i).data = dir([sprintf(im.dir,seq(i).camId),sprintf(config.files.imnames,seq(i).camId),im.ext]); | ||
[sprintf(im.dir,seq(i).camId),sprintf(config.files.imnames,seq(i).camId),im.ext] | ||
else | ||
seq(i).data = dir([im.dir,sprintf(config.files.imnames),im.ext]); | ||
end | ||
seq(i).size = size(seq(i).data,1); | ||
if seq(i).size<4 | ||
i, seq | ||
error('Not enough images found. Wrong image path or name pattern?'); | ||
end | ||
end | ||
|
||
% Expected number of 3D points is equal to the number of frames. | ||
% In fact, some frames might be without any calibration point | ||
|
||
% Because of non-consistent stopping of capturing, the sequences might | ||
% have different number of images, select the minimal value as the right one | ||
NoPoints = min([seq.size]); | ||
|
||
% compute the average images that will be used for finding LEDs | ||
% if not already computed | ||
|
||
pointsIdx = [1:STEP4STAT:NoPoints]; | ||
|
||
t = cputime; | ||
for i=1:NoCams, | ||
if ~exist(sprintf(config.files.avIM,seq(i).camId)), | ||
disp(sprintf('The average image of the camera %d is being computed',seq(i).camId)); | ||
avIM = zeros(size(imread([sprintf(im.dir,seq(i).camId),seq(i).data(1).name]))); | ||
for j=pointsIdx, | ||
IM = imread([sprintf(im.dir,seq(i).camId),seq(i).data(j).name]); | ||
avIM = avIM + double(IM); | ||
end | ||
avIM = uint8(round(avIM./size(pointsIdx,2))); | ||
imwrite(avIM,sprintf(config.files.avIM,seq(i).camId)); | ||
else disp('Average files already exist'); | ||
end | ||
end | ||
disp(sprintf('Elapsed time for average images: %d [sec]',cputime-t)) | ||
% compute the standard deviations images that will be used for finding LEDs | ||
% if not already computed | ||
t = cputime; | ||
for i=1:NoCams, | ||
if ~exist(sprintf(config.files.stdIM,seq(i).camId)), | ||
avIM = double(imread(sprintf(config.files.avIM,seq(i).camId))); | ||
disp(sprintf('The image of standard deviations of the camera %d is being computed',seq(i).camId)); | ||
stdIM = zeros(size(imread([sprintf(im.dir,seq(i).camId),seq(i).data(1).name]))); | ||
for j=pointsIdx, | ||
IM = imread([sprintf(im.dir,seq(i).camId),seq(i).data(j).name]); | ||
stdIM = stdIM + (double(IM)-avIM).^2; | ||
end | ||
stdIM = uint8(round(sqrt(stdIM./(size(pointsIdx,2)-1)))); | ||
imwrite(stdIM,sprintf(config.files.stdIM,seq(i).camId)); | ||
else | ||
disp('Image of standard deviations already exist') | ||
end | ||
end | ||
disp(sprintf('Elapsed time for computation of images [sec]: %d',cputime-t)) | ||
|
||
% find points in the images | ||
Ws = []; | ||
IdWs = []; | ||
Res = []; | ||
|
||
IdMat = ones(NoCams,NoPoints); | ||
% IdMat is very important for Martinec&Pajdla filling [ECCV2002] | ||
% it is a NoCams x NoPoints matrix, | ||
% IdMat(i,j) = 0 -> no j-th point in i-th | ||
% IdMat(i,j) = 1 -> point successfully detected | ||
|
||
for i=1:NoCams, | ||
Points = []; | ||
avIM = imread(sprintf(config.files.avIM,seq(i).camId)); | ||
stdIM = imread(sprintf(config.files.stdIM,seq(i).camId)); | ||
for j=1:NoPoints, | ||
[pos,err] = getpoint([sprintf(im.dir,seq(i).camId),seq(i).data(j).name], 0, config.imgs, avIM, stdIM); | ||
if err | ||
IdMat(i,j) = 0; | ||
Points = [Points, [NaN; NaN; NaN]]; | ||
else | ||
Points = [Points, [pos; 1]]; | ||
end | ||
end | ||
Ws = [Ws; Points]; | ||
Res= [Res; size(avIM,2), size(avIM,1)]; | ||
end | ||
|
||
idx = '.'; | ||
for i=CamsIds, | ||
idx = sprintf('%s%02d',idx,i); | ||
end | ||
|
||
save([config.files.points,idx], 'Ws','-ASCII') | ||
% save(config.files.IdPoints,'IdWs','-ASCII') | ||
save([config.files.Res,idx], 'Res', '-ASCII') | ||
save([config.files.IdMat,idx], 'IdMat', '-ASCII') | ||
|
||
% write auxiliary file that is done | ||
done=1; | ||
save(donefile,'done','-ascii'); | ||
|
||
% exit the Matlab | ||
% this script is to be used in the batch mode | ||
% hence exit at the end is necessary | ||
exit; |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,73 @@ | ||
% LocalConfig configuration file for self-calibration experiments | ||
% | ||
% | ||
% config = configdata(experiment) | ||
% | ||
% experiment ... string with an experiment name | ||
|
||
function config = configdata(experiment) | ||
|
||
HOME_PATH = '/home/svoboda/Work/BlueCCal/'; | ||
|
||
% add paths | ||
addpath([HOME_PATH,'MultiCamSelfCal/FindingPoints']); | ||
addpath([HOME_PATH,'BlueCFindingPoints']); | ||
|
||
|
||
if nargin<1, | ||
display('No name of the experiment specified: >>basic<< used as default') | ||
experiment = 'basic'; | ||
end | ||
|
||
if strcmp(experiment,'basic') | ||
error; | ||
elseif strcmp(experiment,'BlueCHoengg') | ||
config.paths.data = '/local/tomas/'; | ||
config.paths.img = config.paths.data; | ||
config.files.imnames = 'arctic%d.pvi.*.'; | ||
config.files.idxcams = [1:16]; % related to the imnames | ||
config.files.imgext = 'jpg'; | ||
config.imgs.LEDsize = 7; % avg diameter of a LED in pixels | ||
config.imgs.LEDcolor = 'green'; % color of the laser pointer | ||
config.imgs.subpix = 1/5; | ||
elseif strcmp(experiment,'BlueCRZ') | ||
config.paths.data = '/local/tomas/'; | ||
config.paths.img = config.paths.data; | ||
config.files.imnames = 'atlantic%d.pvi.*.'; | ||
config.files.idxcams = [3:12,14:18]; % related to the imnames | ||
config.files.imgext = 'jpg'; | ||
config.imgs.LEDsize = 7; % avg diameter of a LED in pixels | ||
config.imgs.LEDcolor = 'green'; % color of the laser pointer | ||
config.imgs.subpix = 1/5; | ||
else | ||
error('Configdata: wrong identifier of the data set'); | ||
end | ||
|
||
|
||
% image resolution | ||
try config.imgs.res; catch, config.imgs.res = [640,480]; end; | ||
|
||
% scale for the subpixel accuracy | ||
% 1/3 is a good compromise between speed and accuracy | ||
% for high-resolution images or bigger LEDs you may try 1/1 or 1/2 | ||
try config.imgs.subpix; catch, config.imgs.subpix = 1/3; end; | ||
|
||
% data names | ||
try config.files.Pmats; catch, config.files.Pmats = [config.paths.data,'Pmatrices.dat']; end; | ||
try config.files.points; catch, config.files.points = [config.paths.data,'points.dat']; end; | ||
try config.files.IdPoints; catch, config.files.IdPoints = [config.paths.data,'IdPoints.dat']; end; | ||
try config.files.Res; catch, config.files.Res = [config.paths.data,'Res.dat']; end; | ||
try config.files.IdMat; catch, config.files.IdMat = [config.paths.data,'IdMat.dat']; end; | ||
try config.files.inidx; catch, config.files.inidx = [config.paths.data,'idxin.dat']; end; | ||
try config.files.avIM; catch, config.files.avIM = [config.paths.data,'camera%d.average.tiff']; end; | ||
try config.files.stdIM; catch, config.files.stdIM = [config.paths.data,'camera%d.std.tiff']; end; | ||
try config.files.CalPar; catch, config.files.CalPar = [config.paths.data,'camera%d.cal']; end; | ||
try config.files.CalPmat; catch, config.files.CalPmat = [config.paths.data,'camera%d.Pmat.cal']; end; | ||
try config.files.StCalPar; catch, config.files.StCalPar = [config.paths.data,'atlantic%d.ethz.ch.cal']; end; | ||
|
||
|
||
|
||
|
||
|
||
|
||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,3 @@ | ||
Source codes by courtesy of Jean-Yves Bouguet at jean-yves.bouguet@intel.com | ||
|
||
http://www.vision.caltech.edu/bouguetj/calib_doc/ |
Oops, something went wrong.