Skip to content
Open

V1 #999

Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 11 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,13 @@
# Unignore all dirs
!*/


# 忽略所有 csv log 檔案

*.txt
# 忽略資料集目錄 (Euroc 相關)
data/

CMakeLists.txt.user
CMakeLists_modified.txt

Expand Down Expand Up @@ -91,3 +98,7 @@ my_settings.txt
borrar/*

*/ExecMean.txt
evaluation/fix_mono_tum_imu_corr_2.1txt
evaluation/fix_mono_tum_imu_corr_2.2txt
evaluation/fix_mono_tum_imu_corr_2.3txt
evaluation/fix_mono_tum_imu_corr_2.4txt
20 changes: 20 additions & 0 deletions .vscode/c_cpp_properties.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
{
"configurations": [
{
"name": "Linux",
"includePath": [
"${workspaceFolder}/**",
"${workspaceFolder}/include",
"/usr/include/opencv4",
"/usr/local/include/opencv4",
"/usr/include/eigen3"
],
"defines": [],
"compilerPath": "/usr/bin/gcc",
"cStandard": "c17",
"cppStandard": "gnu++17",
"intelliSenseMode": "linux-gcc-x64"
}
],
"version": 4
}
19 changes: 10 additions & 9 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 2.8)
cmake_minimum_required(VERSION 3.10)
project(ORB_SLAM3)

IF(NOT CMAKE_BUILD_TYPE)
Expand All @@ -14,18 +14,19 @@ set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -march=native")

# Check C++11 or C++0x support
include(CheckCXXCompilerFlag)
CHECK_CXX_COMPILER_FLAG("-std=c++14" COMPILER_SUPPORTS_CXX14)
CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
if(COMPILER_SUPPORTS_CXX11)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")

if(COMPILER_SUPPORTS_CXX14)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -Wno-maybe-uninitialized -w")
add_definitions(-DCOMPILEDWITHC14)
message(STATUS "Using flag -std=c++14.")
elseif(COMPILER_SUPPORTS_CXX11)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -Wno-maybe-uninitialized -w")
add_definitions(-DCOMPILEDWITHC11)
message(STATUS "Using flag -std=c++11.")
elseif(COMPILER_SUPPORTS_CXX0X)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
add_definitions(-DCOMPILEDWITHC0X)
message(STATUS "Using flag -std=c++0x.")
else()
message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.")
message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11/C++14 support. Please use a different C++ compiler.")
endif()

LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)
Expand Down
8 changes: 4 additions & 4 deletions Examples/Monocular-Inertial/mono_inertial_euroc.cc
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ int main(int argc, char *argv[])
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#endif
#endif
int width = im.cols * imageScale;
Expand All @@ -161,7 +161,7 @@ int main(int argc, char *argv[])
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#endif
t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
SLAM.InsertResizeTime(t_resize);
Expand All @@ -187,7 +187,7 @@ int main(int argc, char *argv[])
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
#endif

// Pass the image to the SLAM system
Expand All @@ -197,7 +197,7 @@ int main(int argc, char *argv[])
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
#endif

#ifdef REGISTER_TIMES
Expand Down
10 changes: 5 additions & 5 deletions Examples/Monocular-Inertial/mono_inertial_realsense_D435i.cc
Original file line number Diff line number Diff line change
Expand Up @@ -317,7 +317,7 @@ int main(int argc, char **argv) {
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point time_Start_Process = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point time_Start_Process = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point time_Start_Process = std::chrono::steady_clock::now();
#endif

if(count_im_buffer>1)
Expand Down Expand Up @@ -368,7 +368,7 @@ int main(int argc, char **argv) {
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#endif
#endif
int width = im.cols * imageScale;
Expand All @@ -378,7 +378,7 @@ int main(int argc, char **argv) {
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#endif
t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
SLAM.InsertResizeTime(t_resize);
Expand All @@ -389,7 +389,7 @@ int main(int argc, char **argv) {
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_Start_Track = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Track = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_Start_Track = std::chrono::steady_clock::now();
#endif
#endif
// Pass the image to the SLAM system
Expand All @@ -398,7 +398,7 @@ int main(int argc, char **argv) {
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_End_Track = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Track = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_End_Track = std::chrono::steady_clock::now();
#endif
t_track = t_resize + std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Track - t_Start_Track).count();
SLAM.InsertTrackTime(t_track);
Expand Down
10 changes: 5 additions & 5 deletions Examples/Monocular-Inertial/mono_inertial_realsense_t265.cc
Original file line number Diff line number Diff line change
Expand Up @@ -233,7 +233,7 @@ int main(int argc, char **argv)
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point time_Start_Process = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point time_Start_Process = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point time_Start_Process = std::chrono::steady_clock::now();
#endif

if(count_im_buffer>1)
Expand All @@ -260,7 +260,7 @@ int main(int argc, char **argv)
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#endif
#endif
int width = imCV.cols * imageScale;
Expand All @@ -270,7 +270,7 @@ int main(int argc, char **argv)
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#endif
t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
SLAM.InsertResizeTime(t_resize);
Expand Down Expand Up @@ -311,15 +311,15 @@ int main(int argc, char **argv)
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_Start_Track = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Track = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_Start_Track = std::chrono::steady_clock::now();
#endif
// Pass the image to the SLAM system
SLAM.TrackMonocular(im, timestamp, vImuMeas);

#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_End_Track = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Track = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_End_Track = std::chrono::steady_clock::now();
#endif

#ifdef REGISTER_TIMES
Expand Down
10 changes: 5 additions & 5 deletions Examples/Monocular-Inertial/mono_inertial_tum_vi.cc
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ int main(int argc, char **argv)
cout << "IMU data in the sequence: " << nImu << endl << endl;*/

// Create SLAM system. It initializes all system threads and gets ready to process frames.
ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_MONOCULAR, true, 0, file_name);
ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_MONOCULAR, false, 0, file_name);
float imageScale = SLAM.GetImageScale();

double t_resize = 0.f;
Expand Down Expand Up @@ -175,7 +175,7 @@ int main(int argc, char **argv)
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#endif
#endif
int width = im.cols * imageScale;
Expand All @@ -185,7 +185,7 @@ int main(int argc, char **argv)
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#endif
t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
SLAM.InsertResizeTime(t_resize);
Expand All @@ -198,7 +198,7 @@ int main(int argc, char **argv)
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
#endif

// Pass the image to the SLAM system
Expand All @@ -208,7 +208,7 @@ int main(int argc, char **argv)
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
#endif

#ifdef REGISTER_TIMES
Expand Down
10 changes: 5 additions & 5 deletions Examples/Monocular/mono_euroc.cc
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ int main(int argc, char **argv)
int fps = 20;
float dT = 1.f/fps;
// Create SLAM system. It initializes all system threads and gets ready to process frames.
ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR, false);
ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR, true);//切換視覺化
float imageScale = SLAM.GetImageScale();

double t_resize = 0.f;
Expand Down Expand Up @@ -112,7 +112,7 @@ int main(int argc, char **argv)
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#endif
#endif
int width = im.cols * imageScale;
Expand All @@ -122,7 +122,7 @@ int main(int argc, char **argv)
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#endif
t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
SLAM.InsertResizeTime(t_resize);
Expand All @@ -132,7 +132,7 @@ int main(int argc, char **argv)
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
#endif

// Pass the image to the SLAM system
Expand All @@ -142,7 +142,7 @@ int main(int argc, char **argv)
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
#endif

#ifdef REGISTER_TIMES
Expand Down
8 changes: 4 additions & 4 deletions Examples/Monocular/mono_kitti.cc
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ int main(int argc, char **argv)
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#endif
#endif
int width = im.cols * imageScale;
Expand All @@ -91,7 +91,7 @@ int main(int argc, char **argv)
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#endif
t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
SLAM.InsertResizeTime(t_resize);
Expand All @@ -101,7 +101,7 @@ int main(int argc, char **argv)
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
#endif

// Pass the image to the SLAM system
Expand All @@ -110,7 +110,7 @@ int main(int argc, char **argv)
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
#endif

#ifdef REGISTER_TIMES
Expand Down
10 changes: 5 additions & 5 deletions Examples/Monocular/mono_realsense_D435i.cc
Original file line number Diff line number Diff line change
Expand Up @@ -231,7 +231,7 @@ int main(int argc, char **argv) {
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point time_Start_Process = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point time_Start_Process = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point time_Start_Process = std::chrono::steady_clock::now();
#endif

if(count_im_buffer>1)
Expand All @@ -250,7 +250,7 @@ int main(int argc, char **argv) {
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#endif
#endif
int width = im.cols * imageScale;
Expand All @@ -261,7 +261,7 @@ int main(int argc, char **argv) {
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#endif
t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
SLAM.InsertResizeTime(t_resize);
Expand All @@ -272,7 +272,7 @@ int main(int argc, char **argv) {
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_Start_Track = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Track = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_Start_Track = std::chrono::steady_clock::now();
#endif
#endif
// Stereo images are already rectified.
Expand All @@ -281,7 +281,7 @@ int main(int argc, char **argv) {
#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t_End_Track = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Track = std::chrono::monotonic_clock::now();
std::chrono::steady_clock::time_point t_End_Track = std::chrono::steady_clock::now();
#endif
t_track = t_resize + std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Track - t_Start_Track).count();
SLAM.InsertTrackTime(t_track);
Expand Down
Loading