# Init Feature Tracker #============================================ num_features=2000 tracker_type = FeatureTrackerTypes.DES_BF # descriptor-based, brute force matching with knn #tracker_type = FeatureTrackerTypes.DES_FLANN # descriptor-based, FLANN-based matching # select your tracker configuration (see the file feature_tracker_configs.py) tracker_config = FeatureTrackerConfigs.TEST tracker_config['num_features'] = num_features tracker_config['match_ratio_test'] = 0.8 # 0.7 is the default in feature_tracker_configs.py tracker_config['tracker_type'] = tracker_type print('feature_manager_config: ',tracker_config) feature_tracker = feature_tracker_factory(**tracker_config) #============================================ # Compute keypoints and descriptors #============================================ # loop for measuring time performance N=1 for i in range(N): # Find the keypoints and descriptors in img1 kps1, des1 = feature_tracker.detectAndCompute(img1) timer.start() # Find the keypoints and descriptors in img2 kps2, des2 = feature_tracker.detectAndCompute(img2)
cam = PinholeCamera(config.cam_settings['Camera.width'], config.cam_settings['Camera.height'], config.cam_settings['Camera.fx'], config.cam_settings['Camera.fy'], config.cam_settings['Camera.cx'], config.cam_settings['Camera.cy'], config.DistCoef) num_features=parameters.kNumFeatures """ select your feature tracker N.B.1: here you can use just ORB descriptors! ... at present time N.B.2: ORB detector (not descriptor) does not work as expected! """ tracker_type = TrackerTypes.DES_BF #tracker_type = TrackerTypes.DES_FLANN feature_tracker = feature_tracker_factory(min_num_features=num_features, detector_type = FeatureDetectorTypes.SHI_TOMASI, descriptor_type = FeatureDescriptorTypes.ORB, tracker_type = tracker_type) #feature_tracker = feature_tracker_factory(min_num_features=num_features, num_levels = 1, detector_type = FeatureDetectorTypes.FAST, descriptor_type = FeatureDescriptorTypes.ORB, tracker_type = tracker_type) #feature_tracker = feature_tracker_factory(min_num_features=num_features, num_levels = 3, detector_type = FeatureDetectorTypes.BRISK, descriptor_type = FeatureDescriptorTypes.ORB, tracker_type = tracker_type) #feature_tracker = feature_tracker_factory(min_num_features=num_features, detector_type = FeatureDetectorTypes.ORB, descriptor_type = FeatureDescriptorTypes.ORB, tracker_type = tracker_type) slam = SLAM(cam, feature_tracker, grountruth) timer = Timer() #------------- # N.B.: keep this coherent with the above forced camera settings img_ref = cv2.imread('kitti06-12.png',cv2.IMREAD_COLOR) #img_cur = cv2.imread('kitti06-12-01.png',cv2.IMREAD_COLOR) img_cur = cv2.imread('kitti06-13.png',cv2.IMREAD_COLOR)