forked from luigifreda/pyslam
-
Notifications
You must be signed in to change notification settings - Fork 0
/
local_mapping.py
414 lines (323 loc) · 18.1 KB
/
local_mapping.py
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
"""
* This file is part of PYSLAM
*
* Copyright (C) 2016-present Luigi Freda <luigi dot freda at gmail dot com>
*
* PYSLAM 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.
*
* PYSLAM 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 PYSLAM. If not, see <http://www.gnu.org/licenses/>.
"""
from __future__ import print_function # This must be the first statement before other statements
import sys
import time
import numpy as np
import cv2
import g2o
from enum import Enum
from collections import defaultdict
from threading import RLock, Thread, Condition
from queue import Queue
from concurrent.futures import ThreadPoolExecutor
from parameters import Parameters
#from frame import Frame, match_frames
from keyframe import KeyFrame
from frame import Frame
from search_points import search_frame_for_triangulation, search_and_fuse
from map_point import MapPoint
from map import Map
from timer import Timer, TimerFps
import optimizer_g2o
from utils import Printer
from utils_geom import triangulate_normalized_points
kVerbose=True
kTimerVerbose = False
kLocalMappingOnSeparateThread = Parameters.kLocalMappingOnSeparateThread
kUseLargeWindowBA = Parameters.kUseLargeWindowBA
kNumMinObsForKeyFrameDefault = 3
kLocalMappingSleepTime = 3e-3 # [s]
if kLocalMappingOnSeparateThread:
# redirect the prints of local mapping to the file local_mapping.log
# you can watch the output in separate shell by running:
# $ tail -f local_mapping.log
import builtins as __builtin__
logging_file=open('local_mapping.log','w+')
def print(*args, **kwargs):
return __builtin__.print(*args, **kwargs,file=logging_file,flush=True)
if not kVerbose:
def print(*args, **kwargs):
pass
class LocalMapping(object):
def __init__(self, map):
self.map = map
self.recently_added_points = set()
self.kf_cur = None # current processed keyframe
self.kid_last_BA = -1 # last keyframe id when performed BA
self.descriptor_distance_sigma = Parameters.kMaxDescriptorDistance
self.timer_verbose = kTimerVerbose # set this to True if you want to print timings
self.timer_triangulation = TimerFps('Triangulation', is_verbose = self.timer_verbose)
self.timer_pts_culling = TimerFps('Culling points', is_verbose = self.timer_verbose)
self.timer_pts_fusion = TimerFps('Fusing points', is_verbose = self.timer_verbose)
self.time_local_opt = TimerFps('Local optimization', is_verbose = self.timer_verbose)
self.time_large_opt = TimerFps('Large window optimization', is_verbose = self.timer_verbose)
self.queue = Queue()
self.work_thread = Thread(target=self.run)
self.stop = False
self.lock_accept_keyframe = RLock()
self._is_idle = True
self.idle_codition = Condition()
self.opt_abort_flag = g2o.Flag(False)
self.log_file = None
self.thread_large_BA = None
def start(self):
self.work_thread.start()
def quit(self):
print('local mapping: quitting...')
self.stop = True
self.opt_abort_flag.value = True
self.work_thread.join()
print('local mapping: done')
def push_keyframe(self, keyframe):
self.queue.put(keyframe)
self.opt_abort_flag.value = True
def queue_size(self):
return self.queue.qsize()
def is_idle(self):
with self.lock_accept_keyframe:
return self._is_idle
def set_idle(self, flag):
with self.lock_accept_keyframe:
self._is_idle = flag
def wait_idle(self):
with self.idle_codition:
self.idle_codition.wait()
def interrupt_optimization(self):
Printer.yellow('interrupting local mapping optimization')
self.opt_abort_flag.value = True
def run(self):
while not self.stop:
with self.idle_codition:
self.set_idle(False)
self.do_local_mapping()
self.set_idle(True)
self.idle_codition.notifyAll()
time.sleep(kLocalMappingSleepTime)
def do_local_mapping(self):
if self.queue.empty():
return
if self.map.local_map.is_empty():
return
Printer.cyan('@local mapping')
time_start = time.time()
self.kf_cur = self.queue.get()
if kLocalMappingOnSeparateThread:
print('..................................')
print('processing KF: ', self.kf_cur.id, ', queue size: ', self.queue_size())
#print('descriptor_distance_sigma: ', self.descriptor_distance_sigma)
self.process_new_keyframe()
# do map points culling
self.timer_pts_culling.start()
num_culled_points = self.cull_map_points()
self.timer_pts_culling.refresh()
print(' # culled points: ', num_culled_points)
# create new points by triangulation
self.timer_triangulation.start()
total_new_pts = self.create_new_map_points()
self.timer_triangulation.refresh()
print(" # new map points: %d " % (total_new_pts))
if self.queue.empty():
# fuse map points of close keyframes
self.timer_pts_fusion.start()
total_fused_pts = self.fuse_map_points()
self.timer_pts_fusion.refresh()
print(" # fused map points: %d " % (total_fused_pts))
# reset optimization flag
self.opt_abort_flag.value = False
if self.queue.empty():
if self.thread_large_BA is not None:
if self.thread_large_BA.is_alive(): # for security, check if large BA thread finished his work
self.thread_large_BA.join()
# launch local bundle adjustment
self.local_BA()
if kUseLargeWindowBA and \
self.kf_cur.kid >= Parameters.kEveryNumFramesLargeWindowBA and \
self.kid_last_BA != self.kf_cur.kid and self.kf_cur.kid % Parameters.kEveryNumFramesLargeWindowBA == 0:
# launch a parallel large window BA of the map
self.thread_large_BA = Thread(target=self.large_window_BA)
self.thread_large_BA.start()
# check redundant local Keyframes
num_culled_keyframes = self.cull_keyframes()
print(" # culled keyframes: %d " % (num_culled_keyframes))
duration = time.time() - time_start
print('local mapping duration: ', duration)
def local_BA(self):
# local optimization
self.time_local_opt.start()
err = self.map.locally_optimize(kf_ref=self.kf_cur, abort_flag=self.opt_abort_flag)
self.time_local_opt.refresh()
print("local optimization error^2: %f" % err)
num_kf_ref_tracked_points = self.kf_cur.num_tracked_points(kNumMinObsForKeyFrameDefault) # number of tracked points in k_ref
Printer.purple('KF(%d) #points: %d ' %(self.kf_cur.id, num_kf_ref_tracked_points))
def large_window_BA(self):
Printer.blue('@large BA')
# large window optimization of the map
self.kid_last_BA = self.kf_cur.kid
self.time_large_opt.start()
err = self.map.optimize(local_window=Parameters.kLargeBAWindow, abort_flag=self.opt_abort_flag) # verbose=True)
self.time_large_opt.refresh()
Printer.blue('large window optimization error^2: %f, KF id: %d' % (err,self.kf_cur.kid))
def process_new_keyframe(self):
# associate map points to keyframe observations (only good points)
# and update normal and descriptor
for idx,p in enumerate(self.kf_cur.get_points()):
if p is not None and not p.is_bad:
if p.add_observation(self.kf_cur, idx):
p.update_info()
else:
self.recently_added_points.add(p)
self.kf_cur.update_connections()
self.map.add_keyframe(self.kf_cur) # add kf_cur to map
def cull_map_points(self):
print('>>>> culling map points...')
th_num_observations = 2
min_found_ratio = 0.25
current_kid = self.kf_cur.kid
remove_set = set()
for p in self.recently_added_points:
if p.is_bad:
remove_set.add(p)
elif p.get_found_ratio() < min_found_ratio:
self.map.remove_point(p)
remove_set.add(p)
elif (current_kid - p.first_kid) >= 2 and p.num_observations <= th_num_observations:
self.map.remove_point(p)
remove_set.add(p)
elif (current_kid - p.first_kid) >= 3: # after three keyframes we do not consider the point a recent one
remove_set.add(p)
self.recently_added_points = self.recently_added_points - remove_set
num_culled_points = len(remove_set)
return num_culled_points
def cull_keyframes(self):
print('>>>> culling keyframes...')
num_culled_keyframes = 0
# check redundant keyframes in local keyframes: a keyframe is considered redundant if the 90% of the MapPoints it sees,
# are seen in at least other 3 keyframes (in the same or finer scale)
th_num_observations = 3
for kf in self.kf_cur.get_covisible_keyframes():
if kf.kid==0:
continue
kf_num_points = 0 # num good points for kf
kf_num_redundant_observations = 0 # num redundant observations for kf
for i,p in enumerate(kf.get_points()):
if p is not None and not p.is_bad:
kf_num_points += 1
if p.num_observations>th_num_observations:
scale_level = kf.octaves[i] # scale level of observation in kf
p_num_observations = 0
for kf_j,idx in p.observations():
if kf_j is kf:
continue
assert(not kf_j.is_bad)
scale_level_i = kf_j.octaves[idx] # scale level of observation in kfi
if scale_level_i <= scale_level+1: # N.B.1 <- more aggressive culling (expecially when scale_factor=2)
#if scale_level_i <= scale_level: # N.B.2 <- only same scale or finer
p_num_observations +=1
if p_num_observations >= th_num_observations:
break
if p_num_observations >= th_num_observations:
kf_num_redundant_observations += 1
if kf_num_redundant_observations > Parameters.kKeyframeCullingRedundantObsRatio * kf_num_points:
print('setting keyframe ', kf.id,' bad - redundant observations: ', kf_num_redundant_observations/max(kf_num_points,1),'%')
kf.set_bad()
num_culled_keyframes += 1
return num_culled_keyframes
def precompute_kps_matches(self, match_idxs, local_keyframes):
kf_pairs = []
if not Parameters.kLocalMappingParallelKpsMatching:
# do serial computation
for kf in local_keyframes:
if kf is self.kf_cur or kf.is_bad:
continue
idxs1, idxs2 = Frame.feature_matcher.match(self.kf_cur.des, kf.des)
match_idxs[(self.kf_cur,kf)]=(idxs1,idxs2)
else:
# do parallell computation
def thread_match_function(kf_pair):
kf1,kf2 = kf_pair
idxs1, idxs2 = Frame.feature_matcher.match(kf1.des, kf2.des)
match_idxs[(kf1, kf2)]=(idxs1,idxs2)
for kf in local_keyframes:
if kf is self.kf_cur or kf.is_bad:
continue
kf_pairs.append((self.kf_cur, kf))
with ThreadPoolExecutor(max_workers = Parameters.kLocalMappingParallelKpsMatchingNumWorkers) as executor:
executor.map(thread_match_function, kf_pairs) # automatic join() at the end of the `width` block
return match_idxs
# triangulate matched keypoints (without a corresponding map point) amongst recent keyframes
def create_new_map_points(self):
print('>>>> creating new map points')
total_new_pts = 0
local_keyframes = self.map.local_map.get_best_neighbors(self.kf_cur)
print('local map keyframes: ', [kf.id for kf in local_keyframes if not kf.is_bad], ' + ', self.kf_cur.id, '...')
match_idxs = defaultdict(lambda: (None,None)) # dictionary of matches (kf_i, kf_j) -> (idxs_i,idxs_j)
# precompute keypoint matches
match_idxs = self.precompute_kps_matches(match_idxs, local_keyframes)
for i,kf in enumerate(local_keyframes):
if kf is self.kf_cur or kf.is_bad:
continue
if i>0 and not self.queue.empty():
print('creating new map points *** interruption ***')
return total_new_pts
#print("adding map points for KFs (%d, %d)" % (self.kf_cur.id, kf.id))
# extract matches from precomputed map
idxs_kf_cur, idxs_kf = match_idxs[(self.kf_cur,kf)]
# find keypoint matches between self.kf_cur and kf
# N.B.: all the matched keypoints computed by search_frame_for_triangulation() are without a corresponding map point
idxs_cur, idxs, num_found_matches, _ = search_frame_for_triangulation(self.kf_cur, kf, idxs_kf_cur, idxs_kf,
max_descriptor_distance=0.5*self.descriptor_distance_sigma)
if len(idxs_cur) > 0:
# try to triangulate the matched keypoints that do not have a corresponding map point
pts3d, mask_pts3d = triangulate_normalized_points(self.kf_cur.pose, kf.pose, self.kf_cur.kpsn[idxs_cur], kf.kpsn[idxs])
new_pts_count,_,list_added_points = self.map.add_points(pts3d, mask_pts3d, self.kf_cur, kf, idxs_cur, idxs, self.kf_cur.img, do_check=True)
print("# added map points: %d for KFs (%d, %d)" % (new_pts_count, self.kf_cur.id, kf.id))
total_new_pts += new_pts_count
self.recently_added_points.update(list_added_points)
return total_new_pts
# fuse close map points of local keyframes
def fuse_map_points(self):
print('>>>> fusing map points')
total_fused_pts = 0
local_keyframes = self.map.local_map.get_best_neighbors(self.kf_cur)
print('local map keyframes: ', [kf.id for kf in local_keyframes if not kf.is_bad], ' + ', self.kf_cur.id, '...')
# search matches by projection from current KF in close KFs
for kf in local_keyframes:
if kf is self.kf_cur or kf.is_bad:
continue
num_fused_pts = search_and_fuse(self.kf_cur.get_points(), kf,
max_reproj_distance=Parameters.kMaxReprojectionDistanceFuse,
max_descriptor_distance=0.5*self.descriptor_distance_sigma) # finer search
print("# fused map points: %d for KFs (%d, %d)" % (num_fused_pts, self.kf_cur.id, kf.id))
total_fused_pts += num_fused_pts
# search matches by projection from local points in current KF
good_local_points = [p for kf in local_keyframes if not kf.is_bad for p in kf.get_points() if (p is not None and not p.is_bad) ] # all good points in local frames
good_local_points = np.array(list(set(good_local_points))) # be sure to get only one instance per point
num_fused_pts = search_and_fuse(good_local_points, self.kf_cur,
max_reproj_distance=Parameters.kMaxReprojectionDistanceFuse,
max_descriptor_distance=0.5*self.descriptor_distance_sigma) # finer search
print("# fused map points: %d for local map into KF %d" % (num_fused_pts, self.kf_cur.id))
total_fused_pts += num_fused_pts
# update points info
for p in self.kf_cur.get_points():
if p is not None and not p.is_bad:
p.update_info()
# update connections in covisibility graph
self.kf_cur.update_connections()
return total_fused_pts