def track_previous_frame(self, f_ref, f_cur): print('>>>> tracking previous frame ...') is_search_frame_by_projection_failure = False use_search_frame_by_projection = self.motion_model.is_ok and kUseSearchFrameByProjection and kUseMotionModel if use_search_frame_by_projection: # search frame by projection: match map points observed in f_ref with keypoints of f_cur print('search frame by projection') search_radius = Parameters.kMaxReprojectionDistanceFrame f_cur.reset_points() self.timer_seach_frame_proj.start() idxs_ref, idxs_cur, num_found_map_pts = search_frame_by_projection( f_ref, f_cur, max_reproj_distance=search_radius, max_descriptor_distance=self.descriptor_distance_sigma) self.timer_seach_frame_proj.refresh() self.num_matched_kps = len(idxs_cur) print("# matched map points in prev frame: %d " % self.num_matched_kps) # if not enough map point matches consider a larger search radius if self.num_matched_kps < Parameters.kMinNumMatchedFeaturesSearchFrameByProjection: f_cur.remove_frame_views(idxs_cur) f_cur.reset_points() idxs_ref, idxs_cur, num_found_map_pts = search_frame_by_projection( f_ref, f_cur, max_reproj_distance=2 * search_radius, max_descriptor_distance=0.5 * self.descriptor_distance_sigma) self.num_matched_kps = len(idxs_cur) Printer.orange( "# matched map points in prev frame (wider search): %d " % self.num_matched_kps) if kDebugDrawMatches and True: img_matches = draw_feature_matches(f_ref.img, f_cur.img, f_ref.kps[idxs_ref], f_cur.kps[idxs_cur], f_ref.sizes[idxs_ref], f_cur.sizes[idxs_cur], horizontal=False) cv2.imshow('tracking frame by projection - matches', img_matches) cv2.waitKey(1) if self.num_matched_kps < Parameters.kMinNumMatchedFeaturesSearchFrameByProjection: f_cur.remove_frame_views(idxs_cur) f_cur.reset_points() is_search_frame_by_projection_failure = True Printer.red( 'Not enough matches in search frame by projection: ', self.num_matched_kps) else: # search frame by projection was successful if kUseDynamicDesDistanceTh: self.descriptor_distance_sigma = self.dyn_config.update_descriptor_stat( f_ref, f_cur, idxs_ref, idxs_cur) # store tracking info (for possible reuse) self.idxs_ref = idxs_ref self.idxs_cur = idxs_cur # f_cur pose optimization 1: # here, we use f_cur pose as first guess and exploit the matched map point of f_ref self.pose_optimization(f_cur, 'proj-frame-frame') # update matched map points; discard outliers detected in last pose optimization num_matched_points = f_cur.clean_outlier_map_points() print(' # num_matched_map_points: %d' % (self.num_matched_map_points)) #print(' # matched points: %d' % (num_matched_points) ) if not self.pose_is_ok or self.num_matched_map_points < kNumMinInliersPoseOptimizationTrackFrame: Printer.red( 'failure in tracking previous frame, # matched map points: ', self.num_matched_map_points) self.pose_is_ok = False if not use_search_frame_by_projection or is_search_frame_by_projection_failure: self.track_reference_frame(f_ref, f_cur, 'match-frame-frame')
def track(self, img, frame_id, pose=None, verts=None): # check image size is coherent with camera params print("img.shape ", img.shape) print("cam ", self.H, " x ", self.W) assert img.shape[0:2] == (self.H, self.W) self.timer_main_track.start() # build current frame self.timer_frame.start() f_cur = Frame(self.map, img, self.K, self.Kinv, self.D, des=verts) self.timer_frame.refresh() if self.stage == SLAMStage.NO_IMAGES_YET: # push first frame in the inizializer self.intializer.init(f_cur) self.stage = SLAMStage.NOT_INITIALIZED return # EXIT (jump to second frame) if self.stage == SLAMStage.NOT_INITIALIZED: # try to inizialize initializer_output, is_ok = self.intializer.initialize(f_cur, img) if is_ok: f_ref = self.intializer.f_ref # add the two initialized frames in the map self.map.add_frame( f_ref) # add first frame in map and update its id self.map.add_frame( f_cur) # add second frame in map and update its id # add points in map new_pts_count, _ = self.map.add_points( initializer_output.points4d, None, f_cur, f_ref, initializer_output.idx_cur, initializer_output.idx_ref, img) Printer.green("map: initialized %d new points" % (new_pts_count)) self.stage = SLAMStage.OK return # EXIT (jump to next frame) f_ref = self.map.frames[-1] # get previous frame in map self.map.add_frame(f_cur) # add f_cur to map # udpdate (velocity) motion model (kinematic without damping) self.velocity = np.dot(f_ref.pose, np.linalg.inv(self.map.frames[-2].pose)) predicted_pose = np.dot(self.velocity, f_ref.pose) if kUseMotionModel is True: print('using motion model') # set intial guess for current pose optimization f_cur.pose = predicted_pose.copy() #f_cur.pose = f_ref.pose.copy() # get the last pose as an initial guess for optimization if kUseSearchFrameByProjection: # search frame by projection: match map points observed in f_ref with keypoints of f_cur print('search frame by projection...') idx_ref, idx_cur, num_found_map_pts = search_frame_by_projection( f_ref, f_cur) print("# found map points in prev frame: %d " % num_found_map_pts) else: self.timer_match.start() # find keypoint matches between f_cur and f_ref idx_cur, idx_ref = match_frames(f_cur, f_ref) self.num_matched_kps = idx_cur.shape[0] print('# keypoint matches: ', self.num_matched_kps) self.timer_match.refresh() else: print('estimating pose by fitting essential mat') self.timer_match.start() # find keypoint matches between f_cur and f_ref idx_cur, idx_ref = match_frames(f_cur, f_ref) self.num_matched_kps = idx_cur.shape[0] print('# keypoint matches: ', self.num_matched_kps) self.timer_match.refresh() # N.B.: please, in order to understand the limitations of fitting an essential mat, read the comments of the method self.estimate_pose_ess_mat() self.timer_pose_est.start() # estimate inter frame camera motion by using found keypoint matches Mrc = self.estimate_pose_ess_mat(f_ref.kpsn[idx_ref], f_cur.kpsn[idx_cur]) Mcr = np.linalg.inv(poseRt(Mrc[:3, :3], Mrc[:3, 3])) f_cur.pose = np.dot(Mcr, f_ref.pose) self.timer_pose_est.refresh() # remove outliers from keypoint matches by using the mask computed with inter frame pose estimation mask_index = (self.mask_match.ravel() == 1) self.num_inliers = sum(mask_index) print('# inliers: ', self.num_inliers) idx_ref = idx_ref[mask_index] idx_cur = idx_cur[mask_index] # if too many outliers reset estimated pose if self.num_inliers < kNumMinInliersEssentialMat: f_cur.pose = f_ref.pose.copy( ) # reset estimated pose to previous frame Printer.red('Essential mat: not enough inliers!') # set intial guess for current pose optimization: # keep the estimated rotation and override translation with ref frame translation (we do not have a proper scale for the translation) f_cur.pose[:, 3] = f_ref.pose[:, 3].copy() #f_cur.pose[:,3] = predicted_pose[:,3].copy() # or use motion model for translation # populate f_cur with map points by propagating map point matches of f_ref: # we use map points observed in f_ref and keypoint matches between f_ref and f_cur num_found_map_pts_inter_frame = 0 if not kUseSearchFrameByProjection: for i, idx in enumerate(idx_ref): # iterate over keypoint matches if f_ref.points[ idx] is not None: # if we have a map point P for i-th matched keypoint in f_ref f_ref.points[idx].add_observation( f_cur, idx_cur[i] ) # then P is automatically matched to the i-th matched keypoint in f_cur num_found_map_pts_inter_frame += 1 print("# matched map points in prev frame: %d " % num_found_map_pts_inter_frame) # f_cur pose optimization 1 (here we use first available information coming from first guess of f_cur pose and map points of f_ref matched keypoints ) self.timer_pose_opt.start() pose_opt_error, pose_is_ok, self.num_vo_map_points = optimizer_g2o.poseOptimization( f_cur, verbose=False) print("pose opt err1: %f, ok: %d" % (pose_opt_error, int(pose_is_ok))) # discard outliers detected in pose optimization (in current frame) #f_cur.reset_outlier_map_points() if pose_is_ok is True: # discard outliers detected in f_cur pose optimization (in current frame) f_cur.reset_outlier_map_points() else: # if current pose optimization failed, reset f_cur pose to f_ref pose f_cur.pose = f_ref.pose.copy() self.timer_pose_opt.pause() # TODO: add recover in case of f_cur pose optimization failure # now, having a better estimate of f_cur pose, we can find more map point matches: # find matches between {local map points} (points in the built local map) and {unmatched keypoints of f_cur} if pose_is_ok is True and not self.map.local_map.is_empty(): self.timer_seach_map.start() #num_found_map_pts = search_local_frames_by_projection(self.map, f_cur) num_found_map_pts = search_map_by_projection( self.map.local_map.points, f_cur) # use the built local map print("# matched map points in local map: %d " % num_found_map_pts) self.timer_seach_map.refresh() # f_cur pose optimization 2 with all the matched map points self.timer_pose_opt.resume() pose_opt_error, pose_is_ok, self.num_vo_map_points = optimizer_g2o.poseOptimization( f_cur, verbose=False) print("pose opt err2: %f, ok: %d" % (pose_opt_error, int(pose_is_ok))) print("# valid matched map points: %d " % self.num_vo_map_points) # discard outliers detected in pose optimization (in current frame) if pose_is_ok is True: f_cur.reset_outlier_map_points() self.timer_pose_opt.refresh() if kUseSearchFrameByProjection: print("search for triangulation with epipolar lines...") idx_ref, idx_cur, self.num_matched_kps, _ = search_frame_for_triangulation( f_ref, f_cur, img) print("# matched keypoints in prev frame: %d " % self.num_matched_kps) # if pose is ok, then we try to triangulate the matched keypoints (between f_cur and f_ref) that do not have a corresponding map point if pose_is_ok is True and len(idx_ref) > 0: self.timer_triangulation.start() # TODO: this triangulation should be done from keyframes! good_pts4d = np.array([ f_cur.points[i] is None for i in idx_cur ]) # matched keypoints of f_cur without a corresponding map point # do triangulation in global frame pts4d = triangulate_points(f_cur.pose, f_ref.pose, f_cur.kpsn[idx_cur], f_ref.kpsn[idx_ref], good_pts4d) good_pts4d &= np.abs(pts4d[:, 3]) != 0 #pts4d /= pts4d[:, 3:] pts4d[good_pts4d] /= pts4d[good_pts4d, 3:] # get homogeneous 3-D coords new_pts_count, _ = self.map.add_points(pts4d, good_pts4d, f_cur, f_ref, idx_cur, idx_ref, img, check_parallax=True) print("# added map points: %d " % (new_pts_count)) self.timer_triangulation.refresh() # local optimization self.time_local_opt.start() err = self.map.locally_optimize(local_window=kLocalWindow) print("local optimization error: %f" % err) self.time_local_opt.refresh() # large window optimization of the map # TODO: move this in a seperate thread with local mapping if kUseLargeWindowBA is True and f_cur.id >= parameters.kEveryNumFramesLargeWindowBA and f_cur.id % parameters.kEveryNumFramesLargeWindowBA == 0: err = self.map.optimize( local_window=parameters.kLargeWindow) # verbose=True) Printer.blue("large window optimization error: %f" % err) print("map: %d points, %d frames" % (len(self.map.points), len(self.map.frames))) #self.updateHistory() self.timer_main_track.refresh()