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

Dbow3 integration #784

Closed
wants to merge 15 commits into from
Closed
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
18 changes: 9 additions & 9 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,25 +12,25 @@ 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
# Check C++14 or C++0x support
include(CheckCXXCompilerFlag)
CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
CHECK_CXX_COMPILER_FLAG("-std=c++14" COMPILER_SUPPORTS_CXX14)
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.")
if(COMPILER_SUPPORTS_CXX14)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14")
add_definitions(-DCOMPILEDWITHC14)
message(STATUS "Using flag -std=c++14.")
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++14 support. Please use a different C++ compiler.")
endif()

LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)

find_package(OpenCV 4.4)
find_package(OpenCV)
if(NOT OpenCV_FOUND)
message(FATAL_ERROR "OpenCV > 4.4 not found.")
endif()
Expand Down Expand Up @@ -119,7 +119,7 @@ target_link_libraries(${PROJECT_NAME}
${OpenCV_LIBS}
${EIGEN3_LIBS}
${Pangolin_LIBRARIES}
${PROJECT_SOURCE_DIR}/Thirdparty/DBoW2/lib/libDBoW2.so
${PROJECT_SOURCE_DIR}/Thirdparty/DBoW2/lib/libDBoW3.so
${PROJECT_SOURCE_DIR}/Thirdparty/g2o/lib/libg2o.so
-lboost_serialization
-lcrypto
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 @@ -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
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 @@ -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
10 changes: 5 additions & 5 deletions Examples/Monocular/mono_realsense_D435i.cc
Original file line number Diff line number Diff line change
Expand Up @@ -228,7 +228,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 All @@ -247,7 +247,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 @@ -258,7 +258,7 @@ int main(int argc, char **argv) {
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 @@ -269,7 +269,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 @@ -278,7 +278,7 @@ int main(int argc, char **argv) {
// Stereo images are already rectified.
SLAM.TrackMonocular(im, timestamp);
#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
8 changes: 4 additions & 4 deletions Examples/Monocular/mono_realsense_t265.cc
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,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 @@ -126,7 +126,7 @@ int main(int argc, char **argv)
int height = imCV.rows * imageScale;
cv::resize(imCV, imCV, 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 @@ -141,7 +141,7 @@ int main(int argc, char **argv)
//clahe->apply(imRight,imRight);

#ifdef REGISTER_TIMES
#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 @@ -152,7 +152,7 @@ int main(int argc, char **argv)
SLAM.TrackMonocular(imCV, timestamp_ms);

#ifdef REGISTER_TIMES
#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