Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[ Stable Build ] : Corrects major bugs, and creates buildable repo #798

Open
wants to merge 4 commits into
base: master
Choose a base branch
from
Open
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
The table of contents is too big for display.
Diff view
Diff view
  •  
  •  
  •  
139 changes: 3 additions & 136 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,21 +12,9 @@ set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3")
set(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -march=native")
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++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")
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.")
endif()
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_EXTENSIONS OFF)
add_definitions(-DCOMPILEDWITHC14)

LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)

Expand Down Expand Up @@ -267,124 +255,3 @@ if(realsense2_FOUND)
Examples/Calibration/recorder_realsense_T265.cc)
target_link_libraries(recorder_realsense_T265 ${PROJECT_NAME})
endif()

#Old examples

# RGB-D examples
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples_old/RGB-D)

add_executable(rgbd_tum_old
Examples_old/RGB-D/rgbd_tum.cc)
target_link_libraries(rgbd_tum_old ${PROJECT_NAME})

if(realsense2_FOUND)
add_executable(rgbd_realsense_D435i_old
Examples_old/RGB-D/rgbd_realsense_D435i.cc)
target_link_libraries(rgbd_realsense_D435i_old ${PROJECT_NAME})
endif()


# RGB-D inertial examples
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples_old/RGB-D-Inertial)

if(realsense2_FOUND)
add_executable(rgbd_inertial_realsense_D435i_old
Examples_old/RGB-D-Inertial/rgbd_inertial_realsense_D435i.cc)
target_link_libraries(rgbd_inertial_realsense_D435i_old ${PROJECT_NAME})
endif()

#Stereo examples
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples_old/Stereo)

add_executable(stereo_kitti_old
Examples_old/Stereo/stereo_kitti.cc)
target_link_libraries(stereo_kitti_old ${PROJECT_NAME})

add_executable(stereo_euroc_old
Examples_old/Stereo/stereo_euroc.cc)
target_link_libraries(stereo_euroc_old ${PROJECT_NAME})

add_executable(stereo_tum_vi_old
Examples_old/Stereo/stereo_tum_vi.cc)
target_link_libraries(stereo_tum_vi_old ${PROJECT_NAME})

if(realsense2_FOUND)
add_executable(stereo_realsense_t265_old
Examples_old/Stereo/stereo_realsense_t265.cc)
target_link_libraries(stereo_realsense_t265_old ${PROJECT_NAME})

add_executable(stereo_realsense_D435i_old
Examples_old/Stereo/stereo_realsense_D435i.cc)
target_link_libraries(stereo_realsense_D435i_old ${PROJECT_NAME})
endif()

#Monocular examples
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples_old/Monocular)

add_executable(mono_tum_old
Examples_old/Monocular/mono_tum.cc)
target_link_libraries(mono_tum_old ${PROJECT_NAME})

add_executable(mono_kitti_old
Examples_old/Monocular/mono_kitti.cc)
target_link_libraries(mono_kitti_old ${PROJECT_NAME})

add_executable(mono_euroc_old
Examples_old/Monocular/mono_euroc.cc)
target_link_libraries(mono_euroc_old ${PROJECT_NAME})

add_executable(mono_tum_vi_old
Examples_old/Monocular/mono_tum_vi.cc)
target_link_libraries(mono_tum_vi_old ${PROJECT_NAME})

if(realsense2_FOUND)
add_executable(mono_realsense_t265_old
Examples_old/Monocular/mono_realsense_t265.cc)
target_link_libraries(mono_realsense_t265_old ${PROJECT_NAME})

add_executable(mono_realsense_D435i_old
Examples_old/Monocular/mono_realsense_D435i.cc)
target_link_libraries(mono_realsense_D435i_old ${PROJECT_NAME})
endif()

#Monocular inertial examples
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples_old/Monocular-Inertial)

add_executable(mono_inertial_euroc_old
Examples_old/Monocular-Inertial/mono_inertial_euroc.cc)
target_link_libraries(mono_inertial_euroc_old ${PROJECT_NAME})

add_executable(mono_inertial_tum_vi_old
Examples_old/Monocular-Inertial/mono_inertial_tum_vi.cc)
target_link_libraries(mono_inertial_tum_vi_old ${PROJECT_NAME})

if(realsense2_FOUND)
add_executable(mono_inertial_realsense_t265_old
Examples_old/Monocular-Inertial/mono_inertial_realsense_t265.cc)
target_link_libraries(mono_inertial_realsense_t265_old ${PROJECT_NAME})

add_executable(mono_inertial_realsense_D435i_old
Examples_old/Monocular-Inertial/mono_inertial_realsense_D435i.cc)
target_link_libraries(mono_inertial_realsense_D435i_old ${PROJECT_NAME})
endif()

#Stereo Inertial examples
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples_old/Stereo-Inertial)

add_executable(stereo_inertial_euroc_old
Examples_old/Stereo-Inertial/stereo_inertial_euroc.cc)
target_link_libraries(stereo_inertial_euroc_old ${PROJECT_NAME})

add_executable(stereo_inertial_tum_vi_old
Examples_old/Stereo-Inertial/stereo_inertial_tum_vi.cc)
target_link_libraries(stereo_inertial_tum_vi_old ${PROJECT_NAME})

if(realsense2_FOUND)
add_executable(stereo_inertial_realsense_t265_old
Examples_old/Stereo-Inertial/stereo_inertial_realsense_t265.cc)
target_link_libraries(stereo_inertial_realsense_t265_old ${PROJECT_NAME})

add_executable(stereo_inertial_realsense_D435i_old
Examples_old/Stereo-Inertial/stereo_inertial_realsense_D435i.cc)
target_link_libraries(stereo_inertial_realsense_D435i_old ${PROJECT_NAME})
endif()
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 @@ -148,7 +148,7 @@ int main(int argc, char *argv[])
if(imageScale != 1.f)
{
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand All @@ -158,7 +158,7 @@ int main(int argc, char *argv[])
int height = im.rows * imageScale;
cv::resize(im, im, cv::Size(width, height));
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand All @@ -184,7 +184,7 @@ int main(int argc, char *argv[])
}
}

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand All @@ -194,7 +194,7 @@ int main(int argc, char *argv[])
// cout << "tframe = " << tframe << endl;
SLAM.TrackMonocular(im,tframe,vImuMeas); // TODO change to monocular_inertial

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
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 @@ -314,7 +314,7 @@ int main(int argc, char **argv) {
if(!image_ready)
cond_image_rec.wait(lk);

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand Down Expand Up @@ -365,7 +365,7 @@ int main(int argc, char **argv) {
if(imageScale != 1.f)
{
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand All @@ -375,7 +375,7 @@ int main(int argc, char **argv) {
int height = im.rows * imageScale;
cv::resize(im, im, cv::Size(width, height));
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand All @@ -386,7 +386,7 @@ int main(int argc, char **argv) {
}

#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand All @@ -395,7 +395,7 @@ int main(int argc, char **argv) {
// Pass the image to the SLAM system
SLAM.TrackMonocular(im, timestamp, vImuMeas);
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
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 @@ -230,7 +230,7 @@ int main(int argc, char **argv)
while(!image_ready)
cond_image_rec.wait(lk);

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand All @@ -257,7 +257,7 @@ int main(int argc, char **argv)
else
{
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand All @@ -267,7 +267,7 @@ int main(int argc, char **argv)
int height = imCV.rows * imageScale;
cv::resize(imCV, im, cv::Size(width, height));
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand Down Expand Up @@ -308,15 +308,15 @@ int main(int argc, char **argv)
}
}

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
#endif
// Pass the image to the SLAM system
SLAM.TrackMonocular(im, timestamp, vImuMeas);

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand Down
8 changes: 4 additions & 4 deletions Examples/Monocular-Inertial/mono_inertial_tum_vi.cc
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ int main(int argc, char **argv)
if(imageScale != 1.f)
{
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand All @@ -182,7 +182,7 @@ int main(int argc, char **argv)
int height = im.rows * imageScale;
cv::resize(im, im, cv::Size(width, height));
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand All @@ -195,7 +195,7 @@ int main(int argc, char **argv)
// cout << "first imu: " << first_imu[seq] << endl;
/*cout << "first imu time: " << fixed << vTimestampsImu[first_imu] << endl;
cout << "size vImu: " << vImuMeas.size() << endl;*/
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand All @@ -205,7 +205,7 @@ int main(int argc, char **argv)
// cout << "tframe = " << tframe << endl;
SLAM.TrackMonocular(im,tframe,vImuMeas); // TODO change to monocular_inertial

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand Down
8 changes: 4 additions & 4 deletions Examples/Monocular/mono_euroc.cc
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ int main(int argc, char **argv)
if(imageScale != 1.f)
{
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand All @@ -119,7 +119,7 @@ int main(int argc, char **argv)
int height = im.rows * imageScale;
cv::resize(im, im, cv::Size(width, height));
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand All @@ -129,7 +129,7 @@ int main(int argc, char **argv)
#endif
}

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand All @@ -139,7 +139,7 @@ int main(int argc, char **argv)
// cout << "tframe = " << tframe << endl;
SLAM.TrackMonocular(im,tframe); // TODO change to monocular_inertial

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
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 @@ -78,7 +78,7 @@ int main(int argc, char **argv)
if(imageScale != 1.f)
{
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand All @@ -88,7 +88,7 @@ int main(int argc, char **argv)
int height = im.rows * imageScale;
cv::resize(im, im, cv::Size(width, height));
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand All @@ -98,7 +98,7 @@ int main(int argc, char **argv)
#endif
}

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand All @@ -107,7 +107,7 @@ int main(int argc, char **argv)
// Pass the image to the SLAM system
SLAM.TrackMonocular(im,tframe,vector<ORB_SLAM3::IMU::Point>(), vstrImageFilenames[ni]);

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand Down
Loading