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

♻️ Refactored the code to support OpenCV4 while fixing known bugs to compile and run perfectly on ubuntu 20.04 #1075

Open
wants to merge 3 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
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -22,3 +22,5 @@ build/
*~
lib/

.vscode
.clang-format
31 changes: 17 additions & 14 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,42 +7,45 @@ ENDIF()

MESSAGE("Build type: " ${CMAKE_BUILD_TYPE})

set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native")
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -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 3.0 QUIET)
find_package(OpenCV 4.2 QUIET)
if(NOT OpenCV_FOUND)
find_package(OpenCV 2.4.3 QUIET)
find_package(OpenCV 3.4.7 QUIET)
if(NOT OpenCV_FOUND)
message(FATAL_ERROR "OpenCV > 2.4.3 not found.")
message(FATAL_ERROR "OpenCV > 3.4.7 not found.")
endif()
endif()
message(STATUS "OpenCV library status:")
message(STATUS " version: ${OpenCV_VERSION}")
message(STATUS " libraries: ${OpenCV_LIBS}")
message(STATUS " include path: ${OpenCV_INCLUDE_DIRS}")

find_package(Eigen3 3.1.0 REQUIRED)
find_package(Eigen3 3.1.0 REQUIRED NO_MODULE)
find_package(Pangolin REQUIRED)

include_directories(
${PROJECT_SOURCE_DIR}
${PROJECT_SOURCE_DIR}/include
${EIGEN3_INCLUDE_DIR}
${Pangolin_INCLUDE_DIRS}
)

Expand Down
6 changes: 3 additions & 3 deletions Examples/Monocular/mono_euroc.cc
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ int main(int argc, char **argv)
for(int ni=0; ni<nImages; ni++)
{
// Read image from file
im = cv::imread(vstrImageFilenames[ni],CV_LOAD_IMAGE_UNCHANGED);
im = cv::imread(vstrImageFilenames[ni], cv::IMREAD_UNCHANGED);
double tframe = vTimestamps[ni];

if(im.empty())
Expand All @@ -80,7 +80,7 @@ int main(int argc, char **argv)
return 1;
}

#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 @@ -89,7 +89,7 @@ int main(int argc, char **argv)
// Pass the image to the SLAM system
SLAM.TrackMonocular(im,tframe);

#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
6 changes: 3 additions & 3 deletions Examples/Monocular/mono_kitti.cc
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ int main(int argc, char **argv)
for(int ni=0; ni<nImages; ni++)
{
// Read image from file
im = cv::imread(vstrImageFilenames[ni],CV_LOAD_IMAGE_UNCHANGED);
im = cv::imread(vstrImageFilenames[ni], cv::IMREAD_UNCHANGED);
double tframe = vTimestamps[ni];

if(im.empty())
Expand All @@ -74,7 +74,7 @@ int main(int argc, char **argv)
return 1;
}

#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 @@ -83,7 +83,7 @@ int main(int argc, char **argv)
// Pass the image to the SLAM system
SLAM.TrackMonocular(im,tframe);

#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
6 changes: 3 additions & 3 deletions Examples/Monocular/mono_tum.cc
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ int main(int argc, char **argv)
for(int ni=0; ni<nImages; ni++)
{
// Read image from file
im = cv::imread(string(argv[3])+"/"+vstrImageFilenames[ni],CV_LOAD_IMAGE_UNCHANGED);
im = cv::imread(string(argv[3])+"/"+vstrImageFilenames[ni], cv::IMREAD_UNCHANGED);
double tframe = vTimestamps[ni];

if(im.empty())
Expand All @@ -75,7 +75,7 @@ int main(int argc, char **argv)
return 1;
}

#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 @@ -84,7 +84,7 @@ int main(int argc, char **argv)
// Pass the image to the SLAM system
SLAM.TrackMonocular(im,tframe);

#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/RGB-D/rgbd_tum.cc
Original file line number Diff line number Diff line change
Expand Up @@ -77,8 +77,8 @@ int main(int argc, char **argv)
for(int ni=0; ni<nImages; ni++)
{
// Read image and depthmap from file
imRGB = cv::imread(string(argv[3])+"/"+vstrImageFilenamesRGB[ni],CV_LOAD_IMAGE_UNCHANGED);
imD = cv::imread(string(argv[3])+"/"+vstrImageFilenamesD[ni],CV_LOAD_IMAGE_UNCHANGED);
imRGB = cv::imread(string(argv[3])+"/"+vstrImageFilenamesRGB[ni], cv::IMREAD_UNCHANGED);
imD = cv::imread(string(argv[3])+"/"+vstrImageFilenamesD[ni], cv::IMREAD_UNCHANGED);
double tframe = vTimestamps[ni];

if(imRGB.empty())
Expand All @@ -88,7 +88,7 @@ int main(int argc, char **argv)
return 1;
}

#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 @@ -97,7 +97,7 @@ int main(int argc, char **argv)
// Pass the image to the SLAM system
SLAM.TrackRGBD(imRGB,imD,tframe);

#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
20 changes: 10 additions & 10 deletions Examples/ROS/ORB_SLAM2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,29 +12,29 @@ MESSAGE("Build type: " ${ROS_BUILD_TYPE})
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -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 3.0 QUIET)
find_package(OpenCV 4.2 QUIET)
if(NOT OpenCV_FOUND)
find_package(OpenCV 2.4.3 QUIET)
find_package(OpenCV 3.4.7 QUIET)
if(NOT OpenCV_FOUND)
message(FATAL_ERROR "OpenCV > 2.4.3 not found.")
message(FATAL_ERROR "OpenCV > 3.4.7 not found.")
endif()
endif()

Expand Down
8 changes: 4 additions & 4 deletions Examples/Stereo/stereo_euroc.cc
Original file line number Diff line number Diff line change
Expand Up @@ -116,8 +116,8 @@ int main(int argc, char **argv)
for(int ni=0; ni<nImages; ni++)
{
// Read left and right images from file
imLeft = cv::imread(vstrImageLeft[ni],CV_LOAD_IMAGE_UNCHANGED);
imRight = cv::imread(vstrImageRight[ni],CV_LOAD_IMAGE_UNCHANGED);
imLeft = cv::imread(vstrImageLeft[ni], cv::IMREAD_UNCHANGED);
imRight = cv::imread(vstrImageRight[ni], cv::IMREAD_UNCHANGED);

if(imLeft.empty())
{
Expand All @@ -139,7 +139,7 @@ int main(int argc, char **argv)
double tframe = vTimeStamp[ni];


#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 @@ -148,7 +148,7 @@ int main(int argc, char **argv)
// Pass the images to the SLAM system
SLAM.TrackStereo(imLeftRect,imRightRect,tframe);

#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/Stereo/stereo_kitti.cc
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,8 @@ int main(int argc, char **argv)
for(int ni=0; ni<nImages; ni++)
{
// Read left and right images from file
imLeft = cv::imread(vstrImageLeft[ni],CV_LOAD_IMAGE_UNCHANGED);
imRight = cv::imread(vstrImageRight[ni],CV_LOAD_IMAGE_UNCHANGED);
imLeft = cv::imread(vstrImageLeft[ni], cv::IMREAD_UNCHANGED);
imRight = cv::imread(vstrImageRight[ni], cv::IMREAD_UNCHANGED);
double tframe = vTimestamps[ni];

if(imLeft.empty())
Expand All @@ -77,7 +77,7 @@ int main(int argc, char **argv)
return 1;
}

#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 @@ -86,7 +86,7 @@ int main(int argc, char **argv)
// Pass the images to the SLAM system
SLAM.TrackStereo(imLeft,imRight,tframe);

#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