Skip to content

Commit ef97841

Browse files
Updated to V0.3beta
- RGB-D compatibility, the RGB-D examples had been adapted to the new version. - Kitti and TUM dataset compatibility, these examples had been adapted to the new version. - ROS compatibility, It had been updated the old references in the code to work with this version. - Config file parser, the YAML file contains the session configuration, a wrong parametrization may break the execution without any information to solve it. This version parses the file to read all the fields and give a proper answer if one of the fields have been wrong deffined or don't exist. - Fixed minor bugs.
1 parent 8ac600a commit ef97841

29 files changed

+1021
-239
lines changed

.gitignore

+1
Original file line numberDiff line numberDiff line change
@@ -46,3 +46,4 @@ cmake_modules/
4646
cmake-build-debug/
4747

4848
*.pyc
49+
*.osa

Changelog.md

+26
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
# ORB-SLAM3
2+
Details of changes between the different versions.
3+
4+
### V0.3: Beta version, 4 Sep 2020
5+
6+
- RGB-D compatibility, the RGB-D examples had been adapted to the new version.
7+
8+
- Kitti and TUM dataset compatibility, these examples had been adapted to the new version.
9+
10+
- ROS compatibility, It had been updated the old references in the code to work with this version.
11+
12+
- Config file parser, the YAML file contains the session configuration, a wrong parametrization may break the execution without any information to solve it. This version parses the file to read all the fields and give a proper answer if one of the fields have been wrong deffined or don't exist.
13+
14+
- Fixed minor bugs.
15+
16+
17+
### V0.2: Beta version, 7 Aug 2020
18+
Initial release. It has these capabilities:
19+
20+
- Multiple-Maps capabilities, it is able to handle multiple maps in the same session and merge them when a common area is detected with a seamless fussion.
21+
22+
- Inertial sensor, the IMU initialization takes a 2 seconds to achieve a scale error less than 5\% and it is reffined in the next 10 seconds until is around 1\%. Inertial measures are integrated at frame rate to estimate the scale, gravity and velocity in order to improve the visual features detection and make the system robust to temporal occlusions.
23+
24+
- Fisheye sensor, the fisheye sensors are now fully supported in monocular and stereo.
25+
26+

Dependencies.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
##List of Known Dependencies
2-
###ORB-SLAM3 version 0.2
2+
###ORB-SLAM3 version 0.3
33

44
In this document we list all the pieces of code included by ORB-SLAM3 and linked libraries which are not property of the authors of ORB-SLAM3.
55

Examples/Monocular/EuRoC.yaml

+3
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,9 @@ Camera.k2: 0.07395907
1616
Camera.p1: 0.00019359
1717
Camera.p2: 1.76187114e-05
1818

19+
Camera.width: 752
20+
Camera.height: 480
21+
1922
# Camera frames per second
2023
Camera.fps: 20.0
2124

Examples/Monocular/KITTI00-02.yaml

+4
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,10 @@ Camera.fps: 10.0
2222
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
2323
Camera.RGB: 1
2424

25+
# Camera resolution
26+
Camera.width: 1241
27+
Camera.height: 376
28+
2529
#--------------------------------------------------------------------------------------------
2630
# ORB Parameters
2731
#--------------------------------------------------------------------------------------------

Examples/Monocular/KITTI03.yaml

+4
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,10 @@ Camera.fps: 10.0
2222
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
2323
Camera.RGB: 1
2424

25+
# Camera resolution
26+
Camera.width: 1241
27+
Camera.height: 376
28+
2529
#--------------------------------------------------------------------------------------------
2630
# ORB Parameters
2731
#--------------------------------------------------------------------------------------------

Examples/Monocular/KITTI04-12.yaml

+4
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,10 @@ Camera.fps: 10.0
2222
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
2323
Camera.RGB: 1
2424

25+
# Camera resolution
26+
Camera.width: 1241
27+
Camera.height: 376
28+
2529
#--------------------------------------------------------------------------------------------
2630
# ORB Parameters
2731
#--------------------------------------------------------------------------------------------

Examples/Monocular/TUM1.yaml

+4
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,10 @@ Camera.fps: 30.0
2323
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
2424
Camera.RGB: 1
2525

26+
# Camera resolution
27+
Camera.width: 640
28+
Camera.height: 480
29+
2630
#--------------------------------------------------------------------------------------------
2731
# ORB Parameters
2832
#--------------------------------------------------------------------------------------------

Examples/Monocular/TUM2.yaml

+4
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,10 @@ Camera.fps: 30.0
2323
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
2424
Camera.RGB: 1
2525

26+
# Camera resolution
27+
Camera.width: 640
28+
Camera.height: 480
29+
2630
#--------------------------------------------------------------------------------------------
2731
# ORB Parameters
2832
#--------------------------------------------------------------------------------------------

Examples/Monocular/TUM3.yaml

+4
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,10 @@ Camera.fps: 30.0
2222
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
2323
Camera.RGB: 1
2424

25+
# Camera resolution
26+
Camera.width: 640
27+
Camera.height: 480
28+
2529
#--------------------------------------------------------------------------------------------
2630
# ORB Parameters
2731
#--------------------------------------------------------------------------------------------

Examples/RGB-D/TUM2.yaml

+3
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,9 @@ ThDepth: 40.0
3535
# Deptmap values factor
3636
DepthMapFactor: 5208.0
3737

38+
Camera.width: 640
39+
Camera.height: 480
40+
3841
#--------------------------------------------------------------------------------------------
3942
# ORB Parameters
4043
#--------------------------------------------------------------------------------------------

Examples/RGB-D/TUM3.yaml

+3
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,9 @@ ThDepth: 40.0
3434
# Deptmap values factor
3535
DepthMapFactor: 5000.0
3636

37+
Camera.width: 640
38+
Camera.height: 480
39+
3740
#--------------------------------------------------------------------------------------------
3841
# ORB Parameters
3942
#--------------------------------------------------------------------------------------------

Examples/Stereo-Inertial/EuRoC.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ Camera.bf: 47.90639384423901
2929
Camera.RGB: 1
3030

3131
# Close/Far threshold. Baseline times.
32-
ThDepth: 35 # 35
32+
ThDepth: 35.0 # 35
3333

3434
# Transformation from camera 0 to body-frame (imu)
3535
Tbc: !!opencv-matrix

Examples/Stereo-Inertial/TUM_512.yaml

+6-3
Original file line numberDiff line numberDiff line change
@@ -39,8 +39,11 @@ Tlr: !!opencv-matrix
3939
-0.000656143613644, -0.046896036240590, 0.998899560146304, 0.001015350132563]
4040

4141
# Lapping area between images
42-
Lapping.left: 0
43-
Lapping.right: 511
42+
Camera.lappingBegin: 0
43+
Camera.lappingEnd: 511
44+
45+
Camera2.lappingBegin: 0
46+
Camera2.lappingEnd: 511
4447

4548
# Camera resolution
4649
Camera.width: 512
@@ -53,7 +56,7 @@ Camera.fps: 20.0
5356
Camera.RGB: 1
5457

5558
# Close/Far threshold. Baseline times.
56-
ThDepth: 40
59+
ThDepth: 40.0
5760
Camera.bf: 19.3079
5861

5962

Examples/Stereo-Inertial/TUM_512_outdoors.yaml

+6-3
Original file line numberDiff line numberDiff line change
@@ -39,8 +39,11 @@ Tlr: !!opencv-matrix
3939
-0.000656143613644, -0.046896036240590, 0.998899560146304, 0.001015350132563]
4040

4141
# Lapping area between images
42-
Lapping.left: 0
43-
Lapping.right: 511
42+
Camera.lappingBegin: 0
43+
Camera.lappingEnd: 511
44+
45+
Camera2.lappingBegin: 0
46+
Camera2.lappingEnd: 511
4447

4548
# Camera resolution
4649
Camera.width: 512
@@ -53,7 +56,7 @@ Camera.fps: 20.0
5356
Camera.RGB: 1
5457

5558
# Close/Far threshold. Baseline times.
56-
ThDepth: 40
59+
ThDepth: 40.0
5760
Camera.bf: 19.3079
5861

5962

Examples/Stereo/EuRoC.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ Camera.bf: 47.90639384423901
3131
Camera.RGB: 1
3232

3333
# Close/Far threshold. Baseline times.
34-
ThDepth: 35
34+
ThDepth: 35.0
3535

3636
#--------------------------------------------------------------------------------------------
3737
# Stereo Rectification. Only if you need to pre-rectify the images.

Examples/Stereo/KITTI00-02.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ Camera.bf: 386.1448
3131
Camera.RGB: 1
3232

3333
# Close/Far threshold. Baseline times.
34-
ThDepth: 35
34+
ThDepth: 35.0
3535

3636
#--------------------------------------------------------------------------------------------
3737
# ORB Parameters

Examples/Stereo/KITTI03.yaml

+1-3
Original file line numberDiff line numberDiff line change
@@ -16,8 +16,6 @@ Camera.k2: 0.0
1616
Camera.p1: 0.0
1717
Camera.p2: 0.0
1818

19-
Camera.bFishEye: 0
20-
2119
Camera.width: 1241
2220
Camera.height: 376
2321

@@ -31,7 +29,7 @@ Camera.bf: 387.5744
3129
Camera.RGB: 1
3230

3331
# Close/Far threshold. Baseline times.
34-
ThDepth: 40
32+
ThDepth: 40.0
3533

3634
#--------------------------------------------------------------------------------------------
3735
# ORB Parameters

Examples/Stereo/KITTI04-12.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ Camera.bf: 379.8145
3131
Camera.RGB: 1
3232

3333
# Close/Far threshold. Baseline times.
34-
ThDepth: 40
34+
ThDepth: 40.0
3535

3636
#--------------------------------------------------------------------------------------------
3737
# ORB Parameters

Examples/Stereo/TUM_512.yaml

+9-3
Original file line numberDiff line numberDiff line change
@@ -46,10 +46,16 @@ Tlr: !!opencv-matrix
4646
-0.000823363992158, 0.998899461915674, 0.046895490788700, 0.001946204678584,
4747
-0.000656143613644, -0.046896036240590, 0.998899560146304, 0.001015350132563]
4848

49+
# Camera resolution
50+
Camera.width: 512
51+
Camera.height: 512
52+
4953
# Lapping area between images
50-
Lapping.left: 0
51-
Lapping.right: 511
54+
Camera.lappingBegin: 0
55+
Camera.lappingEnd: 511
5256

57+
Camera2.lappingBegin: 0
58+
Camera2.lappingEnd: 511
5359

5460
# Camera frames per second
5561
Camera.fps: 20.0
@@ -58,7 +64,7 @@ Camera.fps: 20.0
5864
Camera.RGB: 1
5965

6066
# Close/Far threshold. Baseline times.
61-
ThDepth: 40
67+
ThDepth: 40.0
6268

6369
Camera.bf: 19.3079
6470

README.md

+3-1
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,10 @@
11
# ORB-SLAM3
22

3-
### V0.3: Beta version, 7 Aug 2020
3+
### V0.3: Beta version, 4 Sep 2020
44
**Authors:** Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, [José M. M. Montiel](http://webdiis.unizar.es/~josemari/), [Juan D. Tardos](http://webdiis.unizar.es/~jdtardos/).
55

6+
The [Changelog](https://github.com/UZ-SLAMLab/ORB_SLAM3/Changelog.md) describes the features of each version.
7+
68
ORB-SLAM3 is the first real-time SLAM library able to perform **Visual, Visual-Inertial and Multi-Map SLAM** with **monocular, stereo and RGB-D** cameras, using **pin-hole and fisheye** lens models. In all sensor configurations, ORB-SLAM3 is as robust as the best systems available in the literature, and significantly more accurate.
79

810
We provide examples to run ORB-SLAM3 in the [EuRoC dataset](http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets) using stereo or monocular, with or without IMU, and in the [TUM-VI dataset](https://vision.in.tum.de/data/datasets/visual-inertial-dataset) using fisheye stereo or monocular, with or without IMU. Videos of some example executions can be found at [ORB-SLAM3 channel](https://www.youtube.com/channel/UCXVt-kXG6T95Z4tVaYlU80Q).

include/MapDrawer.h

+2
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,8 @@ class MapDrawer
4747

4848
private:
4949

50+
bool ParseViewerParamFile(cv::FileStorage &fSettings);
51+
5052
float mKeyFrameSize;
5153
float mKeyFrameLineWidth;
5254
float mGraphLineWidth;

include/Tracking.h

+5
Original file line numberDiff line numberDiff line change
@@ -62,6 +62,11 @@ class Tracking
6262

6363
~Tracking();
6464

65+
// Parse the config file
66+
bool ParseCamParamFile(cv::FileStorage &fSettings);
67+
bool ParseORBParamFile(cv::FileStorage &fSettings);
68+
bool ParseIMUParamFile(cv::FileStorage &fSettings);
69+
6570
// Preprocess the input and call Track(). Extract features and performs stereo matching.
6671
cv::Mat GrabImageStereo(const cv::Mat &imRectLeft,const cv::Mat &imRectRight, const double &timestamp, string filename);
6772
cv::Mat GrabImageRGBD(const cv::Mat &imRGB,const cv::Mat &imD, const double &timestamp, string filename);

include/Viewer.h

+2
Original file line numberDiff line numberDiff line change
@@ -61,6 +61,8 @@ class Viewer
6161
bool both;
6262
private:
6363

64+
bool ParseViewerParamFile(cv::FileStorage &fSettings);
65+
6466
bool Stop();
6567

6668
System* mpSystem;

src/Frame.cc

+2-2
Original file line numberDiff line numberDiff line change
@@ -1047,8 +1047,8 @@ Frame::Frame(const cv::Mat &imLeft, const cv::Mat &imRight, const double &timeSt
10471047
mvInvLevelSigma2 = mpORBextractorLeft->GetInverseScaleSigmaSquares();
10481048

10491049
// ORB extraction
1050-
thread threadLeft(&Frame::ExtractORB,this,0,imLeft,0,511);
1051-
thread threadRight(&Frame::ExtractORB,this,1,imRight,0,511);
1050+
thread threadLeft(&Frame::ExtractORB,this,0,imLeft,static_cast<KannalaBrandt8*>(mpCamera)->mvLappingArea[0],static_cast<KannalaBrandt8*>(mpCamera)->mvLappingArea[1]);
1051+
thread threadRight(&Frame::ExtractORB,this,1,imRight,static_cast<KannalaBrandt8*>(mpCamera2)->mvLappingArea[0],static_cast<KannalaBrandt8*>(mpCamera2)->mvLappingArea[1]);
10521052
threadLeft.join();
10531053
threadRight.join();
10541054
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();

0 commit comments

Comments
 (0)