-
Notifications
You must be signed in to change notification settings - Fork 0
/
monovslams.m
482 lines (372 loc) · 18 KB
/
monovslams.m
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
obj = VideoReader('test.mp4');
dataFolder = fullfile(tempdir, 'img', filesep);
folderExists = exist(dataFolder, 'dir');
if ~folderExists
mkdir(dataFolder);
for frame = 1 : obj.NumFrames
% Extract the frame from the movie structure.
thisFrame = read(obj, frame);
outputBaseFileName = sprintf('Frame %4.4d.png', frame);
outputFullFileName = fullfile(dataFolder, outputBaseFileName);
imwrite(thisFrame, outputFullFileName, 'png');
end
end
%while hasFrame(obj)
% frame = readFrame(obj);
%grayscale=rgb2gray(frame)
%end
currFrameIdx = 1;
currI = read(obj,currFrameIdx);
himage = imshow(currI);
focalLength = [535.4, 539.2];
principalPoint = [320.1, 247.6];
imageSize = size(currI,[1 2]);
intrinsics = cameraIntrinsics(focalLength, principalPoint, imageSize);
scaleFactor = 1.2;
numLevels = 8;
[preFeatures, prePoints] = helperDetectAndExtractFeatures(currI, scaleFactor, numLevels);
currFrameIdx = currFrameIdx + 1;
firstI = currI; % Preserve the first frame
isMapInitialized = false;
% Map initialization loop
while ~isMapInitialized && currFrameIdx < obj.NumFrames
currI = read(obj,currFrameIdx);
[currFeatures, currPoints] = helperDetectAndExtractFeatures(currI, scaleFactor, numLevels);
currFrameIdx = currFrameIdx + 1;
% Find putative feature matches
indexPairs = matchFeatures(preFeatures, currFeatures, 'Unique', true, ...
'MaxRatio', 0.9, 'MatchThreshold', 40);
preMatchedPoints = prePoints(indexPairs(:,1),:);
currMatchedPoints = currPoints(indexPairs(:,2),:);
% If not enough matches are found, check the next frame
minMatches = 100;
if size(indexPairs, 1) < minMatches
continue
end
preMatchedPoints = prePoints(indexPairs(:,1),:);
currMatchedPoints = currPoints(indexPairs(:,2),:);
% Compute homography and evaluate reconstruction
[tformH, scoreH, inliersIdxH] = helperComputeHomography(preMatchedPoints, currMatchedPoints);
% Compute fundamental matrix and evaluate reconstruction
[tformF, scoreF, inliersIdxF] = helperComputeFundamentalMatrix(preMatchedPoints, currMatchedPoints);
% Select the model based on a heuristic
ratio = scoreH/(scoreH + scoreF);
ratioThreshold = 0.45;
if ratio > ratioThreshold
inlierTformIdx = inliersIdxH;
tform = tformH;
else
inlierTformIdx = inliersIdxF;
tform = tformF;
end
% Computes the camera location up to scale. Use half of the
% points to reduce computation
inlierPrePoints = preMatchedPoints(inlierTformIdx);
inlierCurrPoints = currMatchedPoints(inlierTformIdx);
[relOrient, relLoc, validFraction] = relativeCameraPose(tform, intrinsics, ...
inlierPrePoints(1:2:end), inlierCurrPoints(1:2:end));
% If not enough inliers are found, move to the next frame
if validFraction < 0.9 || numel(size(relOrient))==3
continue
end
% Triangulate two views to obtain 3-D map points
relPose = rigid3d(relOrient, relLoc);
minParallax = 1; % In degrees
[isValid, xyzWorldPoints, inlierTriangulationIdx] = helperTriangulateTwoFrames(...
rigid3d, relPose, inlierPrePoints, inlierCurrPoints, intrinsics, minParallax);
if ~isValid
continue
end
% Get the original index of features in the two key frames
indexPairs = indexPairs(inlierTformIdx(inlierTriangulationIdx),:);
isMapInitialized = true;
disp(['Map initialized with frame 1 and frame ', num2str(currFrameIdx-1)])
end % End of map initialization loop
if isMapInitialized
close(himage.Parent.Parent); % Close the previous figure
% Show matched features
hfeature = showMatchedFeatures(firstI, currI, prePoints(indexPairs(:,1)), ...
currPoints(indexPairs(:, 2)), 'Montage');
else
error('Unable to initialize map.')
end
% Create an empty imageviewset object to store key frames
vSetKeyFrames = imageviewset;
% Create an empty worldpointset object to store 3-D map points
mapPointSet = worldpointset;
% Create a helperViewDirectionAndDepth object to store view direction and depth
directionAndDepth = helperViewDirectionAndDepth(size(xyzWorldPoints, 1));
% Add the first key frame. Place the camera associated with the first
% key frame at the origin, oriented along the Z-axis
preViewId = 1;
vSetKeyFrames = addView(vSetKeyFrames, preViewId, rigid3d, 'Points', prePoints,...
'Features', preFeatures.Features);
% Add the second key frame
currViewId = 2;
vSetKeyFrames = addView(vSetKeyFrames, currViewId, relPose, 'Points', currPoints,...
'Features', currFeatures.Features);
% Add connection between the first and the second key frame
vSetKeyFrames = addConnection(vSetKeyFrames, preViewId, currViewId, relPose, 'Matches', indexPairs);
% Add 3-D map points
[mapPointSet, newPointIdx] = addWorldPoints(mapPointSet, xyzWorldPoints);
% Add observations of the map points
preLocations = prePoints.Location;
currLocations = currPoints.Location;
preScales = prePoints.Scale;
currScales = currPoints.Scale;
% Add image points corresponding to the map points in the first key frame
mapPointSet = addCorrespondences(mapPointSet, preViewId, newPointIdx, indexPairs(:,1));
% Add image points corresponding to the map points in the second key frame
mapPointSet = addCorrespondences(mapPointSet, currViewId, newPointIdx, indexPairs(:,2));
% Run full bundle adjustment on the first two key frames
tracks = findTracks(vSetKeyFrames);
cameraPoses = poses(vSetKeyFrames);
[refinedPoints, refinedAbsPoses] = bundleAdjustment(xyzWorldPoints, tracks, ...
cameraPoses, intrinsics, 'FixedViewIDs', 1, ...
'PointsUndistorted', true, 'AbsoluteTolerance', 1e-7,...
'RelativeTolerance', 1e-15, 'MaxIteration', 50);
% Scale the map and the camera pose using the median depth of map points
medianDepth = median(vecnorm(refinedPoints.'));
refinedPoints = refinedPoints / medianDepth;
refinedAbsPoses.AbsolutePose(currViewId).Translation = ...
refinedAbsPoses.AbsolutePose(currViewId).Translation / medianDepth;
relPose.Translation = relPose.Translation/medianDepth;
% Update key frames with the refined poses
vSetKeyFrames = updateView(vSetKeyFrames, refinedAbsPoses);
vSetKeyFrames = updateConnection(vSetKeyFrames, preViewId, currViewId, relPose);
% Update map points with the refined positions
mapPointSet = updateWorldPoints(mapPointSet, newPointIdx, refinedPoints);
% Update view direction and depth
directionAndDepth = update(directionAndDepth, mapPointSet, vSetKeyFrames.Views, newPointIdx, true);
% Visualize matched features in the current frame
close(hfeature.Parent.Parent);
featurePlot = helperVisualizeMatchedFeatures(currI, currPoints(indexPairs(:,2)));
% Visualize initial map points and camera trajectory
mapPlot = helperVisualizeMotionAndStructure(vSetKeyFrames, mapPointSet);
% Show legend
showLegend(mapPlot);
% ViewId of the current key frame
currKeyFrameId = currViewId;
% ViewId of the last key frame
lastKeyFrameId = currViewId;
% ViewId of the reference key frame that has the most co-visible
% map points with the current key frame
refKeyFrameId = currViewId;
% Index of the last key frame in the input image sequence
lastKeyFrameIdx = currFrameIdx - 1;
% Indices of all the key frames in the input image sequence
addedFramesIdx = [1; lastKeyFrameIdx];
isLoopClosed = false;
% Main loop
while ~isLoopClosed && currFrameIdx < obj.NumFrames
currI = read(obj, currFrameIdx);
[currFeatures, currPoints] = helperDetectAndExtractFeatures(currI, scaleFactor, numLevels);
% Track the last key frame
% mapPointsIdx: Indices of the map points observed in the current frame
% featureIdx: Indices of the corresponding feature points in the
% current frame
[currPose, mapPointsIdx, featureIdx] = helperTrackLastKeyFrame(mapPointSet, ...
vSetKeyFrames.Views, currFeatures, currPoints, lastKeyFrameId, intrinsics, scaleFactor);
% Track the local map
% refKeyFrameId: ViewId of the reference key frame that has the most
% co-visible map points with the current frame
% localKeyFrameIds: ViewId of the connected key frames of the current frame
[refKeyFrameId, localKeyFrameIds, currPose, mapPointsIdx, featureIdx] = ...
helperTrackLocalMap(mapPointSet, directionAndDepth, vSetKeyFrames, mapPointsIdx, ...
featureIdx, currPose, currFeatures, currPoints, intrinsics, scaleFactor, numLevels);
% Check if the current frame is a key frame.
% A frame is a key frame if both of the following conditions are satisfied:
%
% 1. At least 20 frames have passed since the last key frame or the
% current frame tracks fewer than 100 map points
% 2. The map points tracked by the current frame are fewer than 90% of
% points tracked by the reference key frame
isKeyFrame = helperIsKeyFrame(mapPointSet, refKeyFrameId, lastKeyFrameIdx, ...
currFrameIdx, mapPointsIdx);
% Visualize matched features
updatePlot(featurePlot, currI, currPoints(featureIdx));
if ~isKeyFrame
currFrameIdx = currFrameIdx + 1;
continue
end
% Update current key frame ID
currKeyFrameId = currKeyFrameId + 1;
% Add the new key frame
[mapPointSet, vSetKeyFrames] = helperAddNewKeyFrame(mapPointSet, vSetKeyFrames, ...
currPose, currFeatures, currPoints, mapPointsIdx, featureIdx, localKeyFrameIds);
% Remove outlier map points that are observed in fewer than 3 key frames
[mapPointSet, directionAndDepth, mapPointsIdx] = helperCullRecentMapPoints(mapPointSet, ...
directionAndDepth, mapPointsIdx, newPointIdx);
% Create new map points by triangulation
minNumMatches = 20;
minParallax = 3;
[mapPointSet, vSetKeyFrames, newPointIdx] = helperCreateNewMapPoints(mapPointSet, vSetKeyFrames, ...
currKeyFrameId, intrinsics, scaleFactor, minNumMatches, minParallax);
% Update view direction and depth
directionAndDepth = update(directionAndDepth, mapPointSet, vSetKeyFrames.Views, ...
[mapPointsIdx; newPointIdx], true);
% Local bundle adjustment
[mapPointSet, directionAndDepth, vSetKeyFrames, newPointIdx] = helperLocalBundleAdjustment( ...
mapPointSet, directionAndDepth, vSetKeyFrames, ...
currKeyFrameId, intrinsics, newPointIdx);
% Visualize 3D world points and camera trajectory
updatePlot(mapPlot, vSetKeyFrames, mapPointSet);
% Initialize the loop closure database
if currKeyFrameId == 3
% Load the bag of features data created offline
bofData = load('bagOfFeaturesData.mat');
% Initialize the place recognition database
loopCandidates = [1; 2];
loopDatabase = indexImages(subset(imds, loopCandidates), bofData.bof);
% Check loop closure after some key frames have been created
elseif currKeyFrameId > 20
% Minimum number of feature matches of loop edges
loopEdgeNumMatches = 50;
% Detect possible loop closure key frame candidates
[isDetected, validLoopCandidates] = helperCheckLoopClosure(vSetKeyFrames, currKeyFrameId, ...
loopDatabase, currI, loopCandidates, loopEdgeNumMatches);
if isDetected
% Add loop closure connections
[isLoopClosed, mapPointSet, vSetKeyFrames] = helperAddLoopConnections(...
mapPointSet, vSetKeyFrames, validLoopCandidates, currKeyFrameId, ...
currFeatures, currPoints, loopEdgeNumMatches);
end
end
% If no loop closure is detected, add the image into the database
if ~isLoopClosed
addImages(loopDatabase, subset(imds, currFrameIdx), 'Verbose', false);
loopCandidates= [loopCandidates; currKeyFrameId]; %#ok<AGROW>
end
% Update IDs and indices
lastKeyFrameId = currKeyFrameId;
lastKeyFrameIdx = currFrameIdx;
addedFramesIdx = [addedFramesIdx; currFrameIdx]; %#ok<AGROW>
currFrameIdx = currFrameIdx + 1;
end % End of main loop
% Optimize the poses
minNumMatches = 30;
[vSetKeyFramesOptim, poseScales] = optimizePoses(vSetKeyFrames, minNumMatches, 'Tolerance', 1e-16);
% Update map points after optimizing the poses
mapPointSet = helperUpdateGlobalMap(mapPointSet, directionAndDepth, ...
vSetKeyFrames, vSetKeyFramesOptim, poseScales);
updatePlot(mapPlot, vSetKeyFrames, mapPointSet);
% Plot the optimized camera trajectory
optimizedPoses = poses(vSetKeyFramesOptim);
plotOptimizedTrajectory(mapPlot, optimizedPoses)
% Update legend
showLegend(mapPlot);
showLegend(mapPlot);
%Functions
function [features, validPoints] = helperDetectAndExtractFeatures(Irgb, ...
scaleFactor, numLevels, varargin)
numPoints = 1000;
% In this example, the images are already undistorted. In a general
% workflow, uncomment the following code to undistort the images.
%
% if nargin > 3
% intrinsics = varargin{1};
% end
% Irgb = undistortImage(Irgb, intrinsics);
% Detect ORB features
Igray = im2gray(Irgb);
points = detectORBFeatures(Igray, 'ScaleFactor', scaleFactor, 'NumLevels', numLevels);
% Select a subset of features, uniformly distributed throughout the image
points = selectUniform(points, numPoints, size(Igray, 1:2));
% Extract features
[features, validPoints] = extractFeatures(Igray, points);
end
function [H, score, inliersIndex] = helperComputeHomography(matchedPoints1, matchedPoints2)
[H, inliersLogicalIndex] = estimateGeometricTransform2D( ...
matchedPoints1, matchedPoints2, 'projective', ...
'MaxNumTrials', 1e3, 'MaxDistance', 4, 'Confidence', 90);
inlierPoints1 = matchedPoints1(inliersLogicalIndex);
inlierPoints2 = matchedPoints2(inliersLogicalIndex);
inliersIndex = find(inliersLogicalIndex);
locations1 = inlierPoints1.Location;
locations2 = inlierPoints2.Location;
xy1In2 = transformPointsForward(H, locations1);
xy2In1 = transformPointsInverse(H, locations2);
error1in2 = sum((locations2 - xy1In2).^2, 2);
error2in1 = sum((locations1 - xy2In1).^2, 2);
outlierThreshold = 6;
score = sum(max(outlierThreshold-error1in2, 0)) + ...
sum(max(outlierThreshold-error2in1, 0));
end
function [F, score, inliersIndex] = helperComputeFundamentalMatrix(matchedPoints1, matchedPoints2)
[F, inliersLogicalIndex] = estimateFundamentalMatrix( ...
matchedPoints1, matchedPoints2, 'Method','RANSAC',...
'NumTrials', 1e3, 'DistanceThreshold', 0.01);
inlierPoints1 = matchedPoints1(inliersLogicalIndex);
inlierPoints2 = matchedPoints2(inliersLogicalIndex);
inliersIndex = find(inliersLogicalIndex);
locations1 = inlierPoints1.Location;
locations2 = inlierPoints2.Location;
% Distance from points to epipolar line
lineIn1 = epipolarLine(F', locations2);
error2in1 = (sum([locations1, ones(size(locations1, 1),1)].* lineIn1, 2)).^2 ...
./ sum(lineIn1(:,1:2).^2, 2);
lineIn2 = epipolarLine(F, locations1);
error1in2 = (sum([locations2, ones(size(locations2, 1),1)].* lineIn2, 2)).^2 ...
./ sum(lineIn2(:,1:2).^2, 2);
outlierThreshold = 4;
score = sum(max(outlierThreshold-error1in2, 0)) + ...
sum(max(outlierThreshold-error2in1, 0));
end
function [isValid, xyzPoints, inlierIdx] = helperTriangulateTwoFrames(...
pose1, pose2, matchedPoints1, matchedPoints2, intrinsics, minParallax)
[R1, t1] = cameraPoseToExtrinsics(pose1.Rotation, pose1.Translation);
camMatrix1 = cameraMatrix(intrinsics, R1, t1);
[R2, t2] = cameraPoseToExtrinsics(pose2.Rotation, pose2.Translation);
camMatrix2 = cameraMatrix(intrinsics, R2, t2);
[xyzPoints, reprojectionErrors, isInFront] = triangulate(matchedPoints1, ...
matchedPoints2, camMatrix1, camMatrix2);
% Filter points by view direction and reprojection error
minReprojError = 1;
inlierIdx = isInFront & reprojectionErrors < minReprojError;
xyzPoints = xyzPoints(inlierIdx ,:);
% A good two-view with significant parallax
ray1 = xyzPoints - pose1.Translation;
ray2 = xyzPoints - pose2.Translation;
cosAngle = sum(ray1 .* ray2, 2) ./ (vecnorm(ray1, 2, 2) .* vecnorm(ray2, 2, 2));
% Check parallax
isValid = all(cosAngle < cosd(minParallax) & cosAngle>0);
end
function isKeyFrame = helperIsKeyFrame(mapPoints, ...
refKeyFrameId, lastKeyFrameIndex, currFrameIndex, mapPointsIndices)
numPointsRefKeyFrame = numel(findWorldPointsInView(mapPoints, refKeyFrameId));
% More than 20 frames have passed from last key frame insertion
tooManyNonKeyFrames = currFrameIndex > lastKeyFrameIndex + 20;
% Track less than 100 map points
tooFewMapPoints = numel(mapPointsIndices) < 100;
% Tracked map points are fewer than 90% of points tracked by
% the reference key frame
tooFewTrackedPoints = numel(mapPointsIndices) < 0.9 * numPointsRefKeyFrame;
isKeyFrame = (tooManyNonKeyFrames || tooFewMapPoints) && tooFewTrackedPoints;
end
function [mapPointSet, directionAndDepth, mapPointsIdx] = helperCullRecentMapPoints(mapPointSet, directionAndDepth, mapPointsIdx, newPointIdx)
outlierIdx = setdiff(newPointIdx, mapPointsIdx);
if ~isempty(outlierIdx)
mapPointSet = removeWorldPoints(mapPointSet, outlierIdx);
directionAndDepth = remove(directionAndDepth, outlierIdx);
mapPointsIdx = mapPointsIdx - arrayfun(@(x) nnz(x>outlierIdx), mapPointsIdx);
end
end
function [mapPointSet, directionAndDepth] = helperUpdateGlobalMap(...
mapPointSet, directionAndDepth, vSetKeyFrames, vSetKeyFramesOptim, poseScales)
%helperUpdateGlobalMap update map points after pose graph optimization
posesOld = vSetKeyFrames.Views.AbsolutePose;
posesNew = vSetKeyFramesOptim.Views.AbsolutePose;
positionsOld = mapPointSet.WorldPoints;
positionsNew = positionsOld;
indices = 1:mapPointSet.Count;
% Update world location of each map point based on the new absolute pose of
% the corresponding major view
for i = 1: mapPointSet.Count
majorViewIds = directionAndDepth.MajorViewId(i);
poseNew = posesNew(majorViewIds).T;
poseNew(1:3, 1:3) = poseNew(1:3, 1:3) * poseScales(majorViewIds);
tform = posesOld(majorViewIds).T \ poseNew;
positionsNew(i, :) = positionsOld(i, :) * tform(1:3,1:3) + tform(4, 1:3);
end
mapPointSet = updateWorldPoints(mapPointSet, indices, positionsNew);
end