diff --git a/README.md b/README.md index 321c717..d62c92a 100644 --- a/README.md +++ b/README.md @@ -249,6 +249,7 @@ Suggested material: * *[Vision Algorithms for Mobile Robotics](http://rpg.ifi.uzh.ch/teaching.html)* by Davide Scaramuzza * *[CS 682 Computer Vision](http://cs.gmu.edu/~kosecka/cs682.html)* by Jana Kosecka * *[The Role of Wide Baseline Stereo in the Deep Learning World](https://ducha-aiki.github.io/wide-baseline-stereo-blog/2020/03/27/intro.html)* by Dmytro Mishkin +* *[To Learn or Not to Learn: Visual Localization from Essential Matrices](https://arxiv.org/abs/1908.01293)* by Qunjie Zhou, Torsten Sattler, Marc Pollefeys, Laura Leal-Taixe * *[Awesome local-global descriptors](https://github.com/shamangary/awesome-local-global-descriptor)* repository Moreover, you may want to have a look at the OpenCV [guide](https://docs.opencv.org/3.0-beta/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html) or [tutorials](https://opencv-python-tutroals.readthedocs.io/en/latest/py_tutorials/py_tutorials.html). diff --git a/initializer.py b/initializer.py index 77e4045..22f01bf 100644 --- a/initializer.py +++ b/initializer.py @@ -129,7 +129,7 @@ def initialize(self, f_cur, img_cur): # find keypoint matches idxs_cur, idxs_ref = match_frames(f_cur, f_ref, kFeatureMatchRatioTestInitializer) - print('├────────') + print('|------------') #print('deque ids: ', [f.id for f in self.frames]) print('initializing frames ', f_cur.id, ', ', f_ref.id) print("# keypoint matches: ", len(idxs_cur)) @@ -195,5 +195,5 @@ def initialize(self, f_cur, img_cur): else: self.num_failures += 1 Printer.red('Inializer: ko!') - print('├────────') + print('|------------') return out, is_ok \ No newline at end of file diff --git a/local_mapping.py b/local_mapping.py index 0feef6c..4e16ffe 100644 --- a/local_mapping.py +++ b/local_mapping.py @@ -256,7 +256,7 @@ def process_new_keyframe(self): def cull_map_points(self): - print('»» culling map points...') + print('>>>> culling map points...') th_num_observations = 2 min_found_ratio = 0.25 current_kid = self.kf_cur.kid @@ -278,7 +278,7 @@ def cull_map_points(self): def cull_keyframes(self): - print('»» culling keyframes...') + 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) @@ -339,7 +339,7 @@ def thread_match_function(kf_pair): # triangulate matched keypoints (without a corresponding map point) amongst recent keyframes def create_new_map_points(self): - print('»» creating new map points') + print('>>>> creating new map points') total_new_pts = 0 local_keyframes = self.map.local_map.get_best_neighbors(self.kf_cur) @@ -378,7 +378,7 @@ def create_new_map_points(self): # fuse close map points of local keyframes def fuse_map_points(self): - print('»» fusing map points') + print('>>>> fusing map points') total_fused_pts = 0 local_keyframes = self.map.local_map.get_best_neighbors(self.kf_cur) @@ -411,4 +411,4 @@ def fuse_map_points(self): # update connections in covisibility graph self.kf_cur.update_connections() - return total_fused_pts \ No newline at end of file + return total_fused_pts diff --git a/slam.py b/slam.py index 1d7da72..02a68d8 100755 --- a/slam.py +++ b/slam.py @@ -264,7 +264,7 @@ def pose_optimization(self, f_cur, name=''): # track camera motion of f_cur w.r.t. f_ref def track_previous_frame(self, f_ref, f_cur): - print('»» tracking previous frame ...') + 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 @@ -332,7 +332,7 @@ def track_previous_frame(self, f_ref, f_cur): # track camera motion of f_cur w.r.t. f_ref # estimate motion by matching keypoint descriptors def track_reference_frame(self, f_ref, f_cur, name=''): - print('»» tracking reference %d ...' %(f_ref.id)) + print('>>>> tracking reference %d ...' %(f_ref.id)) if f_ref is None: return # find keypoint matches between f_cur and kf_ref @@ -397,7 +397,7 @@ def update_local_map(self): def track_local_map(self, f_cur): if self.map.local_map.is_empty(): return - print('»» tracking local map...') + print('>>>> tracking local map...') self.timer_seach_map.start() self.update_local_map() @@ -685,11 +685,11 @@ def wait_for_local_mapping(self): if kTrackingWaitForLocalMappingToGetIdle: #while not self.local_mapping.is_idle() or self.local_mapping.queue_size()>0: if not self.local_mapping.is_idle(): - print('»» waiting for local mapping...') + print('>>>> waiting for local mapping...') self.local_mapping.wait_idle() else: if not self.local_mapping.is_idle() and kTrackingWaitForLocalMappingSleepTime>0: - print('»» sleeping for local mapping...') + print('>>>> sleeping for local mapping...') time.sleep(kTrackingWaitForLocalMappingSleepTime) # check again for debug #is_local_mapping_idle = self.local_mapping.is_idle()