└── master
└── LearnVIORB_NOROS
├── .gitignore
├── CMakeLists.txt
├── Dependencies.md
├── Examples
├── Monocular
│ ├── EuRoC.yaml
│ ├── EuRoC_TimeStamps
│ │ ├── MH01.txt
│ │ ├── MH02.txt
│ │ ├── MH03.txt
│ │ ├── MH04.txt
│ │ ├── MH05.txt
│ │ ├── V101.txt
│ │ ├── V102.txt
│ │ ├── V103.txt
│ │ ├── V201.txt
│ │ ├── V202.txt
│ │ └── V203.txt
│ ├── KITTI00-02.yaml
│ ├── KITTI03.yaml
│ ├── KITTI04-12.yaml
│ ├── TUM1.yaml
│ ├── TUM2.yaml
│ ├── TUM3.yaml
│ ├── mono_euroc.cc
│ ├── mono_kitti.cc
│ └── mono_tum.cc
├── RGB-D
│ ├── TUM1.yaml
│ ├── TUM2.yaml
│ ├── TUM3.yaml
│ ├── associations
│ │ ├── fr1_desk.txt
│ │ ├── fr1_desk2.txt
│ │ ├── fr1_room.txt
│ │ ├── fr1_xyz.txt
│ │ ├── fr2_desk.txt
│ │ ├── fr2_xyz.txt
│ │ ├── fr3_nstr_tex_near.txt
│ │ ├── fr3_office.txt
│ │ ├── fr3_office_val.txt
│ │ ├── fr3_str_tex_far.txt
│ │ └── fr3_str_tex_near.txt
│ └── rgbd_tum.cc
├── ROS
│ ├── ORB_SLAM2
│ │ ├── Asus.yaml
│ │ ├── CMakeLists.txt
│ │ ├── manifest.xml
│ │ └── src
│ │ │ ├── ros_mono.cc
│ │ │ ├── ros_rgbd.cc
│ │ │ └── ros_stereo.cc
│ └── ORB_VIO
│ │ ├── CMakeLists.txt
│ │ ├── launch
│ │ └── testeuroc.launch
│ │ ├── manifest.xml
│ │ └── src
│ │ ├── MsgSync
│ │ ├── MsgSynchronizer.cpp
│ │ └── MsgSynchronizer.h
│ │ └── ros_vio.cc
└── Stereo
│ ├── EuRoC.yaml
│ ├── EuRoC_TimeStamps
│ ├── MH01.txt
│ ├── MH02.txt
│ ├── MH03.txt
│ ├── MH04.txt
│ ├── MH05.txt
│ ├── V101.txt
│ ├── V102.txt
│ ├── V103.txt
│ ├── V201.txt
│ ├── V202.txt
│ └── V203.txt
│ ├── KITTI00-02.yaml
│ ├── KITTI03.yaml
│ ├── KITTI04-12.yaml
│ ├── stereo_euroc.cc
│ └── stereo_kitti.cc
├── LICENSE.txt
├── License-gpl.txt
├── README.md
├── Thirdparty
├── DBoW2
│ ├── CMakeLists.txt
│ ├── DBoW2
│ │ ├── BowVector.cpp
│ │ ├── BowVector.h
│ │ ├── FClass.h
│ │ ├── FORB.cpp
│ │ ├── FORB.h
│ │ ├── FeatureVector.cpp
│ │ ├── FeatureVector.h
│ │ ├── ScoringObject.cpp
│ │ ├── ScoringObject.h
│ │ └── TemplatedVocabulary.h
│ ├── DUtils
│ │ ├── Random.cpp
│ │ ├── Random.h
│ │ ├── Timestamp.cpp
│ │ └── Timestamp.h
│ ├── LICENSE.txt
│ └── README.txt
└── g2o
│ ├── CMakeLists.txt
│ ├── README.txt
│ ├── cmake_modules
│ ├── FindBLAS.cmake
│ ├── FindCSparse.cmake
│ ├── FindCholmod.cmake
│ ├── FindEigen3.cmake
│ ├── FindLAPACK.cmake
│ └── FindSuiteSparse.cmake
│ ├── config.h
│ ├── config.h.in
│ ├── g2o
│ ├── core
│ │ ├── base_binary_edge.h
│ │ ├── base_binary_edge.hpp
│ │ ├── base_edge.h
│ │ ├── base_multi_edge.h
│ │ ├── base_multi_edge.hpp
│ │ ├── base_unary_edge.h
│ │ ├── base_unary_edge.hpp
│ │ ├── base_vertex.h
│ │ ├── base_vertex.hpp
│ │ ├── batch_stats.cpp
│ │ ├── batch_stats.h
│ │ ├── block_solver.h
│ │ ├── block_solver.hpp
│ │ ├── cache.cpp
│ │ ├── cache.h
│ │ ├── creators.h
│ │ ├── eigen_types.h
│ │ ├── estimate_propagator.cpp
│ │ ├── estimate_propagator.h
│ │ ├── factory.cpp
│ │ ├── factory.h
│ │ ├── hyper_dijkstra.cpp
│ │ ├── hyper_dijkstra.h
│ │ ├── hyper_graph.cpp
│ │ ├── hyper_graph.h
│ │ ├── hyper_graph_action.cpp
│ │ ├── hyper_graph_action.h
│ │ ├── jacobian_workspace.cpp
│ │ ├── jacobian_workspace.h
│ │ ├── linear_solver.h
│ │ ├── marginal_covariance_cholesky.cpp
│ │ ├── marginal_covariance_cholesky.h
│ │ ├── matrix_operations.h
│ │ ├── matrix_structure.cpp
│ │ ├── matrix_structure.h
│ │ ├── openmp_mutex.h
│ │ ├── optimizable_graph.cpp
│ │ ├── optimizable_graph.h
│ │ ├── optimization_algorithm.cpp
│ │ ├── optimization_algorithm.h
│ │ ├── optimization_algorithm_dogleg.cpp
│ │ ├── optimization_algorithm_dogleg.h
│ │ ├── optimization_algorithm_factory.cpp
│ │ ├── optimization_algorithm_factory.h
│ │ ├── optimization_algorithm_gauss_newton.cpp
│ │ ├── optimization_algorithm_gauss_newton.h
│ │ ├── optimization_algorithm_levenberg.cpp
│ │ ├── optimization_algorithm_levenberg.h
│ │ ├── optimization_algorithm_property.h
│ │ ├── optimization_algorithm_with_hessian.cpp
│ │ ├── optimization_algorithm_with_hessian.h
│ │ ├── parameter.cpp
│ │ ├── parameter.h
│ │ ├── parameter_container.cpp
│ │ ├── parameter_container.h
│ │ ├── robust_kernel.cpp
│ │ ├── robust_kernel.h
│ │ ├── robust_kernel_factory.cpp
│ │ ├── robust_kernel_factory.h
│ │ ├── robust_kernel_impl.cpp
│ │ ├── robust_kernel_impl.h
│ │ ├── solver.cpp
│ │ ├── solver.h
│ │ ├── sparse_block_matrix.h
│ │ ├── sparse_block_matrix.hpp
│ │ ├── sparse_block_matrix_ccs.h
│ │ ├── sparse_block_matrix_diagonal.h
│ │ ├── sparse_block_matrix_test.cpp
│ │ ├── sparse_optimizer.cpp
│ │ └── sparse_optimizer.h
│ ├── solvers
│ │ ├── linear_solver_cholmod.h
│ │ ├── linear_solver_dense.h
│ │ └── linear_solver_eigen.h
│ ├── stuff
│ │ ├── color_macros.h
│ │ ├── macros.h
│ │ ├── misc.h
│ │ ├── os_specific.c
│ │ ├── os_specific.h
│ │ ├── property.cpp
│ │ ├── property.h
│ │ ├── sparse_helper.cpp
│ │ ├── sparse_helper.h
│ │ ├── string_tools.cpp
│ │ ├── string_tools.h
│ │ ├── timeutil.cpp
│ │ └── timeutil.h
│ └── types
│ │ ├── se3_ops.h
│ │ ├── se3_ops.hpp
│ │ ├── se3quat.h
│ │ ├── sim3.h
│ │ ├── types_sba.cpp
│ │ ├── types_sba.h
│ │ ├── types_seven_dof_expmap.cpp
│ │ ├── types_seven_dof_expmap.h
│ │ ├── types_six_dof_expmap.cpp
│ │ └── types_six_dof_expmap.h
│ └── license-bsd.txt
├── Vocabulary
└── ORBvoc.bin
├── build.sh
├── cmake_modules
├── FindCholmod.cmake
└── FindEigen3.cmake
├── config
└── euroc.yaml
├── include
├── Converter.h
├── Frame.h
├── FrameDrawer.h
├── Initializer.h
├── KeyFrame.h
├── KeyFrameDatabase.h
├── LocalMapping.h
├── LoopClosing.h
├── Map.h
├── MapDrawer.h
├── MapPoint.h
├── ORBVocabulary.h
├── ORBextractor.h
├── ORBmatcher.h
├── Optimizer.h
├── PnPsolver.h
├── Sim3Solver.h
├── System.h
├── Tracking.h
└── Viewer.h
├── pyplotscripts
├── plotinit.py
└── plotnavstate.py
├── src
├── Converter.cc
├── Frame.cc
├── FrameDrawer.cc
├── IMU
│ ├── IMUPreintegrator.cpp
│ ├── IMUPreintegrator.h
│ ├── NavState.cpp
│ ├── NavState.h
│ ├── configparam.cpp
│ ├── configparam.h
│ ├── g2otypes.cpp
│ ├── g2otypes.h
│ ├── imudata.cpp
│ ├── imudata.h
│ ├── so3.cpp
│ └── so3.h
├── Initializer.cc
├── KeyFrame.cc
├── KeyFrameDatabase.cc
├── LocalMapping.cc
├── LoopClosing.cc
├── Map.cc
├── MapDrawer.cc
├── MapPoint.cc
├── ORBextractor.cc
├── ORBmatcher.cc
├── Optimizer.cc
├── PnPsolver.cc
├── Sim3Solver.cc
├── System.cc
├── Tracking.cc
└── Viewer.cc
└── tools
└── bin_vocabulary.cc
/master/LearnVIORB_NOROS/.gitignore:
--------------------------------------------------------------------------------
1 | *.user
2 | *~
3 | **/build/*
4 | **/lib/*
5 | Vocabulary/*.txt
6 | *.kdev4
7 | **/KeyFrameTrajectory.txt
8 | **/KeyFrameNavStateTrajectory.txt
9 | *.autosave
10 | **/tmp/*
11 | **/debug.txt
12 |
13 | Examples/ROS/ORB_SLAM2/Mono
14 | Examples/ROS/ORB_SLAM2/RGBD
15 | Examples/ROS/ORB_SLAM2/Stereo
16 | Examples/Monocular/mono_euroc
17 | Examples/Monocular/mono_kitti
18 | Examples/Monocular/mono_tum
19 | Examples/RGB-D/rgbd_tum
20 | Examples/Stereo/stereo_euroc
21 | Examples/Stereo/stereo_kitti
22 |
23 | Examples/ROS/ORB_VIO/VIO
24 |
25 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Dependencies.md:
--------------------------------------------------------------------------------
1 | ##List of Known Dependencies
2 | ###ORB-SLAM2 version 1.0
3 |
4 | In this document we list all the pieces of code included by ORB-SLAM2 and linked libraries which are not property of the authors of ORB-SLAM2.
5 |
6 |
7 | #####Code in **src** and **include** folders
8 |
9 | * *ORBextractor.cc*.
10 | This is a modified version of orb.cpp of OpenCV library. The original code is BSD licensed.
11 |
12 | * *PnPsolver.h, PnPsolver.cc*.
13 | This is a modified version of the epnp.h and epnp.cc of Vincent Lepetit.
14 | This code can be found in popular BSD licensed computer vision libraries as [OpenCV](https://github.com/Itseez/opencv/blob/master/modules/calib3d/src/epnp.cpp) and [OpenGV](https://github.com/laurentkneip/opengv/blob/master/src/absolute_pose/modules/Epnp.cpp). The original code is FreeBSD.
15 |
16 | * Function *ORBmatcher::DescriptorDistance* in *ORBmatcher.cc*.
17 | The code is from: http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetParallel.
18 | The code is in the public domain.
19 |
20 | #####Code in Thirdparty folder
21 |
22 | * All code in **DBoW2** folder.
23 | This is a modified version of [DBoW2](https://github.com/dorian3d/DBoW2) and [DLib](https://github.com/dorian3d/DLib) library. All files included are BSD licensed.
24 |
25 | * All code in **g2o** folder.
26 | This is a modified version of [g2o](https://github.com/RainerKuemmerle/g2o). All files included are BSD licensed.
27 |
28 | #####Library dependencies
29 |
30 | * **Pangolin (visualization and user interface)**.
31 | [MIT license](https://en.wikipedia.org/wiki/MIT_License).
32 |
33 | * **OpenCV**.
34 | BSD license.
35 |
36 | * **Eigen3**.
37 | For versions greater than 3.1.1 is MPL2, earlier versions are LGPLv3.
38 |
39 | * **BLAS** (required by g2o).
40 | [Freely-available software](http://www.netlib.org/blas/#_licensing).
41 |
42 | * **LAPACK**(required by g2o).
43 | BSD license.
44 |
45 | * **ROS (Optional, only if you build Examples/ROS)**.
46 | BSD license. In the manifest.xml the only declared package dependencies are roscpp, tf, sensor_msgs, image_transport, cv_bridge, which are all BSD licensed.
47 |
48 |
49 |
50 |
51 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/Monocular/EuRoC.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 |
3 | #--------------------------------------------------------------------------------------------
4 | # Camera Parameters. Adjust them!
5 | #--------------------------------------------------------------------------------------------
6 |
7 | # Camera calibration and distortion parameters (OpenCV)
8 | Camera.fx: 458.654
9 | Camera.fy: 457.296
10 | Camera.cx: 367.215
11 | Camera.cy: 248.375
12 |
13 | Camera.k1: -0.28340811
14 | Camera.k2: 0.07395907
15 | Camera.p1: 0.00019359
16 | Camera.p2: 1.76187114e-05
17 |
18 | # Camera frames per second
19 | Camera.fps: 20.0
20 |
21 | # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
22 | Camera.RGB: 1
23 |
24 | #--------------------------------------------------------------------------------------------
25 | # ORB Parameters
26 | #--------------------------------------------------------------------------------------------
27 |
28 | # ORB Extractor: Number of features per image
29 | ORBextractor.nFeatures: 1000
30 |
31 | # ORB Extractor: Scale factor between levels in the scale pyramid
32 | ORBextractor.scaleFactor: 1.2
33 |
34 | # ORB Extractor: Number of levels in the scale pyramid
35 | ORBextractor.nLevels: 8
36 |
37 | # ORB Extractor: Fast threshold
38 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
39 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
40 | # You can lower these values if your images have low contrast
41 | ORBextractor.iniThFAST: 20
42 | ORBextractor.minThFAST: 7
43 |
44 | #--------------------------------------------------------------------------------------------
45 | # Viewer Parameters
46 | #---------------------------------------------------------------------------------------------
47 | Viewer.KeyFrameSize: 0.05
48 | Viewer.KeyFrameLineWidth: 1
49 | Viewer.GraphLineWidth: 0.9
50 | Viewer.PointSize:2
51 | Viewer.CameraSize: 0.08
52 | Viewer.CameraLineWidth: 3
53 | Viewer.ViewpointX: 0
54 | Viewer.ViewpointY: -0.7
55 | Viewer.ViewpointZ: -1.8
56 | Viewer.ViewpointF: 500
57 |
58 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/Monocular/KITTI00-02.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 |
3 | #--------------------------------------------------------------------------------------------
4 | # Camera Parameters. Adjust them!
5 | #--------------------------------------------------------------------------------------------
6 |
7 | # Camera calibration and distortion parameters (OpenCV)
8 | Camera.fx: 718.856
9 | Camera.fy: 718.856
10 | Camera.cx: 607.1928
11 | Camera.cy: 185.2157
12 |
13 | Camera.k1: 0.0
14 | Camera.k2: 0.0
15 | Camera.p1: 0.0
16 | Camera.p2: 0.0
17 |
18 | # Camera frames per second
19 | Camera.fps: 10.0
20 |
21 | # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
22 | Camera.RGB: 1
23 |
24 | #--------------------------------------------------------------------------------------------
25 | # ORB Parameters
26 | #--------------------------------------------------------------------------------------------
27 |
28 | # ORB Extractor: Number of features per image
29 | ORBextractor.nFeatures: 2000
30 |
31 | # ORB Extractor: Scale factor between levels in the scale pyramid
32 | ORBextractor.scaleFactor: 1.2
33 |
34 | # ORB Extractor: Number of levels in the scale pyramid
35 | ORBextractor.nLevels: 8
36 |
37 | # ORB Extractor: Fast threshold
38 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
39 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
40 | # You can lower these values if your images have low contrast
41 | ORBextractor.iniThFAST: 20
42 | ORBextractor.minThFAST: 7
43 |
44 | #--------------------------------------------------------------------------------------------
45 | # Viewer Parameters
46 | #--------------------------------------------------------------------------------------------
47 | Viewer.KeyFrameSize: 0.1
48 | Viewer.KeyFrameLineWidth: 1
49 | Viewer.GraphLineWidth: 1
50 | Viewer.PointSize:2
51 | Viewer.CameraSize: 0.15
52 | Viewer.CameraLineWidth: 2
53 | Viewer.ViewpointX: 0
54 | Viewer.ViewpointY: -10
55 | Viewer.ViewpointZ: -0.1
56 | Viewer.ViewpointF: 2000
57 |
58 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/Monocular/KITTI03.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 |
3 | #--------------------------------------------------------------------------------------------
4 | # Camera Parameters. Adjust them!
5 | #--------------------------------------------------------------------------------------------
6 |
7 | # Camera calibration and distortion parameters (OpenCV)
8 | Camera.fx: 721.5377
9 | Camera.fy: 721.5377
10 | Camera.cx: 609.5593
11 | Camera.cy: 172.854
12 |
13 | Camera.k1: 0.0
14 | Camera.k2: 0.0
15 | Camera.p1: 0.0
16 | Camera.p2: 0.0
17 |
18 | # Camera frames per second
19 | Camera.fps: 10.0
20 |
21 | # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
22 | Camera.RGB: 1
23 |
24 | #--------------------------------------------------------------------------------------------
25 | # ORB Parameters
26 | #--------------------------------------------------------------------------------------------
27 |
28 | # ORB Extractor: Number of features per image
29 | ORBextractor.nFeatures: 2000
30 |
31 | # ORB Extractor: Scale factor between levels in the scale pyramid
32 | ORBextractor.scaleFactor: 1.2
33 |
34 | # ORB Extractor: Number of levels in the scale pyramid
35 | ORBextractor.nLevels: 8
36 |
37 | # ORB Extractor: Fast threshold
38 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
39 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
40 | # You can lower these values if your images have low contrast
41 | ORBextractor.iniThFAST: 20
42 | ORBextractor.minThFAST: 7
43 |
44 | #--------------------------------------------------------------------------------------------
45 | # Viewer Parameters
46 | #--------------------------------------------------------------------------------------------
47 | Viewer.KeyFrameSize: 0.1
48 | Viewer.KeyFrameLineWidth: 1
49 | Viewer.GraphLineWidth: 1
50 | Viewer.PointSize:2
51 | Viewer.CameraSize: 0.15
52 | Viewer.CameraLineWidth: 2
53 | Viewer.ViewpointX: 0
54 | Viewer.ViewpointY: -10
55 | Viewer.ViewpointZ: -0.1
56 | Viewer.ViewpointF: 2000
57 |
58 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/Monocular/KITTI04-12.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 |
3 | #--------------------------------------------------------------------------------------------
4 | # Camera Parameters. Adjust them!
5 | #--------------------------------------------------------------------------------------------
6 |
7 | # Camera calibration and distortion parameters (OpenCV)
8 | Camera.fx: 707.0912
9 | Camera.fy: 707.0912
10 | Camera.cx: 601.8873
11 | Camera.cy: 183.1104
12 |
13 | Camera.k1: 0.0
14 | Camera.k2: 0.0
15 | Camera.p1: 0.0
16 | Camera.p2: 0.0
17 |
18 | # Camera frames per second
19 | Camera.fps: 10.0
20 |
21 | # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
22 | Camera.RGB: 1
23 |
24 | #--------------------------------------------------------------------------------------------
25 | # ORB Parameters
26 | #--------------------------------------------------------------------------------------------
27 |
28 | # ORB Extractor: Number of features per image
29 | ORBextractor.nFeatures: 2000
30 |
31 | # ORB Extractor: Scale factor between levels in the scale pyramid
32 | ORBextractor.scaleFactor: 1.2
33 |
34 | # ORB Extractor: Number of levels in the scale pyramid
35 | ORBextractor.nLevels: 8
36 |
37 | # ORB Extractor: Fast threshold
38 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
39 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
40 | # You can lower these values if your images have low contrast
41 | ORBextractor.iniThFAST: 20
42 | ORBextractor.minThFAST: 7
43 |
44 | #--------------------------------------------------------------------------------------------
45 | # Viewer Parameters
46 | #--------------------------------------------------------------------------------------------
47 | Viewer.KeyFrameSize: 0.1
48 | Viewer.KeyFrameLineWidth: 1
49 | Viewer.GraphLineWidth: 1
50 | Viewer.PointSize:2
51 | Viewer.CameraSize: 0.15
52 | Viewer.CameraLineWidth: 2
53 | Viewer.ViewpointX: 0
54 | Viewer.ViewpointY: -10
55 | Viewer.ViewpointZ: -0.1
56 | Viewer.ViewpointF: 2000
57 |
58 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/Monocular/TUM1.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 |
3 | #--------------------------------------------------------------------------------------------
4 | # Camera Parameters. Adjust them!
5 | #--------------------------------------------------------------------------------------------
6 |
7 | # Camera calibration and distortion parameters (OpenCV)
8 | Camera.fx: 517.306408
9 | Camera.fy: 516.469215
10 | Camera.cx: 318.643040
11 | Camera.cy: 255.313989
12 |
13 | Camera.k1: 0.262383
14 | Camera.k2: -0.953104
15 | Camera.p1: -0.005358
16 | Camera.p2: 0.002628
17 | Camera.k3: 1.163314
18 |
19 | # Camera frames per second
20 | Camera.fps: 30.0
21 |
22 | # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
23 | Camera.RGB: 1
24 |
25 | #--------------------------------------------------------------------------------------------
26 | # ORB Parameters
27 | #--------------------------------------------------------------------------------------------
28 |
29 | # ORB Extractor: Number of features per image
30 | ORBextractor.nFeatures: 1000
31 |
32 | # ORB Extractor: Scale factor between levels in the scale pyramid
33 | ORBextractor.scaleFactor: 1.2
34 |
35 | # ORB Extractor: Number of levels in the scale pyramid
36 | ORBextractor.nLevels: 8
37 |
38 | # ORB Extractor: Fast threshold
39 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
40 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
41 | # You can lower these values if your images have low contrast
42 | ORBextractor.iniThFAST: 20
43 | ORBextractor.minThFAST: 7
44 |
45 | #--------------------------------------------------------------------------------------------
46 | # Viewer Parameters
47 | #--------------------------------------------------------------------------------------------
48 | Viewer.KeyFrameSize: 0.05
49 | Viewer.KeyFrameLineWidth: 1
50 | Viewer.GraphLineWidth: 0.9
51 | Viewer.PointSize:2
52 | Viewer.CameraSize: 0.08
53 | Viewer.CameraLineWidth: 3
54 | Viewer.ViewpointX: 0
55 | Viewer.ViewpointY: -0.7
56 | Viewer.ViewpointZ: -1.8
57 | Viewer.ViewpointF: 500
58 |
59 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/Monocular/TUM2.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 |
3 | #--------------------------------------------------------------------------------------------
4 | # Camera Parameters. Adjust them!
5 | #--------------------------------------------------------------------------------------------
6 |
7 | # Camera calibration and distortion parameters (OpenCV)
8 | Camera.fx: 520.908620
9 | Camera.fy: 521.007327
10 | Camera.cx: 325.141442
11 | Camera.cy: 249.701764
12 |
13 | Camera.k1: 0.231222
14 | Camera.k2: -0.784899
15 | Camera.p1: -0.003257
16 | Camera.p2: -0.000105
17 | Camera.k3: 0.917205
18 |
19 | # Camera frames per second
20 | Camera.fps: 30.0
21 |
22 | # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
23 | Camera.RGB: 1
24 |
25 | #--------------------------------------------------------------------------------------------
26 | # ORB Parameters
27 | #--------------------------------------------------------------------------------------------
28 |
29 | # ORB Extractor: Number of features per image
30 | ORBextractor.nFeatures: 1000
31 |
32 | # ORB Extractor: Scale factor between levels in the scale pyramid
33 | ORBextractor.scaleFactor: 1.2
34 |
35 | # ORB Extractor: Number of levels in the scale pyramid
36 | ORBextractor.nLevels: 8
37 |
38 | # ORB Extractor: Fast threshold
39 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
40 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
41 | # You can lower these values if your images have low contrast
42 | ORBextractor.iniThFAST: 20
43 | ORBextractor.minThFAST: 7
44 |
45 | #--------------------------------------------------------------------------------------------
46 | # Viewer Parameters
47 | #--------------------------------------------------------------------------------------------
48 | Viewer.KeyFrameSize: 0.05
49 | Viewer.KeyFrameLineWidth: 1
50 | Viewer.GraphLineWidth: 0.9
51 | Viewer.PointSize:2
52 | Viewer.CameraSize: 0.08
53 | Viewer.CameraLineWidth: 3
54 | Viewer.ViewpointX: 0
55 | Viewer.ViewpointY: -0.7
56 | Viewer.ViewpointZ: -1.8
57 | Viewer.ViewpointF: 500
58 |
59 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/Monocular/TUM3.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 |
3 | #--------------------------------------------------------------------------------------------
4 | # Camera Parameters. Adjust them!
5 | #--------------------------------------------------------------------------------------------
6 |
7 | # Camera calibration and distortion parameters (OpenCV)
8 | Camera.fx: 535.4
9 | Camera.fy: 539.2
10 | Camera.cx: 320.1
11 | Camera.cy: 247.6
12 |
13 | Camera.k1: 0.0
14 | Camera.k2: 0.0
15 | Camera.p1: 0.0
16 | Camera.p2: 0.0
17 |
18 | # Camera frames per second
19 | Camera.fps: 30.0
20 |
21 | # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
22 | Camera.RGB: 1
23 |
24 | #--------------------------------------------------------------------------------------------
25 | # ORB Parameters
26 | #--------------------------------------------------------------------------------------------
27 |
28 | # ORB Extractor: Number of features per image
29 | ORBextractor.nFeatures: 1000
30 |
31 | # ORB Extractor: Scale factor between levels in the scale pyramid
32 | ORBextractor.scaleFactor: 1.2
33 |
34 | # ORB Extractor: Number of levels in the scale pyramid
35 | ORBextractor.nLevels: 8
36 |
37 | # ORB Extractor: Fast threshold
38 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
39 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
40 | # You can lower these values if your images have low contrast
41 | ORBextractor.iniThFAST: 20
42 | ORBextractor.minThFAST: 7
43 |
44 | #--------------------------------------------------------------------------------------------
45 | # Viewer Parameters
46 | #--------------------------------------------------------------------------------------------
47 | Viewer.KeyFrameSize: 0.05
48 | Viewer.KeyFrameLineWidth: 1
49 | Viewer.GraphLineWidth: 0.9
50 | Viewer.PointSize:2
51 | Viewer.CameraSize: 0.08
52 | Viewer.CameraLineWidth: 3
53 | Viewer.ViewpointX: 0
54 | Viewer.ViewpointY: -0.7
55 | Viewer.ViewpointZ: -1.8
56 | Viewer.ViewpointF: 500
57 |
58 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/RGB-D/TUM1.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 |
3 | #--------------------------------------------------------------------------------------------
4 | # Camera Parameters. Adjust them!
5 | #--------------------------------------------------------------------------------------------
6 |
7 | # Camera calibration and distortion parameters (OpenCV)
8 | Camera.fx: 517.306408
9 | Camera.fy: 516.469215
10 | Camera.cx: 318.643040
11 | Camera.cy: 255.313989
12 |
13 | Camera.k1: 0.262383
14 | Camera.k2: -0.953104
15 | Camera.p1: -0.005358
16 | Camera.p2: 0.002628
17 | Camera.k3: 1.163314
18 |
19 | Camera.width: 640
20 | Camera.height: 480
21 |
22 | # Camera frames per second
23 | Camera.fps: 30.0
24 |
25 | # IR projector baseline times fx (aprox.)
26 | Camera.bf: 40.0
27 |
28 | # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
29 | Camera.RGB: 1
30 |
31 | # Close/Far threshold. Baseline times.
32 | ThDepth: 40.0
33 |
34 | # Deptmap values factor
35 | DepthMapFactor: 5000.0
36 |
37 | #--------------------------------------------------------------------------------------------
38 | # ORB Parameters
39 | #--------------------------------------------------------------------------------------------
40 |
41 | # ORB Extractor: Number of features per image
42 | ORBextractor.nFeatures: 1000
43 |
44 | # ORB Extractor: Scale factor between levels in the scale pyramid
45 | ORBextractor.scaleFactor: 1.2
46 |
47 | # ORB Extractor: Number of levels in the scale pyramid
48 | ORBextractor.nLevels: 8
49 |
50 | # ORB Extractor: Fast threshold
51 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
52 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
53 | # You can lower these values if your images have low contrast
54 | ORBextractor.iniThFAST: 20
55 | ORBextractor.minThFAST: 7
56 |
57 | #--------------------------------------------------------------------------------------------
58 | # Viewer Parameters
59 | #--------------------------------------------------------------------------------------------
60 | Viewer.KeyFrameSize: 0.05
61 | Viewer.KeyFrameLineWidth: 1
62 | Viewer.GraphLineWidth: 0.9
63 | Viewer.PointSize:2
64 | Viewer.CameraSize: 0.08
65 | Viewer.CameraLineWidth: 3
66 | Viewer.ViewpointX: 0
67 | Viewer.ViewpointY: -0.7
68 | Viewer.ViewpointZ: -1.8
69 | Viewer.ViewpointF: 500
70 |
71 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/RGB-D/TUM2.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 |
3 | #--------------------------------------------------------------------------------------------
4 | # Camera Parameters. Adjust them!
5 | #--------------------------------------------------------------------------------------------
6 |
7 | # Camera calibration and distortion parameters (OpenCV)
8 | Camera.fx: 520.908620
9 | Camera.fy: 521.007327
10 | Camera.cx: 325.141442
11 | Camera.cy: 249.701764
12 |
13 | Camera.k1: 0.231222
14 | Camera.k2: -0.784899
15 | Camera.p1: -0.003257
16 | Camera.p2: -0.000105
17 | Camera.k3: 0.917205
18 |
19 | Camera.width: 640
20 | Camera.height: 480
21 |
22 | # Camera frames per second
23 | Camera.fps: 30.0
24 |
25 | # IR projector baseline times fx (aprox.)
26 | Camera.bf: 40.0
27 |
28 | # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
29 | Camera.RGB: 1
30 |
31 | # Close/Far threshold. Baseline times.
32 | ThDepth: 40.0
33 |
34 | # Deptmap values factor
35 | DepthMapFactor: 5208.0
36 |
37 | #--------------------------------------------------------------------------------------------
38 | # ORB Parameters
39 | #--------------------------------------------------------------------------------------------
40 |
41 | # ORB Extractor: Number of features per image
42 | ORBextractor.nFeatures: 1000
43 |
44 | # ORB Extractor: Scale factor between levels in the scale pyramid
45 | ORBextractor.scaleFactor: 1.2
46 |
47 | # ORB Extractor: Number of levels in the scale pyramid
48 | ORBextractor.nLevels: 8
49 |
50 | # ORB Extractor: Fast threshold
51 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
52 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
53 | # You can lower these values if your images have low contrast
54 | ORBextractor.iniThFAST: 20
55 | ORBextractor.minThFAST: 7
56 |
57 | #--------------------------------------------------------------------------------------------
58 | # Viewer Parameters
59 | #--------------------------------------------------------------------------------------------
60 | Viewer.KeyFrameSize: 0.05
61 | Viewer.KeyFrameLineWidth: 1
62 | Viewer.GraphLineWidth: 0.9
63 | Viewer.PointSize:2
64 | Viewer.CameraSize: 0.08
65 | Viewer.CameraLineWidth: 3
66 | Viewer.ViewpointX: 0
67 | Viewer.ViewpointY: -0.7
68 | Viewer.ViewpointZ: -1.8
69 | Viewer.ViewpointF: 500
70 |
71 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/RGB-D/TUM3.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 |
3 | #--------------------------------------------------------------------------------------------
4 | # Camera Parameters. Adjust them!
5 | #--------------------------------------------------------------------------------------------
6 |
7 | # Camera calibration and distortion parameters (OpenCV)
8 | Camera.fx: 535.4
9 | Camera.fy: 539.2
10 | Camera.cx: 320.1
11 | Camera.cy: 247.6
12 |
13 | Camera.k1: 0.0
14 | Camera.k2: 0.0
15 | Camera.p1: 0.0
16 | Camera.p2: 0.0
17 |
18 | Camera.width: 640
19 | Camera.height: 480
20 |
21 | # Camera frames per second
22 | Camera.fps: 30.0
23 |
24 | # IR projector baseline times fx (aprox.)
25 | Camera.bf: 40.0
26 |
27 | # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
28 | Camera.RGB: 1
29 |
30 | # Close/Far threshold. Baseline times.
31 | ThDepth: 40.0
32 |
33 | # Deptmap values factor
34 | DepthMapFactor: 5000.0
35 |
36 | #--------------------------------------------------------------------------------------------
37 | # ORB Parameters
38 | #--------------------------------------------------------------------------------------------
39 |
40 | # ORB Extractor: Number of features per image
41 | ORBextractor.nFeatures: 1000
42 |
43 | # ORB Extractor: Scale factor between levels in the scale pyramid
44 | ORBextractor.scaleFactor: 1.2
45 |
46 | # ORB Extractor: Number of levels in the scale pyramid
47 | ORBextractor.nLevels: 8
48 |
49 | # ORB Extractor: Fast threshold
50 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
51 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
52 | # You can lower these values if your images have low contrast
53 | ORBextractor.iniThFAST: 20
54 | ORBextractor.minThFAST: 7
55 |
56 | #--------------------------------------------------------------------------------------------
57 | # Viewer Parameters
58 | #--------------------------------------------------------------------------------------------
59 | Viewer.KeyFrameSize: 0.05
60 | Viewer.KeyFrameLineWidth: 1
61 | Viewer.GraphLineWidth: 0.9
62 | Viewer.PointSize:2
63 | Viewer.CameraSize: 0.08
64 | Viewer.CameraLineWidth: 3
65 | Viewer.ViewpointX: 0
66 | Viewer.ViewpointY: -0.7
67 | Viewer.ViewpointZ: -1.8
68 | Viewer.ViewpointF: 500
69 |
70 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/ROS/ORB_SLAM2/Asus.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 |
3 | #--------------------------------------------------------------------------------------------
4 | # Camera Parameters. Adjust them!
5 | #--------------------------------------------------------------------------------------------
6 |
7 | # Camera calibration and distortion parameters (OpenCV)
8 | Camera.fx: 535.4
9 | Camera.fy: 539.2
10 | Camera.cx: 320.1
11 | Camera.cy: 247.6
12 |
13 | Camera.k1: 0.0
14 | Camera.k2: 0.0
15 | Camera.p1: 0.0
16 | Camera.p2: 0.0
17 |
18 | Camera.width: 640
19 | Camera.height: 480
20 |
21 | # Camera frames per second
22 | Camera.fps: 30.0
23 |
24 | # IR projector baseline times fx (aprox.)
25 | Camera.bf: 40.0
26 |
27 | # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
28 | Camera.RGB: 1
29 |
30 | # Close/Far threshold. Baseline times.
31 | ThDepth: 40.0
32 |
33 | # Deptmap values factor
34 | DepthMapFactor: 1.0
35 |
36 | #--------------------------------------------------------------------------------------------
37 | # ORB Parameters
38 | #--------------------------------------------------------------------------------------------
39 |
40 | # ORB Extractor: Number of features per image
41 | ORBextractor.nFeatures: 1000
42 |
43 | # ORB Extractor: Scale factor between levels in the scale pyramid
44 | ORBextractor.scaleFactor: 1.2
45 |
46 | # ORB Extractor: Number of levels in the scale pyramid
47 | ORBextractor.nLevels: 8
48 |
49 | # ORB Extractor: Fast threshold
50 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
51 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
52 | # You can lower these values if your images have low contrast
53 | ORBextractor.iniThFAST: 20
54 | ORBextractor.minThFAST: 7
55 |
56 | #--------------------------------------------------------------------------------------------
57 | # Viewer Parameters
58 | #--------------------------------------------------------------------------------------------
59 | Viewer.KeyFrameSize: 0.05
60 | Viewer.KeyFrameLineWidth: 1
61 | Viewer.GraphLineWidth: 0.9
62 | Viewer.PointSize:2
63 | Viewer.CameraSize: 0.08
64 | Viewer.CameraLineWidth: 3
65 | Viewer.ViewpointX: 0
66 | Viewer.ViewpointY: -0.7
67 | Viewer.ViewpointZ: -1.8
68 | Viewer.ViewpointF: 500
69 |
70 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/ROS/ORB_SLAM2/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.4.6)
2 | include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
3 |
4 | rosbuild_init()
5 |
6 | IF(NOT ROS_BUILD_TYPE)
7 | SET(ROS_BUILD_TYPE Release)
8 | ENDIF()
9 |
10 | MESSAGE("Build type: " ${ROS_BUILD_TYPE})
11 |
12 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ")
13 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native")
14 |
15 | # Check C++11 or C++0x support
16 | include(CheckCXXCompilerFlag)
17 | CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
18 | CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
19 | if(COMPILER_SUPPORTS_CXX11)
20 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
21 | add_definitions(-DCOMPILEDWITHC11)
22 | message(STATUS "Using flag -std=c++11.")
23 | elseif(COMPILER_SUPPORTS_CXX0X)
24 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
25 | add_definitions(-DCOMPILEDWITHC0X)
26 | message(STATUS "Using flag -std=c++0x.")
27 | else()
28 | message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.")
29 | endif()
30 |
31 | LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/../../../cmake_modules)
32 |
33 | find_package(OpenCV 2.4.3 REQUIRED)
34 | find_package(Eigen3 3.1.0 REQUIRED)
35 | find_package(Pangolin REQUIRED)
36 |
37 | include_directories(
38 | ${PROJECT_SOURCE_DIR}
39 | ${PROJECT_SOURCE_DIR}/../../../
40 | ${PROJECT_SOURCE_DIR}/../../../include
41 | ${Pangolin_INCLUDE_DIRS}
42 | )
43 |
44 | set(LIBS
45 | ${OpenCV_LIBS}
46 | ${EIGEN3_LIBS}
47 | ${Pangolin_LIBRARIES}
48 | ${PROJECT_SOURCE_DIR}/../../../Thirdparty/DBoW2/lib/libDBoW2.so
49 | ${PROJECT_SOURCE_DIR}/../../../Thirdparty/g2o/lib/libg2o.so
50 | ${PROJECT_SOURCE_DIR}/../../../lib/libORB_SLAM2.so
51 | )
52 |
53 | # Node for monocular camera
54 | rosbuild_add_executable(Mono
55 | src/ros_mono.cc
56 | )
57 |
58 | target_link_libraries(Mono
59 | ${LIBS}
60 | )
61 |
62 | # Node for stereo camera
63 | rosbuild_add_executable(Stereo
64 | src/ros_stereo.cc
65 | )
66 |
67 | target_link_libraries(Stereo
68 | ${LIBS}
69 | )
70 |
71 | # Node for RGB-D camera
72 | rosbuild_add_executable(RGBD
73 | src/ros_rgbd.cc
74 | )
75 |
76 | target_link_libraries(RGBD
77 | ${LIBS}
78 | )
79 |
80 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/ROS/ORB_SLAM2/manifest.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | ORB_SLAM2
5 |
6 |
7 | Raul Mur-Artal
8 | GPLv3
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/ROS/ORB_SLAM2/src/ros_mono.cc:
--------------------------------------------------------------------------------
1 | /**
2 | * This file is part of ORB-SLAM2.
3 | *
4 | * Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza)
5 | * For more information see
6 | *
7 | * ORB-SLAM2 is free software: you can redistribute it and/or modify
8 | * it under the terms of the GNU General Public License as published by
9 | * the Free Software Foundation, either version 3 of the License, or
10 | * (at your option) any later version.
11 | *
12 | * ORB-SLAM2 is distributed in the hope that it will be useful,
13 | * but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | * GNU General Public License for more details.
16 | *
17 | * You should have received a copy of the GNU General Public License
18 | * along with ORB-SLAM2. If not, see .
19 | */
20 |
21 |
22 | #include
23 | #include
24 | #include
25 | #include
26 |
27 | #include
28 | #include
29 |
30 | #include
31 |
32 | #include"../../../include/System.h"
33 |
34 | using namespace std;
35 |
36 | class ImageGrabber
37 | {
38 | public:
39 | ImageGrabber(ORB_SLAM2::System* pSLAM):mpSLAM(pSLAM){}
40 |
41 | void GrabImage(const sensor_msgs::ImageConstPtr& msg);
42 |
43 | ORB_SLAM2::System* mpSLAM;
44 | };
45 |
46 | int main(int argc, char **argv)
47 | {
48 | ros::init(argc, argv, "Mono");
49 | ros::start();
50 |
51 | if(argc != 3)
52 | {
53 | cerr << endl << "Usage: rosrun ORB_SLAM2 Mono path_to_vocabulary path_to_settings" << endl;
54 | ros::shutdown();
55 | return 1;
56 | }
57 |
58 | // Create SLAM system. It initializes all system threads and gets ready to process frames.
59 | ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true);
60 |
61 | ImageGrabber igb(&SLAM);
62 |
63 | ros::NodeHandle nodeHandler;
64 | ros::Subscriber sub = nodeHandler.subscribe("/camera/image_raw", 1, &ImageGrabber::GrabImage,&igb);
65 |
66 | ros::spin();
67 |
68 | // Stop all threads
69 | SLAM.Shutdown();
70 |
71 | // Save camera trajectory
72 | SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
73 |
74 | ros::shutdown();
75 |
76 | return 0;
77 | }
78 |
79 | void ImageGrabber::GrabImage(const sensor_msgs::ImageConstPtr& msg)
80 | {
81 | // Copy the ros image message to cv::Mat.
82 | cv_bridge::CvImageConstPtr cv_ptr;
83 | try
84 | {
85 | cv_ptr = cv_bridge::toCvShare(msg);
86 | }
87 | catch (cv_bridge::Exception& e)
88 | {
89 | ROS_ERROR("cv_bridge exception: %s", e.what());
90 | return;
91 | }
92 |
93 | mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec());
94 | }
95 |
96 |
97 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/ROS/ORB_SLAM2/src/ros_rgbd.cc:
--------------------------------------------------------------------------------
1 | /**
2 | * This file is part of ORB-SLAM2.
3 | *
4 | * Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza)
5 | * For more information see
6 | *
7 | * ORB-SLAM2 is free software: you can redistribute it and/or modify
8 | * it under the terms of the GNU General Public License as published by
9 | * the Free Software Foundation, either version 3 of the License, or
10 | * (at your option) any later version.
11 | *
12 | * ORB-SLAM2 is distributed in the hope that it will be useful,
13 | * but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | * GNU General Public License for more details.
16 | *
17 | * You should have received a copy of the GNU General Public License
18 | * along with ORB-SLAM2. If not, see .
19 | */
20 |
21 |
22 | #include
23 | #include
24 | #include
25 | #include
26 |
27 | #include
28 | #include
29 | #include
30 | #include
31 | #include
32 |
33 | #include
34 |
35 | #include"../../../include/System.h"
36 |
37 | using namespace std;
38 |
39 | class ImageGrabber
40 | {
41 | public:
42 | ImageGrabber(ORB_SLAM2::System* pSLAM):mpSLAM(pSLAM){}
43 |
44 | void GrabRGBD(const sensor_msgs::ImageConstPtr& msgRGB,const sensor_msgs::ImageConstPtr& msgD);
45 |
46 | ORB_SLAM2::System* mpSLAM;
47 | };
48 |
49 | int main(int argc, char **argv)
50 | {
51 | ros::init(argc, argv, "RGBD");
52 | ros::start();
53 |
54 | if(argc != 3)
55 | {
56 | cerr << endl << "Usage: rosrun ORB_SLAM2 RGBD path_to_vocabulary path_to_settings" << endl;
57 | ros::shutdown();
58 | return 1;
59 | }
60 |
61 | // Create SLAM system. It initializes all system threads and gets ready to process frames.
62 | ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::RGBD,true);
63 |
64 | ImageGrabber igb(&SLAM);
65 |
66 | ros::NodeHandle nh;
67 |
68 | message_filters::Subscriber rgb_sub(nh, "/camera/rgb/image_raw", 1);
69 | message_filters::Subscriber depth_sub(nh, "camera/depth_registered/image_raw", 1);
70 | typedef message_filters::sync_policies::ApproximateTime sync_pol;
71 | message_filters::Synchronizer sync(sync_pol(10), rgb_sub,depth_sub);
72 | sync.registerCallback(boost::bind(&ImageGrabber::GrabRGBD,&igb,_1,_2));
73 |
74 | ros::spin();
75 |
76 | // Stop all threads
77 | SLAM.Shutdown();
78 |
79 | // Save camera trajectory
80 | SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
81 |
82 | ros::shutdown();
83 |
84 | return 0;
85 | }
86 |
87 | void ImageGrabber::GrabRGBD(const sensor_msgs::ImageConstPtr& msgRGB,const sensor_msgs::ImageConstPtr& msgD)
88 | {
89 | // Copy the ros image message to cv::Mat.
90 | cv_bridge::CvImageConstPtr cv_ptrRGB;
91 | try
92 | {
93 | cv_ptrRGB = cv_bridge::toCvShare(msgRGB);
94 | }
95 | catch (cv_bridge::Exception& e)
96 | {
97 | ROS_ERROR("cv_bridge exception: %s", e.what());
98 | return;
99 | }
100 |
101 | cv_bridge::CvImageConstPtr cv_ptrD;
102 | try
103 | {
104 | cv_ptrD = cv_bridge::toCvShare(msgD);
105 | }
106 | catch (cv_bridge::Exception& e)
107 | {
108 | ROS_ERROR("cv_bridge exception: %s", e.what());
109 | return;
110 | }
111 |
112 | mpSLAM->TrackRGBD(cv_ptrRGB->image,cv_ptrD->image,cv_ptrRGB->header.stamp.toSec());
113 | }
114 |
115 |
116 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/ROS/ORB_VIO/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.4.6)
2 | #include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
3 |
4 | #rosbuild_init()
5 |
6 | #IF(NOT ROS_BUILD_TYPE)
7 | # SET(ROS_BUILD_TYPE Release)
8 | #ENDIF()
9 |
10 | #MESSAGE("Build type: " ${ROS_BUILD_TYPE})
11 |
12 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ")
13 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native")
14 |
15 | # Check C++11 or C++0x support
16 | include(CheckCXXCompilerFlag)
17 | CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
18 | CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
19 | if(COMPILER_SUPPORTS_CXX11)
20 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
21 | add_definitions(-DCOMPILEDWITHC11)
22 | message(STATUS "Using flag -std=c++11.")
23 | elseif(COMPILER_SUPPORTS_CXX0X)
24 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
25 | add_definitions(-DCOMPILEDWITHC0X)
26 | message(STATUS "Using flag -std=c++0x.")
27 | else()
28 | message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.")
29 | endif()
30 |
31 | LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/../../../cmake_modules)
32 |
33 | find_package(OpenCV 2.4.3 REQUIRED)
34 | find_package(Eigen3 3.1.0 REQUIRED)
35 | find_package(Pangolin REQUIRED)
36 |
37 | include_directories(
38 | ${PROJECT_SOURCE_DIR}
39 | ${PROJECT_SOURCE_DIR}/../../../
40 | ${PROJECT_SOURCE_DIR}/../../../src
41 | ${PROJECT_SOURCE_DIR}/../../../include
42 | ${Pangolin_INCLUDE_DIRS}
43 | )
44 |
45 | set(LIBS
46 | ${OpenCV_LIBS}
47 | ${EIGEN3_LIBS}
48 | ${Pangolin_LIBRARIES}
49 | ${PROJECT_SOURCE_DIR}/../../../Thirdparty/DBoW2/lib/libDBoW2.so
50 | ${PROJECT_SOURCE_DIR}/../../../Thirdparty/g2o/lib/libg2o.so
51 | ${PROJECT_SOURCE_DIR}/../../../lib/libORB_SLAM2.so
52 | #/home/fyj/ThirdParty/OPENCV249/lib/libopencv_calib3d.so
53 | #/home/fyj/ThirdParty/OPENCV249/lib/libopencv_core.so
54 | #/home/fyj/ThirdParty/OPENCV249/lib/libopencv_flann.so
55 | #/home/fyj/ThirdParty/OPENCV249/lib/libopencv_highgui.so
56 | #/home/fyj/ThirdParty/OPENCV249/lib/libopencv_imgproc.so
57 | #/home/fyj/ThirdParty/OPENCV249/lib/libopencv_features2d.so
58 | #/home/fyj/ThirdParty/OPENCV249/lib/libopencv_superres.so
59 | #/home/fyj/ThirdParty/OPENCV249/lib/libopencv_legacy.so
60 | )
61 |
62 | # Node for monocular camera
63 | #rosbuild_add_executable(VIO
64 | #src/ros_vio.cc
65 | #src/MsgSync/MsgSynchronizer.cpp
66 | #src/MsgSync/MsgSynchronizer.h
67 | #)
68 | add_executable(VIO
69 | src/ros_vio.cc
70 | )
71 | target_link_libraries(VIO
72 | ${LIBS}
73 | )
74 |
75 |
76 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/ROS/ORB_VIO/launch/testeuroc.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/ROS/ORB_VIO/manifest.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | ORB_SLAM2
5 |
6 |
7 | Raul Mur-Artal
8 | GPLv3
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/ROS/ORB_VIO/src/MsgSync/MsgSynchronizer.h:
--------------------------------------------------------------------------------
1 | #ifndef MSGSYNCHRONIZER_H
2 | #define MSGSYNCHRONIZER_H
3 |
4 | #include
5 | #include
6 | #include
7 | #include
8 | #include
9 |
10 | using namespace std;
11 |
12 | namespace ORBVIO
13 | {
14 | class MsgSynchronizer
15 | {
16 | public:
17 | enum Status{
18 | NOTINIT = 0,
19 | INIT,
20 | NORMAL
21 | };
22 |
23 | MsgSynchronizer(const double& imagedelay = 0.);
24 | ~MsgSynchronizer();
25 |
26 | // add messages in callbacks
27 | void addImageMsg(const sensor_msgs::ImageConstPtr &imgmsg);
28 | void addImuMsg(const sensor_msgs::ImuConstPtr &imumsg);
29 |
30 | // loop in main function to handle all messages
31 | bool getRecentMsgs(sensor_msgs::ImageConstPtr &imgmsg, std::vector &vimumsgs);
32 |
33 | void clearMsgs(void);
34 |
35 | // for message callback if needed
36 | void imageCallback(const sensor_msgs::ImageConstPtr& msg);
37 | void imuCallback(const sensor_msgs::ImuConstPtr& msg);
38 |
39 | //
40 | inline Status getStatus(void) {return _status;}
41 |
42 | double getImageDelaySec(void) const {return _imageMsgDelaySec;}
43 |
44 | private:
45 | double _imageMsgDelaySec; // image message delay to imu message, in seconds
46 | std::queue _imageMsgQueue;
47 | std::queue _imuMsgQueue;
48 | ros::Time _imuMsgTimeStart;
49 | Status _status;
50 | int _dataUnsyncCnt;
51 | };
52 |
53 | }
54 |
55 | #endif // MSGSYNCHRONIZER_H
56 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/Stereo/KITTI00-02.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 |
3 | #--------------------------------------------------------------------------------------------
4 | # Camera Parameters. Adjust them!
5 | #--------------------------------------------------------------------------------------------
6 |
7 | # Camera calibration and distortion parameters (OpenCV)
8 | Camera.fx: 718.856
9 | Camera.fy: 718.856
10 | Camera.cx: 607.1928
11 | Camera.cy: 185.2157
12 |
13 | Camera.k1: 0.0
14 | Camera.k2: 0.0
15 | Camera.p1: 0.0
16 | Camera.p2: 0.0
17 |
18 | Camera.width: 1241
19 | Camera.height: 376
20 |
21 | # Camera frames per second
22 | Camera.fps: 10.0
23 |
24 | # stereo baseline times fx
25 | Camera.bf: 386.1448
26 |
27 | # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
28 | Camera.RGB: 1
29 |
30 | # Close/Far threshold. Baseline times.
31 | ThDepth: 35
32 |
33 | #--------------------------------------------------------------------------------------------
34 | # ORB Parameters
35 | #--------------------------------------------------------------------------------------------
36 |
37 | # ORB Extractor: Number of features per image
38 | ORBextractor.nFeatures: 2000
39 |
40 | # ORB Extractor: Scale factor between levels in the scale pyramid
41 | ORBextractor.scaleFactor: 1.2
42 |
43 | # ORB Extractor: Number of levels in the scale pyramid
44 | ORBextractor.nLevels: 8
45 |
46 | # ORB Extractor: Fast threshold
47 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
48 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
49 | # You can lower these values if your images have low contrast
50 | ORBextractor.iniThFAST: 20
51 | ORBextractor.minThFAST: 7
52 |
53 | #--------------------------------------------------------------------------------------------
54 | # Viewer Parameters
55 | #--------------------------------------------------------------------------------------------
56 | Viewer.KeyFrameSize: 0.6
57 | Viewer.KeyFrameLineWidth: 2
58 | Viewer.GraphLineWidth: 1
59 | Viewer.PointSize:2
60 | Viewer.CameraSize: 0.7
61 | Viewer.CameraLineWidth: 3
62 | Viewer.ViewpointX: 0
63 | Viewer.ViewpointY: -100
64 | Viewer.ViewpointZ: -0.1
65 | Viewer.ViewpointF: 2000
66 |
67 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/Stereo/KITTI03.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 |
3 | #--------------------------------------------------------------------------------------------
4 | # Camera Parameters. Adjust them!
5 | #--------------------------------------------------------------------------------------------
6 |
7 | # Camera calibration and distortion parameters (OpenCV)
8 | Camera.fx: 721.5377
9 | Camera.fy: 721.5377
10 | Camera.cx: 609.5593
11 | Camera.cy: 172.854
12 |
13 | Camera.k1: 0.0
14 | Camera.k2: 0.0
15 | Camera.p1: 0.0
16 | Camera.p2: 0.0
17 |
18 | Camera.width: 1241
19 | Camera.height: 376
20 |
21 | # Camera frames per second
22 | Camera.fps: 10.0
23 |
24 | # stereo baseline times fx
25 | Camera.bf: 387.5744
26 |
27 | # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
28 | Camera.RGB: 1
29 |
30 | # Close/Far threshold. Baseline times.
31 | ThDepth: 40
32 |
33 | #--------------------------------------------------------------------------------------------
34 | # ORB Parameters
35 | #--------------------------------------------------------------------------------------------
36 |
37 | # ORB Extractor: Number of features per image
38 | ORBextractor.nFeatures: 2000
39 |
40 | # ORB Extractor: Scale factor between levels in the scale pyramid
41 | ORBextractor.scaleFactor: 1.2
42 |
43 | # ORB Extractor: Number of levels in the scale pyramid
44 | ORBextractor.nLevels: 8
45 |
46 | # ORB Extractor: Fast threshold
47 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
48 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
49 | # You can lower these values if your images have low contrast
50 | ORBextractor.iniThFAST: 20
51 | ORBextractor.minThFAST: 7
52 |
53 | #--------------------------------------------------------------------------------------------
54 | # Viewer Parameters
55 | #--------------------------------------------------------------------------------------------
56 | Viewer.KeyFrameSize: 0.6
57 | Viewer.KeyFrameLineWidth: 2
58 | Viewer.GraphLineWidth: 1
59 | Viewer.PointSize:2
60 | Viewer.CameraSize: 0.7
61 | Viewer.CameraLineWidth: 3
62 | Viewer.ViewpointX: 0
63 | Viewer.ViewpointY: -100
64 | Viewer.ViewpointZ: -0.1
65 | Viewer.ViewpointF: 2000
66 |
67 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Examples/Stereo/KITTI04-12.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 |
3 | #--------------------------------------------------------------------------------------------
4 | # Camera Parameters. Adjust them!
5 | #--------------------------------------------------------------------------------------------
6 |
7 | # Camera calibration and distortion parameters (OpenCV)
8 | Camera.fx: 707.0912
9 | Camera.fy: 707.0912
10 | Camera.cx: 601.8873
11 | Camera.cy: 183.1104
12 |
13 | Camera.k1: 0.0
14 | Camera.k2: 0.0
15 | Camera.p1: 0.0
16 | Camera.p2: 0.0
17 |
18 | Camera.width: 1241
19 | Camera.height: 376
20 |
21 | # Camera frames per second
22 | Camera.fps: 10.0
23 |
24 | # stereo baseline times fx
25 | Camera.bf: 379.8145
26 |
27 | # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
28 | Camera.RGB: 1
29 |
30 | # Close/Far threshold. Baseline times.
31 | ThDepth: 40
32 |
33 | #--------------------------------------------------------------------------------------------
34 | # ORB Parameters
35 | #--------------------------------------------------------------------------------------------
36 |
37 | # ORB Extractor: Number of features per image
38 | ORBextractor.nFeatures: 2000
39 |
40 | # ORB Extractor: Scale factor between levels in the scale pyramid
41 | ORBextractor.scaleFactor: 1.2
42 |
43 | # ORB Extractor: Number of levels in the scale pyramid
44 | ORBextractor.nLevels: 8
45 |
46 | # ORB Extractor: Fast threshold
47 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
48 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
49 | # You can lower these values if your images have low contrast
50 | ORBextractor.iniThFAST: 12
51 | ORBextractor.minThFAST: 7
52 |
53 | #--------------------------------------------------------------------------------------------
54 | # Viewer Parameters
55 | #--------------------------------------------------------------------------------------------
56 | Viewer.KeyFrameSize: 0.6
57 | Viewer.KeyFrameLineWidth: 2
58 | Viewer.GraphLineWidth: 1
59 | Viewer.PointSize:2
60 | Viewer.CameraSize: 0.7
61 | Viewer.CameraLineWidth: 3
62 | Viewer.ViewpointX: 0
63 | Viewer.ViewpointY: -100
64 | Viewer.ViewpointZ: -0.1
65 | Viewer.ViewpointF: 2000
66 |
67 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/LICENSE.txt:
--------------------------------------------------------------------------------
1 | ORB-SLAM2 is released under a GPLv3 license (see License-gpl.txt).
2 | Please see Dependencies.md for a list of all included code and library dependencies which are not property of the authors of ORB-SLAM2.
3 |
4 | For a closed-source version of ORB-SLAM2 for commercial purposes, please contact the authors.
5 |
6 | If you use ORB-SLAM in an academic work, please cite the most relevant publication associated by visiting:
7 | https://github.com/raulmur/ORB_SLAM2
8 |
9 |
10 |
11 |
12 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Thirdparty/DBoW2/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8)
2 | project(DBoW2)
3 |
4 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ")
5 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native")
6 |
7 | set(HDRS_DBOW2
8 | DBoW2/BowVector.h
9 | DBoW2/FORB.h
10 | DBoW2/FClass.h
11 | DBoW2/FeatureVector.h
12 | DBoW2/ScoringObject.h
13 | DBoW2/TemplatedVocabulary.h)
14 | set(SRCS_DBOW2
15 | DBoW2/BowVector.cpp
16 | DBoW2/FORB.cpp
17 | DBoW2/FeatureVector.cpp
18 | DBoW2/ScoringObject.cpp)
19 |
20 | set(HDRS_DUTILS
21 | DUtils/Random.h
22 | DUtils/Timestamp.h)
23 | set(SRCS_DUTILS
24 | DUtils/Random.cpp
25 | DUtils/Timestamp.cpp)
26 |
27 | find_package(OpenCV REQUIRED)
28 |
29 | set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
30 |
31 | include_directories(${OpenCV_INCLUDE_DIRS})
32 | add_library(DBoW2 SHARED ${SRCS_DBOW2} ${SRCS_DUTILS})
33 | target_link_libraries(DBoW2 ${OpenCV_LIBS})
34 |
35 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Thirdparty/DBoW2/DBoW2/BowVector.cpp:
--------------------------------------------------------------------------------
1 | /**
2 | * File: BowVector.cpp
3 | * Date: March 2011
4 | * Author: Dorian Galvez-Lopez
5 | * Description: bag of words vector
6 | * License: see the LICENSE.txt file
7 | *
8 | */
9 |
10 | #include
11 | #include
12 | #include
13 | #include
14 | #include
15 |
16 | #include "BowVector.h"
17 |
18 | namespace DBoW2 {
19 |
20 | // --------------------------------------------------------------------------
21 |
22 | BowVector::BowVector(void)
23 | {
24 | }
25 |
26 | // --------------------------------------------------------------------------
27 |
28 | BowVector::~BowVector(void)
29 | {
30 | }
31 |
32 | // --------------------------------------------------------------------------
33 |
34 | void BowVector::addWeight(WordId id, WordValue v)
35 | {
36 | BowVector::iterator vit = this->lower_bound(id);
37 |
38 | if(vit != this->end() && !(this->key_comp()(id, vit->first)))
39 | {
40 | vit->second += v;
41 | }
42 | else
43 | {
44 | this->insert(vit, BowVector::value_type(id, v));
45 | }
46 | }
47 |
48 | // --------------------------------------------------------------------------
49 |
50 | void BowVector::addIfNotExist(WordId id, WordValue v)
51 | {
52 | BowVector::iterator vit = this->lower_bound(id);
53 |
54 | if(vit == this->end() || (this->key_comp()(id, vit->first)))
55 | {
56 | this->insert(vit, BowVector::value_type(id, v));
57 | }
58 | }
59 |
60 | // --------------------------------------------------------------------------
61 |
62 | void BowVector::normalize(LNorm norm_type)
63 | {
64 | double norm = 0.0;
65 | BowVector::iterator it;
66 |
67 | if(norm_type == DBoW2::L1)
68 | {
69 | for(it = begin(); it != end(); ++it)
70 | norm += fabs(it->second);
71 | }
72 | else
73 | {
74 | for(it = begin(); it != end(); ++it)
75 | norm += it->second * it->second;
76 | norm = sqrt(norm);
77 | }
78 |
79 | if(norm > 0.0)
80 | {
81 | for(it = begin(); it != end(); ++it)
82 | it->second /= norm;
83 | }
84 | }
85 |
86 | // --------------------------------------------------------------------------
87 |
88 | std::ostream& operator<< (std::ostream &out, const BowVector &v)
89 | {
90 | BowVector::const_iterator vit;
91 | std::vector::const_iterator iit;
92 | unsigned int i = 0;
93 | const unsigned int N = v.size();
94 | for(vit = v.begin(); vit != v.end(); ++vit, ++i)
95 | {
96 | out << "<" << vit->first << ", " << vit->second << ">";
97 |
98 | if(i < N-1) out << ", ";
99 | }
100 | return out;
101 | }
102 |
103 | // --------------------------------------------------------------------------
104 |
105 | void BowVector::saveM(const std::string &filename, size_t W) const
106 | {
107 | std::fstream f(filename.c_str(), std::ios::out);
108 |
109 | WordId last = 0;
110 | BowVector::const_iterator bit;
111 | for(bit = this->begin(); bit != this->end(); ++bit)
112 | {
113 | for(; last < bit->first; ++last)
114 | {
115 | f << "0 ";
116 | }
117 | f << bit->second << " ";
118 |
119 | last = bit->first + 1;
120 | }
121 | for(; last < (WordId)W; ++last)
122 | f << "0 ";
123 |
124 | f.close();
125 | }
126 |
127 | // --------------------------------------------------------------------------
128 |
129 | } // namespace DBoW2
130 |
131 |
--------------------------------------------------------------------------------
/master/LearnVIORB_NOROS/Thirdparty/DBoW2/DBoW2/BowVector.h:
--------------------------------------------------------------------------------
1 | /**
2 | * File: BowVector.h
3 | * Date: March 2011
4 | * Author: Dorian Galvez-Lopez
5 | * Description: bag of words vector
6 | * License: see the LICENSE.txt file
7 | *
8 | */
9 |
10 | #ifndef __D_T_BOW_VECTOR__
11 | #define __D_T_BOW_VECTOR__
12 |
13 | #include
14 | #include