Skip to content

Commit a80b467

Browse files
V0.4: Beta version, 21 April 2021
- Changed OpenCV dynamic matrices to static matrices to speed up the code. - Capability to measure running time of the system threads. - Compatibility with OpenCV 4.0 (Requires at least OpenCV 3.0) - Fixed minor bugs.
1 parent ef97841 commit a80b467

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

66 files changed

+2237
-4256
lines changed

CMakeLists.txt

Lines changed: 16 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -33,19 +33,20 @@ endif()
3333

3434
LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)
3535

36-
find_package(OpenCV 3)
36+
find_package(OpenCV 4.0)
3737
if(NOT OpenCV_FOUND)
38-
find_package(OpenCV 2.4.3 QUIET)
39-
if(NOT OpenCV_FOUND)
40-
message(FATAL_ERROR "OpenCV > 2.4.3 not found.")
41-
endif()
38+
find_package(OpenCV 3.0)
39+
if(NOT OpenCV_FOUND)
40+
message(FATAL_ERROR "OpenCV > 3.0 not found.")
41+
endif()
4242
endif()
4343

4444
MESSAGE("OPENCV VERSION:")
4545
MESSAGE(${OpenCV_VERSION})
4646

4747
find_package(Eigen3 3.1.0 REQUIRED)
4848
find_package(Pangolin REQUIRED)
49+
find_package(realsense2)
4950

5051
include_directories(
5152
${PROJECT_SOURCE_DIR}
@@ -72,7 +73,6 @@ src/Atlas.cc
7273
src/Map.cc
7374
src/MapDrawer.cc
7475
src/Optimizer.cc
75-
src/PnPsolver.cc
7676
src/Frame.cc
7777
src/KeyFrameDatabase.cc
7878
src/Sim3Solver.cc
@@ -84,6 +84,7 @@ src/CameraModels/Pinhole.cpp
8484
src/CameraModels/KannalaBrandt8.cpp
8585
src/OptimizableTypes.cpp
8686
src/MLPnPsolver.cpp
87+
src/TwoViewReconstruction.cc
8788
include/System.h
8889
include/Tracking.h
8990
include/LocalMapping.h
@@ -98,7 +99,6 @@ include/Atlas.h
9899
include/Map.h
99100
include/MapDrawer.h
100101
include/Optimizer.h
101-
include/PnPsolver.h
102102
include/Frame.h
103103
include/KeyFrameDatabase.h
104104
include/Sim3Solver.h
@@ -112,7 +112,8 @@ include/CameraModels/KannalaBrandt8.h
112112
include/OptimizableTypes.h
113113
include/MLPnPsolver.h
114114
include/TwoViewReconstruction.h
115-
src/TwoViewReconstruction.cc)
115+
include/Config.h
116+
)
116117

117118
add_subdirectory(Thirdparty/g2o)
118119

@@ -127,14 +128,17 @@ ${PROJECT_SOURCE_DIR}/Thirdparty/g2o/lib/libg2o.so
127128
)
128129

129130

130-
# Build examples
131+
### Build examples
131132

133+
# RGB-D examples
132134
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples/RGB-D)
135+
133136
add_executable(rgbd_tum
134137
Examples/RGB-D/rgbd_tum.cc)
135138
target_link_libraries(rgbd_tum ${PROJECT_NAME})
136139

137140

141+
# Stereo examples
138142
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples/Stereo)
139143

140144
add_executable(stereo_kitti
@@ -149,7 +153,7 @@ add_executable(stereo_tum_vi
149153
Examples/Stereo/stereo_tum_vi.cc)
150154
target_link_libraries(stereo_tum_vi ${PROJECT_NAME})
151155

152-
156+
# Monocular examples
153157
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples/Monocular)
154158

155159
add_executable(mono_tum
@@ -168,7 +172,7 @@ add_executable(mono_tum_vi
168172
Examples/Monocular/mono_tum_vi.cc)
169173
target_link_libraries(mono_tum_vi ${PROJECT_NAME})
170174

171-
175+
# Monocular-Inertial examples
172176
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples/Monocular-Inertial)
173177

174178
add_executable(mono_inertial_euroc
@@ -179,16 +183,14 @@ add_executable(mono_inertial_tum_vi
179183
Examples/Monocular-Inertial/mono_inertial_tum_vi.cc)
180184
target_link_libraries(mono_inertial_tum_vi ${PROJECT_NAME})
181185

182-
186+
# Stereo-Inertial examples
183187
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples/Stereo-Inertial)
184188

185189
add_executable(stereo_inertial_euroc
186190
Examples/Stereo-Inertial/stereo_inertial_euroc.cc)
187191
target_link_libraries(stereo_inertial_euroc ${PROJECT_NAME})
188192

189-
190193
add_executable(stereo_inertial_tum_vi
191194
Examples/Stereo-Inertial/stereo_inertial_tum_vi.cc)
192195
target_link_libraries(stereo_inertial_tum_vi ${PROJECT_NAME})
193196

194-

Changelog.md

Lines changed: 16 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,15 +1,26 @@
11
# ORB-SLAM3
22
Details of changes between the different versions.
33

4+
### V0.4: Beta version, 21 April 2021
5+
6+
- Changed OpenCV dynamic matrices to static matrices to speed up the code.
7+
8+
- Capability to measure running time of the system threads.
9+
10+
- Compatibility with OpenCV 4.0 (Requires at least OpenCV 3.0)
11+
12+
- Fixed minor bugs.
13+
14+
415
### V0.3: Beta version, 4 Sep 2020
516

6-
- RGB-D compatibility, the RGB-D examples had been adapted to the new version.
17+
- RGB-D compatibility, the RGB-D examples have been adapted to the new version.
718

8-
- Kitti and TUM dataset compatibility, these examples had been adapted to the new version.
19+
- Kitti and TUM dataset compatibility, these examples have been adapted to the new version.
920

10-
- ROS compatibility, It had been updated the old references in the code to work with this version.
21+
- ROS compatibility, updated the old references in the code to work with this version.
1122

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.
23+
- 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 wrongly deffined or does not exist.
1324

1425
- Fixed minor bugs.
1526

@@ -19,7 +30,7 @@ Initial release. It has these capabilities:
1930

2031
- 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.
2132

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.
33+
- Inertial sensor, the IMU initialization takes 2 seconds to achieve a scale error less than 5\% and it is reffined in the next 10 seconds until it 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.
2334

2435
- Fisheye sensor, the fisheye sensors are now fully supported in monocular and stereo.
2536

Examples/Monocular-Inertial/mono_inertial_euroc.cc

Lines changed: 9 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -116,25 +116,19 @@ int main(int argc, char *argv[])
116116

117117
cout.precision(17);
118118

119-
/*cout << "Start processing sequence ..." << endl;
120-
cout << "Images in the sequence: " << nImages << endl;
121-
cout << "IMU data in the sequence: " << nImu << endl << endl;*/
122-
123119
// Create SLAM system. It initializes all system threads and gets ready to process frames.
124120
ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_MONOCULAR, true);
125121

126122
int proccIm=0;
127123
for (seq = 0; seq<num_seq; seq++)
128124
{
129-
130-
// Main loop
131125
cv::Mat im;
132126
vector<ORB_SLAM3::IMU::Point> vImuMeas;
133127
proccIm = 0;
134128
for(int ni=0; ni<nImages[seq]; ni++, proccIm++)
135129
{
136130
// Read image from file
137-
im = cv::imread(vstrImageFilenames[seq][ni],CV_LOAD_IMAGE_UNCHANGED);
131+
im = cv::imread(vstrImageFilenames[seq][ni],cv::IMREAD_UNCHANGED);
138132

139133
double tframe = vTimestampsCam[seq][ni];
140134

@@ -150,8 +144,6 @@ int main(int argc, char *argv[])
150144

151145
if(ni>0)
152146
{
153-
// cout << "t_cam " << tframe << endl;
154-
155147
while(vTimestampsImu[seq][first_imu[seq]]<=vTimestampsCam[seq][ni])
156148
{
157149
vImuMeas.push_back(ORB_SLAM3::IMU::Point(vAcc[seq][first_imu[seq]].x,vAcc[seq][first_imu[seq]].y,vAcc[seq][first_imu[seq]].z,
@@ -161,28 +153,29 @@ int main(int argc, char *argv[])
161153
}
162154
}
163155

164-
/*cout << "first imu: " << first_imu << endl;
165-
cout << "first imu time: " << fixed << vTimestampsImu[first_imu] << endl;
166-
cout << "size vImu: " << vImuMeas.size() << endl;*/
156+
167157
#ifdef COMPILEDWITHC11
168158
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
169159
#else
170160
std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
171161
#endif
172162

173163
// Pass the image to the SLAM system
174-
// cout << "tframe = " << tframe << endl;
175-
SLAM.TrackMonocular(im,tframe,vImuMeas); // TODO change to monocular_inertial
164+
SLAM.TrackMonocular(im,tframe,vImuMeas);
176165

177166
#ifdef COMPILEDWITHC11
178167
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
179168
#else
180169
std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
181170
#endif
182171

172+
#ifdef REGISTER_TIMES
173+
double t_track = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t2 - t1).count();
174+
SLAM.InsertTrackTime(t_track);
175+
#endif
176+
183177
double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
184178
ttrack_tot += ttrack;
185-
// std::cout << "ttrack: " << ttrack << std::endl;
186179

187180
vTimesTrack[ni]=ttrack;
188181

@@ -194,7 +187,7 @@ int main(int argc, char *argv[])
194187
T = tframe-vTimestampsCam[seq][ni-1];
195188

196189
if(ttrack<T)
197-
usleep((T-ttrack)*1e6); // 1e6
190+
usleep((T-ttrack)*1e6);
198191
}
199192
if(seq < num_seq - 1)
200193
{

Examples/Monocular-Inertial/mono_inertial_tum_vi.cc

Lines changed: 2 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -110,10 +110,6 @@ int main(int argc, char **argv)
110110
cout << endl << "-------" << endl;
111111
cout.precision(17);
112112

113-
/*cout << "Start processing sequence ..." << endl;
114-
cout << "Images in the sequence: " << nImages << endl;
115-
cout << "IMU data in the sequence: " << nImu << endl << endl;*/
116-
117113
// Create SLAM system. It initializes all system threads and gets ready to process frames.
118114
ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_MONOCULAR, true, 0, file_name);
119115

@@ -135,8 +131,6 @@ int main(int argc, char **argv)
135131
// clahe
136132
clahe->apply(im,im);
137133

138-
139-
// cout << "mat type: " << im.type() << endl;
140134
double tframe = vTimestampsCam[seq][ni];
141135

142136
if(im.empty())
@@ -152,30 +146,24 @@ int main(int argc, char **argv)
152146

153147
if(ni>0)
154148
{
155-
// cout << "t_cam " << tframe << endl;
156149

157150
while(vTimestampsImu[seq][first_imu[seq]]<=vTimestampsCam[seq][ni])
158151
{
159152
vImuMeas.push_back(ORB_SLAM3::IMU::Point(vAcc[seq][first_imu[seq]].x,vAcc[seq][first_imu[seq]].y,vAcc[seq][first_imu[seq]].z,
160153
vGyro[seq][first_imu[seq]].x,vGyro[seq][first_imu[seq]].y,vGyro[seq][first_imu[seq]].z,
161154
vTimestampsImu[seq][first_imu[seq]]));
162-
// cout << "t_imu = " << fixed << vImuMeas.back().t << endl;
163155
first_imu[seq]++;
164156
}
165157
}
166158

167-
// cout << "first imu: " << first_imu[seq] << endl;
168-
/*cout << "first imu time: " << fixed << vTimestampsImu[first_imu] << endl;
169-
cout << "size vImu: " << vImuMeas.size() << endl;*/
170159
#ifdef COMPILEDWITHC11
171160
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
172161
#else
173162
std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
174163
#endif
175164

176165
// Pass the image to the SLAM system
177-
// cout << "tframe = " << tframe << endl;
178-
SLAM.TrackMonocular(im,tframe,vImuMeas); // TODO change to monocular_inertial
166+
SLAM.TrackMonocular(im,tframe,vImuMeas);
179167

180168
#ifdef COMPILEDWITHC11
181169
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
@@ -185,7 +173,6 @@ int main(int argc, char **argv)
185173

186174
double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
187175
ttrack_tot += ttrack;
188-
// std::cout << "ttrack: " << ttrack << std::endl;
189176

190177
vTimesTrack[ni]=ttrack;
191178

@@ -197,7 +184,7 @@ int main(int argc, char **argv)
197184
T = tframe-vTimestampsCam[seq][ni-1];
198185

199186
if(ttrack<T)
200-
usleep((T-ttrack)*1e6); // 1e6
187+
usleep((T-ttrack)*1e6);
201188

202189
}
203190
if(seq < num_seq - 1)
@@ -209,13 +196,9 @@ int main(int argc, char **argv)
209196

210197
}
211198

212-
// cout << "ttrack_tot = " << ttrack_tot << std::endl;
213199
// Stop all threads
214200
SLAM.Shutdown();
215201

216-
217-
// Tracking time statistics
218-
219202
// Save camera trajectory
220203

221204
if (bFileName)
@@ -241,12 +224,6 @@ int main(int argc, char **argv)
241224
cout << "median tracking time: " << vTimesTrack[nImages[0]/2] << endl;
242225
cout << "mean tracking time: " << totaltime/proccIm << endl;
243226

244-
/*const string kf_file = "kf_" + ss.str() + ".txt";
245-
const string f_file = "f_" + ss.str() + ".txt";
246-
247-
SLAM.SaveTrajectoryEuRoC(f_file);
248-
SLAM.SaveKeyFrameTrajectoryEuRoC(kf_file);*/
249-
250227
return 0;
251228
}
252229

Examples/Monocular/mono_euroc.cc

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -91,7 +91,7 @@ int main(int argc, char **argv)
9191
{
9292

9393
// Read image from file
94-
im = cv::imread(vstrImageFilenames[seq][ni],CV_LOAD_IMAGE_UNCHANGED);
94+
im = cv::imread(vstrImageFilenames[seq][ni],cv::IMREAD_UNCHANGED);
9595
double tframe = vTimestampsCam[seq][ni];
9696

9797
if(im.empty())
@@ -108,15 +108,19 @@ int main(int argc, char **argv)
108108
#endif
109109

110110
// Pass the image to the SLAM system
111-
// cout << "tframe = " << tframe << endl;
112-
SLAM.TrackMonocular(im,tframe); // TODO change to monocular_inertial
111+
SLAM.TrackMonocular(im,tframe);
113112

114113
#ifdef COMPILEDWITHC11
115114
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
116115
#else
117116
std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
118117
#endif
119118

119+
#ifdef REGISTER_TIMES
120+
double t_track = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t2 - t1).count();
121+
SLAM.InsertTrackTime(t_track);
122+
#endif
123+
120124
double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
121125

122126
vTimesTrack[ni]=ttrack;
@@ -129,7 +133,7 @@ int main(int argc, char **argv)
129133
T = tframe-vTimestampsCam[seq][ni-1];
130134

131135
if(ttrack<T)
132-
usleep((T-ttrack)*1e6); // 1e6
136+
usleep((T-ttrack)*1e6);
133137
}
134138

135139
if(seq < num_seq - 1)

Examples/Monocular/mono_kitti.cc

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -53,10 +53,6 @@ int main(int argc, char **argv)
5353
vector<float> vTimesTrack;
5454
vTimesTrack.resize(nImages);
5555

56-
cout << endl << "-------" << endl;
57-
cout << "Start processing sequence ..." << endl;
58-
cout << "Images in the sequence: " << nImages << endl << endl;
59-
6056
// Main loop
6157
cv::Mat im;
6258
for(int ni=0; ni<nImages; ni++)

Examples/Monocular/mono_tum.cc

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -55,10 +55,6 @@ int main(int argc, char **argv)
5555
vector<float> vTimesTrack;
5656
vTimesTrack.resize(nImages);
5757

58-
cout << endl << "-------" << endl;
59-
cout << "Start processing sequence ..." << endl;
60-
cout << "Images in the sequence: " << nImages << endl << endl;
61-
6258
// Main loop
6359
cv::Mat im;
6460
for(int ni=0; ni<nImages; ni++)

0 commit comments

Comments
 (0)