Skip to content

Commit

Permalink
Init commit
Browse files Browse the repository at this point in the history
  • Loading branch information
raviBhadeshiya committed May 7, 2017
1 parent 3f32c70 commit 7bb88bb
Show file tree
Hide file tree
Showing 12 changed files with 432 additions and 18 deletions.
21 changes: 3 additions & 18 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1,19 +1,4 @@
# Build and Release Folders
# Data Folders
bin/
bin-debug/
bin-release/
[Oo]bj/ # FlashDevelop obj
[Bb]in/ # FlashDevelop bin

# Other files and folders
.settings/

# Executables
*.swf
*.air
*.ipa
*.apk

# Project files, i.e. `.project`, `.actionScriptProperties` and `.flexProperties`
# should NOT be excluded as they contain compiler settings and other important
# information for Eclipse / Flash Builder.
CarTracking/input/
VisualOdometry/input/
89 changes: 89 additions & 0 deletions CarTracking/code/main.asv
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
clear all; close all; clc;

%%
cd ../input;
videoFReader = vision.VideoFileReader('challenge.avi');
carDetector=vision.CascadeObjectDetector('cars.xml');
cd ../code;

%%
carDetector.MergeThreshold=1;
% carDetector.MinSize=[50 50];
carDetector.MinSize=[100 100];
videoFrame=videoFReader();
videoFrame(1:240,:,:)=0;
boundingBox=step(carDetector, videoFrame);
carAnotate=insertObjectAnnotation(videoFrame, 'rectangle', boundingBox, 'Car');
imshow(carAnotate);

%%
videoPlayer = vision.VideoPlayer('Position',...
[100 100 [size(videoFrame, 2), size(videoFrame, 1)]+30]);

%%
for i=1:size(boundingBox,1)

pointTracker{i} = vision.PointTracker('MaxBidirectionalError',2);
points = detectSURFFeatures(rgb2gray(videoFrame),'ROI', boundingBox(i,:), 'MetricThreshold', 300, 'NumOctaves', 20);

% points = detectHarrisFeatures(rgb2gray(videoFrame),'ROI', boundingBox(i,:), 'MinQuality', 0.00005);
% points = detectMSERFeatures(rgb2gray(videoFrame),'ROI', boundingBox(i,:),'MaxAreaVariation',0.8);
% points = detectBRISKFeatures(rgb2gray(videoFrame),'ROI', boundingBox(i,:));

initialize(pointTracker{i},points.Location,videoFrame);
bboxPoints{i} = bbox2points(boundingBox(i,:));

pointsStruct{i} = points.Location;
oldPoints{i} = pointsStruct{i};
end

%%
while ~isDone(videoFReader)
% get the next frame
videoFrame = step(videoFReader);
visiblePointsList=[];
oldInliers=[];
% Track the points. Note that some points may be lost.
for j=1:length(pointTracker)

[points, isFound] = step(pointTracker{j}, videoFrame);
visiblePoints{j} = points(isFound, :);
visiblePointsList = [visiblePointsList; visiblePoints{j}];
oldInliers = [oldInliers; oldPoints{j}(isFound, :)];

end
% if size(visiblePoints{j}, 1) >= 2 % need at least 2 points

% Estimate the geometric transformation between the old points
% and the new points and eliminate outliers
[xform, oldInliers, visiblePointsList] = estimateGeometricTransform(...
oldInliers, visiblePointsList, 'similarity', 'MaxDistance', 1);
for j=1:length(pointTracker)
% Apply the transformation to the bounding box points
bboxPoints{j} = transformPointsForward(xform, bboxPoints{j});

% Insert a bounding box around the object being tracked
bboxPolygon = reshape(bboxPoints{j}', 1, []);
videoFrame = insertShape(videoFrame, 'Polygon', bboxPolygon, ...
'LineWidth', 2, 'Color', [255 255*(j-1) 255*(j-2)]);

% Display tracked points
videoFrame = insertMarker(videoFrame, visiblePoints{j}, '+', ...
'Color', 'white');
% Reset the points
oldPoints{j} = visiblePoints{j};
setPoints(pointTracker{j}, oldPoints{j});
end

% Display the annotated video frame using the video player object
step(videoPlayer, videoFrame);
end



% Clean up
release(videoFReader);
release(videoPlayer);
for i=1:length(pointTracker)
release(pointTracker{i});
end
88 changes: 88 additions & 0 deletions CarTracking/code/main.m
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
clear all; close all; clc;

%%
cd ../input;
videoFReader = vision.VideoFileReader('simple.avi');
carDetector=vision.CascadeObjectDetector('cars.xml');
cd ../code;

%%
carDetector.MergeThreshold=1;
carDetector.MinSize=[50 50];
videoFrame=videoFReader();
videoFrame(1:240,:,:)=0;
boundingBox=step(carDetector, videoFrame);
carAnotate=insertObjectAnnotation(videoFrame, 'rectangle', boundingBox, 'Car');
imshow(carAnotate);

%%
videoPlayer = vision.VideoPlayer('Position',...
[100 100 [size(videoFrame, 2), size(videoFrame, 1)]+30]);

%%
for i=1:size(boundingBox,1)

pointTracker{i} = vision.PointTracker('MaxBidirectionalError',2);
points = detectSURFFeatures(rgb2gray(videoFrame),'ROI', boundingBox(i,:), 'MetricThreshold', 300, 'NumOctaves', 20);

% points = detectHarrisFeatures(rgb2gray(videoFrame),'ROI', boundingBox(i,:), 'MinQuality', 0.00005);
% points = detectMSERFeatures(rgb2gray(videoFrame),'ROI', boundingBox(i,:),'MaxAreaVariation',0.8);
% points = detectBRISKFeatures(rgb2gray(videoFrame),'ROI', boundingBox(i,:));

initialize(pointTracker{i},points.Location,videoFrame);
bboxPoints{i} = bbox2points(boundingBox(i,:));

pointsStruct{i} = points.Location;
oldPoints{i} = pointsStruct{i};
end

%%
while ~isDone(videoFReader)
% get the next frame
videoFrame = step(videoFReader);
visiblePointsList=[];
oldInliers=[];
% Track the points. Note that some points may be lost.
for j=1:length(pointTracker)

[points, isFound] = step(pointTracker{j}, videoFrame);
visiblePoints{j} = points(isFound, :);
visiblePointsList = [visiblePointsList; visiblePoints{j}];
oldInliers = [oldInliers; oldPoints{j}(isFound, :)];

end
% if size(visiblePoints{j}, 1) >= 2 % need at least 2 points

% Estimate the geometric transformation between the old points
% and the new points and eliminate outliers
[xform, oldInliers, visiblePointsList] = estimateGeometricTransform(...
oldInliers, visiblePointsList, 'similarity', 'MaxDistance', 1);
for j=1:length(pointTracker)
% Apply the transformation to the bounding box points
bboxPoints{j} = transformPointsForward(xform, bboxPoints{j});

% Insert a bounding box around the object being tracked
bboxPolygon = reshape(bboxPoints{j}', 1, []);
videoFrame = insertShape(videoFrame, 'Polygon', bboxPolygon, ...
'LineWidth', 2, 'Color', [255 255*(j-1) 255*(j-2)]);

% Display tracked points
videoFrame = insertMarker(videoFrame, visiblePoints{j}, '+', ...
'Color', 'white');
% Reset the points
oldPoints{j} = visiblePoints{j};
setPoints(pointTracker{j}, oldPoints{j});
end

% Display the annotated video frame using the video player object
step(videoPlayer, videoFrame);
end



% Clean up
release(videoFReader);
release(videoPlayer);
for i=1:length(pointTracker)
release(pointTracker{i});
end
Binary file added VisualOdometry/ENPM673 - Project3_Part2.pdf
Binary file not shown.
16 changes: 16 additions & 0 deletions VisualOdometry/code/EssentialMatrixFromFundamentalMatrix.m
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
function E = EssentialMatrixFromFundamentalMatrix(F,K)
% EssentialMatrixFromFundamentalMatrix
% Use the camera calibration matrix to esimate the Essential matrix
% Inputs:
% K - size (3 x 3) camera calibration (intrinsics) matrix for both
% cameras
% F - size (3 x 3) fundamental matrix from EstimateFundamentalMatrix
% Outputs:
% E - size (3 x 3) Essential matrix with singular values (1,1,0)
E=K'*F*K;
[u d v]=svd(E);
i=eye(3);
i(3,3)=0;
E=u*i*v';
E=E/norm(E);
end
30 changes: 30 additions & 0 deletions VisualOdometry/code/EstimateFundamentalMatrix.m
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@

function F = EstimateFundamentalMatrix(x1, x2)


% EstimateFundamentalMatrix
% Estimate the fundamental matrix from two image point correspondences
% Inputs:
% x1 - size (N x 2) matrix of points in image 1
% x2 - size (N x 2) matrix of points in image 2, each row corresponding
% to x1
% Output:
% F - size (3 x 3) fundamental matrix with rank 2

F=[];
A=[];
for i=1:size(x1,1)
a=[x1(i,1)*x2(i,1) x1(i,1)*x2(i,2) x1(i,1) x1(i,2)*x2(i,1) x1(i,2)*x2(i,2) x1(i,2) x2(i,1) x2(i,2) 1];
A=[A;a];
end

[U,S,V] = svd(A);
F=V(:,end);
F=F';
F=[F(1) F(2) F(3);F(4) F(5) F(6);F(7) F(8) F(9)]; %or reshape(F,3,3);
%rank clean up to 2
[u d v]=svd(F);
d(3,3)=0;
F=u*d*v';
F=F/norm(F);
end
99 changes: 99 additions & 0 deletions VisualOdometry/code/ReadCameraModel.m
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
function [fx, fy, cx, cy, G_camera_image, LUT] = ReadCameraModel(image_dir, models_dir)

% ReadCameraModel - load camera intrisics and undistortion LUT from disk
%
% [fx, fy, cx, cy, G_camera_image, LUT] = ReadCameraModel(image_dir, models_dir)
%
% INPUTS:
% image_dir: directory containing images for which camera model is required
% models_dir: directory containing camera models
%
% OUTPUTS:
% fx: horizontal focal length in pixels
% fy: vertical focal length in pixels
% cx: horizontal principal point in pixels
% cy: vertical principal point in pixels
% G_camera_image: transform that maps from image coordinates to the base
% frame of the camera. For monocular cameras, this is simply a rotation.
% For stereo camera, this is a rotation and a translation to the left-most
% lense.
% LUT: undistortion lookup table. For an image of size w x h, LUT will be an
% array of size [w x h, 2], with a (u,v) pair for each pixel. Maps pixels
% in the undistorted image to pixels in the distorted image

%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%
% Copyright (c) 2016 University of Oxford
% Authors:
% Geoff Pascoe (gmp@robots.ox.ac.uk)
% Will Maddern (wm@robots.ox.ac.uk)
%
% This work is licensed under the Creative Commons
% Attribution-NonCommercial-ShareAlike 4.0 International License.
% To view a copy of this license, visit
% http://creativecommons.org/licenses/by-nc-sa/4.0/ or send a letter to
% Creative Commons, PO Box 1866, Mountain View, CA 94042, USA.
%
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%

if models_dir(end) ~= '/'
models_dir = [models_dir '/'];
end

camera = regexp(image_dir, '(stereo|mono_left|mono_right|mono_rear)', ...
'match');
camera = camera{end};

if strcmp(camera, 'stereo')
sensor = regexp(image_dir, '(left|centre|right)', 'match');
sensor = sensor{end};

if strcmp(sensor, 'left')
model = 'wide_left';
elseif strcmp(sensor, 'right')
model = 'wide_right'; % narrow_right also applies to this sensor
elseif strcmp(sensor, 'centre')
model = 'narrow_left';
else
error('Unknown camera model for given directory');
end

intrinsics_path = [models_dir camera '_' model '.txt'];
lut_path = [models_dir camera '_' model '_distortion_lut.bin'];

else
intrinsics_path = [models_dir camera '.txt'];
lut_path = [models_dir camera '_distortion_lut.bin'];
end

if ~exist(intrinsics_path, 'file')
error(['Camera intrinsics not found at ' intrinsics_path]);
end
intrinsics = dlmread(intrinsics_path);

% First line of intrinsics file: fx fy cx xy
fx = intrinsics(1, 1);
fy = intrinsics(1, 2);
cx = intrinsics(1, 3);
cy = intrinsics(1, 4);

% Lines 2-5 of intrinsics file: 4x4 matrix that transforms between
% x-forward coordinate frame at camera origin, and image frame for
% the specific lense
G_camera_image = intrinsics(2:5, 1:4);

if nargout > 5
if ~exist(lut_path, 'file') == -1
error(['Distortion LUT not found at ' lut_path]);
end
lut_file = fopen(lut_path);
LUT = fread(lut_file, 'double');
fclose(lut_file);

% LUT consists of a (u,v) pair for each pixel
LUT = reshape(LUT, [numel(LUT)/2, 2]);
end

disp(intrinsics_path)

end
Loading

0 comments on commit 7bb88bb

Please sign in to comment.