Skip to content

Commit

Permalink
Remove GPL infringing code (#252)
Browse files Browse the repository at this point in the history
* Fix frame/keyframe (Remove GPL infringing code)

* Fix graph_node (Remove GPL infringing code)

* Fix landmark (Remove GPL infringing code)

* Fix map_database (Remove GPL infringing code)

* Fix frame_publicher (Remove GPL infringing code (Remove overlay text))

* Fix pangolin_viewer (Remove GPL infringing code)

Remove color scheme black

* Fix about request (Remove GPL infringing code)

* Remove temporary variables for tracking (Remove GPL infringing code)

* Fix mapping_module (Remove GPL infringing code)

* Remove temporary variables for loop closing (Remove GPL infringing code),

and
- Remove unused parentheses
- Split global bundle adjustment into two member functions
- Fix nested ifs to logical operations.

* Remove duplicated code in loop_detector (Remove GPL infringing code)

* Fix orb_extractor (Remove GPL infringing code)

* Minimize unnecessary functions (Remove GPL infringing code)

* Move depth_thr to camera (Remove GPL infringing code)

* Update config files (Move depth_thr to Camera)

* Update feature extraction parameters (Remove GPL infringing code)

* Remove database from keyframe/frame (Remove GPL infringing code)

* Add fame_observation (Remove GPL infringing code)

* Fix match::projection (Remove GPL infringing code)

* Fix tracking (Remove GPL infringing code)

* Fix missing #include <cmath>

* Add NOTE to README.md
  • Loading branch information
ymd-stella authored Feb 6, 2022
1 parent aa1f048 commit 183c2a3
Show file tree
Hide file tree
Showing 111 changed files with 1,845 additions and 2,033 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@

---

> *NOTE:* This is a community fork of [xdspacelab/openvslam](https://github.com/xdspacelab/openvslam). It was created to continue active development of OpenVSLAM on Jan 31, 2021. The original repository is no longer available. Please read the [official statement of termination](https://github.com/xdspacelab/openvslam/wiki/Termination-of-the-release) carefully and understand it before using this. If you are interested in a more detailed discussion, see [here](https://github.com/OpenVSLAM-Community/openvslam/issues/37).
> *NOTE:* This is a community fork of [xdspacelab/openvslam](https://github.com/xdspacelab/openvslam). It was created to continue active development of OpenVSLAM on Jan 31, 2021. The original repository is no longer available. Please read the [official statement of termination](https://github.com/xdspacelab/openvslam/wiki/Termination-of-the-release) carefully and understand it before using this. The similarities with ORB_SLAM2 in the original version have been removed by <https://github.com/OpenVSLAM-Community/openvslam/pull/252>. If you find any other issues with the license, please point them out. See <https://github.com/OpenVSLAM-Community/openvslam/issues/37> and <https://github.com/OpenVSLAM-Community/openvslam/issues/249> for discussion so far.
---

Expand Down
42 changes: 37 additions & 5 deletions docs/parameters.rst
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,8 @@ Camera
* - focal_x_baseline
- For stereo cameras, it is the value of the baseline between the left and right cameras multiplied by the focal length fx.
For RGBD cameras, if the measurement method is stereo, set it based on its baseline. If the measurement method is other than that, set the appropriate value based on the relationship between depth accuracy and baseline.
* - depth_threshold
- The ratio used to determine the depth threshold.

.. _section-parameters-feature:

Expand All @@ -53,6 +55,8 @@ Feature

* - Name
- Description
* - name
- name of ORB feature extraction model (id for saving)
* - scale_factor
- Scale of the image pyramid
* - num_levels
Expand All @@ -62,10 +66,10 @@ Feature
* - min_fast_threshold
- FAST threshold for try second time

.. _section-parameters-tracking:
.. _section-parameters-preprocessing:

Tracking
========
Preprocessing
=============

.. list-table::
:header-rows: 1
Expand All @@ -77,10 +81,20 @@ Tracking
- Maximum number of feature points per frame to be used for SLAM.
* - ini_max_num_keypoints
- Maximum number of feature points per frame to be used for Initialization. It is only used for monocular camera models.
* - depth_threshold
- The ratio used to determine the depth threshold.
* - depthmap_factor
- The ratio used to convert depth image pixel values to distance.

.. _section-parameters-tracking:

Tracking
========

.. list-table::
:header-rows: 1
:widths: 1, 3

* - Name
- Description
* - reloc_distance_threshold
- Maximum distance threshold (in meters) where close keyframes could be found when doing a relocalization by pose.
* - reloc_angle_threshold
Expand Down Expand Up @@ -164,6 +178,24 @@ Relocalizer
* - min_num_valid_obs
-

.. _section-parameters-keyframe-inserter:

KeyframeInserter
================

.. list-table::
:header-rows: 1
:widths: 1, 3

* - Name
- Description
* - max_interval
- max interval to insert keyframe
* - lms_ratio_thr_almost_all_lms_are_tracked
- Threshold at which we consider that we are tracking almost all landmarks. Ratio-threshold of "the number of 3D points observed in the current frame" / "that of 3D points observed in the last keyframe"
* - lms_ratio_thr_view_changed
- Threshold at which we consider the view to have changed. Ratio-threshold of "the number of 3D points observed in the current frame" / "that of 3D points observed in the last keyframe"

.. _section-parameters-pangolin:

PangolinViewer
Expand Down
13 changes: 7 additions & 6 deletions example/aist/equirectangular.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -19,23 +19,24 @@ Camera:
# Tracking Parameters #
#=====================#

Tracking:
Preprocessing:
max_num_keypoints: 2000
mask_rectangles:
- [0.0, 1.0, 0.0, 0.1]
- [0.0, 1.0, 0.84, 1.0]
- [0.0, 0.2, 0.7, 1.0]
- [0.8, 1.0, 0.7, 1.0]

#================#
# ORB Parameters #
#================#

Feature:
name: "default ORB feature extraction setting"
scale_factor: 1.2
num_levels: 8
ini_fast_threshold: 20
min_fast_threshold: 7
mask_rectangles:
- [0.0, 1.0, 0.0, 0.1]
- [0.0, 1.0, 0.84, 1.0]
- [0.0, 0.2, 0.7, 1.0]
- [0.8, 1.0, 0.7, 1.0]

#====================#
# Mapping Parameters #
Expand Down
3 changes: 2 additions & 1 deletion example/aist/fisyeye.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -29,14 +29,15 @@ Camera:
# Tracking Parameters #
#=====================#

Tracking:
Preprocessing:
max_num_keypoints: 2000

#================#
# orb parameters #
#================#

Feature:
name: "default ORB feature extraction setting"
scale_factor: 1.2
num_levels: 8
ini_fast_threshold: 20
Expand Down
3 changes: 2 additions & 1 deletion example/euroc/EuRoC_mono.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ Camera:
# Tracking Parameters #
#=====================#

Tracking:
Preprocessing:
max_num_keypoints: 1000
ini_max_num_keypoints: 2000

Expand All @@ -39,6 +39,7 @@ Tracking:
#================#

Feature:
name: "default ORB feature extraction setting"
scale_factor: 1.2
num_levels: 8
ini_fast_threshold: 20
Expand Down
5 changes: 3 additions & 2 deletions example/euroc/EuRoC_stereo.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ Camera:
cols: 752
rows: 480
focal_x_baseline: 47.90639384423901
depth_threshold: 40

color_order: "Gray"

Expand All @@ -55,16 +56,16 @@ StereoRectifier:
# Tracking Parameters #
#=====================#

Tracking:
Preprocessing:
max_num_keypoints: 1000
ini_max_num_keypoints: 2000
depth_threshold: 40

#================#
# ORB Parameters #
#================#

Feature:
name: "default ORB feature extraction setting"
scale_factor: 1.2
num_levels: 8
ini_fast_threshold: 20
Expand Down
3 changes: 2 additions & 1 deletion example/kitti/KITTI_mono_00-02.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ Camera:
# Tracking Parameters #
#=====================#

Tracking:
Preprocessing:
max_num_keypoints: 2000
ini_max_num_keypoints: 4000

Expand All @@ -39,6 +39,7 @@ Tracking:
#================#

Feature:
name: "default ORB feature extraction setting"
scale_factor: 1.2
num_levels: 8
ini_fast_threshold: 20
Expand Down
3 changes: 2 additions & 1 deletion example/kitti/KITTI_mono_03.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ Camera:
# Tracking Parameters #
#=====================#

Tracking:
Preprocessing:
max_num_keypoints: 2000
ini_max_num_keypoints: 4000

Expand All @@ -39,6 +39,7 @@ Tracking:
#================#

Feature:
name: "default ORB feature extraction setting"
scale_factor: 1.2
num_levels: 8
ini_fast_threshold: 20
Expand Down
3 changes: 2 additions & 1 deletion example/kitti/KITTI_mono_04-12.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ Camera:
# Tracking Parameters #
#=====================#

Tracking:
Preprocessing:
max_num_keypoints: 2000
ini_max_num_keypoints: 4000

Expand All @@ -39,6 +39,7 @@ Tracking:
#================#

Feature:
name: "default ORB feature extraction setting"
scale_factor: 1.2
num_levels: 8
ini_fast_threshold: 20
Expand Down
5 changes: 3 additions & 2 deletions example/kitti/KITTI_stereo_00-02.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -24,23 +24,24 @@ Camera:
cols: 1241
rows: 376
focal_x_baseline: 386.1448
depth_threshold: 40

color_order: "Gray"

#=====================#
# Tracking Parameters #
#=====================#

Tracking:
Preprocessing:
max_num_keypoints: 2000
ini_max_num_keypoints: 4000
depth_threshold: 40

#================#
# ORB Parameters #
#================#

Feature:
name: "default ORB feature extraction setting"
scale_factor: 1.2
num_levels: 8
ini_fast_threshold: 12
Expand Down
5 changes: 3 additions & 2 deletions example/kitti/KITTI_stereo_03.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -24,23 +24,24 @@ Camera:
cols: 1242
rows: 375
focal_x_baseline: 387.5744
depth_threshold: 40

color_order: "Gray"

#=====================#
# Tracking Parameters #
#=====================#

Tracking:
Preprocessing:
max_num_keypoints: 2000
ini_max_num_keypoints: 4000
depth_threshold: 40

#================#
# ORB Parameters #
#================#

Feature:
name: "default ORB feature extraction setting"
scale_factor: 1.2
num_levels: 8
ini_fast_threshold: 12
Expand Down
5 changes: 3 additions & 2 deletions example/kitti/KITTI_stereo_04-12.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -24,23 +24,24 @@ Camera:
cols: 1226
rows: 370
focal_x_baseline: 379.8145
depth_threshold: 40

color_order: "Gray"

#=====================#
# Tracking Parameters #
#=====================#

Tracking:
Preprocessing:
max_num_keypoints: 2000
ini_max_num_keypoints: 4000
depth_threshold: 40

#================#
# ORB Parameters #
#================#

Feature:
name: "default ORB feature extraction setting"
scale_factor: 1.2
num_levels: 8
ini_fast_threshold: 12
Expand Down
3 changes: 2 additions & 1 deletion example/tum_rgbd/TUM_RGBD_mono_1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ Camera:
# Tracking Parameters #
#=====================#

Tracking:
Preprocessing:
max_num_keypoints: 1000
ini_max_num_keypoints: 2000

Expand All @@ -39,6 +39,7 @@ Tracking:
#================#

Feature:
name: "default ORB feature extraction setting"
scale_factor: 1.2
num_levels: 8
ini_fast_threshold: 20
Expand Down
3 changes: 2 additions & 1 deletion example/tum_rgbd/TUM_RGBD_mono_2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ Camera:
# Tracking Parameters #
#=====================#

Tracking:
Preprocessing:
max_num_keypoints: 1000
ini_max_num_keypoints: 2000

Expand All @@ -39,6 +39,7 @@ Tracking:
#================#

Feature:
name: "default ORB feature extraction setting"
scale_factor: 1.2
num_levels: 8
ini_fast_threshold: 20
Expand Down
3 changes: 2 additions & 1 deletion example/tum_rgbd/TUM_RGBD_mono_3.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ Camera:
# Tracking Parameters #
#=====================#

Tracking:
Preprocessing:
max_num_keypoints: 1000
ini_max_num_keypoints: 2000

Expand All @@ -39,6 +39,7 @@ Tracking:
#================#

Feature:
name: "default ORB feature extraction setting"
scale_factor: 1.2
num_levels: 8
ini_fast_threshold: 20
Expand Down
5 changes: 3 additions & 2 deletions example/tum_rgbd/TUM_RGBD_rgbd_1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -24,24 +24,25 @@ Camera:
cols: 640
rows: 480
focal_x_baseline: 40.0
depth_threshold: 40.0

color_order: "RGB"

#=====================#
# Tracking Parameters #
#=====================#

Tracking:
Preprocessing:
max_num_keypoints: 1000
ini_max_num_keypoints: 2000
depth_threshold: 40.0
depthmap_factor: 5000.0 # Note: Set it to 1.0 for the rosbag format data set.

#================#
# ORB Parameters #
#================#

Feature:
name: "default ORB feature extraction setting"
scale_factor: 1.2
num_levels: 8
ini_fast_threshold: 20
Expand Down
Loading

0 comments on commit 183c2a3

Please sign in to comment.