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

Compatibility for OpenCV 4.1.1 #1076

Open
wants to merge 9 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
6 changes: 6 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -21,4 +21,10 @@ Vocabulary/ORBvoc.txt
build/
*~
lib/
Datasets/*

FrameTrajectory_KITTI_Format.txt

FrameTrajectory_TUM_Format.txt

KeyFrameTrajectory_TUM_Format.txt
Empty file added 2020-03-12-15_30_49.log
Empty file.
Empty file added 2020-03-12-15_31_25.log
Empty file.
Empty file added 2020-03-12-15_32_36.log
Empty file.
14 changes: 7 additions & 7 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,33 +10,33 @@ 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")

# 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_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")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14")
add_definitions(-DCOMPILEDWITHC11)
message(STATUS "Using flag -std=c++11.")
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.0 QUIET)
if(NOT OpenCV_FOUND)
find_package(OpenCV 2.4.3 QUIET)
if(NOT OpenCV_FOUND)
message(FATAL_ERROR "OpenCV > 2.4.3 not found.")
endif()
endif()

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

include_directories(
Expand Down
3 changes: 2 additions & 1 deletion Examples/Monocular/mono_euroc.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include<algorithm>
#include<fstream>
#include<chrono>
#include "unistd.h"

#include<opencv2/core/core.hpp>

Expand Down Expand Up @@ -70,7 +71,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 Down
3 changes: 2 additions & 1 deletion Examples/Monocular/mono_kitti.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include<fstream>
#include<chrono>
#include<iomanip>
#include "unistd.h"

#include<opencv2/core/core.hpp>

Expand Down Expand Up @@ -65,7 +66,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 Down
3 changes: 2 additions & 1 deletion Examples/Monocular/mono_tum.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include<algorithm>
#include<fstream>
#include<chrono>
#include "unistd.h"

#include<opencv2/core/core.hpp>

Expand Down Expand Up @@ -65,7 +66,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 Down
5 changes: 3 additions & 2 deletions Examples/RGB-D/rgbd_tum.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include<algorithm>
#include<fstream>
#include<chrono>
#include "unistd.h"

#include<opencv2/core/core.hpp>

Expand Down Expand Up @@ -77,8 +78,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 Down
19 changes: 10 additions & 9 deletions Examples/ROS/ORB_SLAM2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,33 +12,33 @@ 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.0 QUIET)
if(NOT OpenCV_FOUND)
find_package(OpenCV 2.4.3 QUIET)
if(NOT OpenCV_FOUND)
message(FATAL_ERROR "OpenCV > 2.4.3 not found.")
endif()
endif()

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

include_directories(
Expand All @@ -55,6 +55,7 @@ ${Pangolin_LIBRARIES}
${PROJECT_SOURCE_DIR}/../../../Thirdparty/DBoW2/lib/libDBoW2.so
${PROJECT_SOURCE_DIR}/../../../Thirdparty/g2o/lib/libg2o.so
${PROJECT_SOURCE_DIR}/../../../lib/libORB_SLAM2.so
-lboost_system
)

# Node for monocular camera
Expand Down
1 change: 1 addition & 0 deletions Examples/ROS/ORB_SLAM2/src/AR/ViewerAR.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
*/

#include "ViewerAR.h"
#include "unistd.h"

#include <opencv2/highgui/highgui.hpp>

Expand Down
1 change: 1 addition & 0 deletions Examples/ROS/ORB_SLAM2/src/AR/ros_mono_ar.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include<algorithm>
#include<fstream>
#include<chrono>
#include "unistd.h"

#include<ros/ros.h>
#include <cv_bridge/cv_bridge.h>
Expand Down
3 changes: 2 additions & 1 deletion Examples/ROS/ORB_SLAM2/src/ros_mono.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include<algorithm>
#include<fstream>
#include<chrono>
#include "unistd.h" //<- Added later

#include<ros/ros.h>
#include <cv_bridge/cv_bridge.h>
Expand Down Expand Up @@ -61,7 +62,7 @@ int main(int argc, char **argv)
ImageGrabber igb(&SLAM);

ros::NodeHandle nodeHandler;
ros::Subscriber sub = nodeHandler.subscribe("/camera/image_raw", 1, &ImageGrabber::GrabImage,&igb);
ros::Subscriber sub = nodeHandler.subscribe("/zed2/zed_node/rgb/image_rect_color", 1, &ImageGrabber::GrabImage,&igb);

ros::spin();

Expand Down
12 changes: 8 additions & 4 deletions Examples/ROS/ORB_SLAM2/src/ros_rgbd.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include<algorithm>
#include<fstream>
#include<chrono>

#include "unistd.h"
#include<ros/ros.h>
#include <cv_bridge/cv_bridge.h>
#include <message_filters/subscriber.h>
Expand Down Expand Up @@ -65,8 +65,10 @@ int main(int argc, char **argv)

ros::NodeHandle nh;

message_filters::Subscriber<sensor_msgs::Image> rgb_sub(nh, "/camera/rgb/image_raw", 1);
message_filters::Subscriber<sensor_msgs::Image> depth_sub(nh, "camera/depth_registered/image_raw", 1);
//message_filters::Subscriber<sensor_msgs::Image> rgb_sub(nh, "/camera/rgb/image_raw", 1);
//message_filters::Subscriber<sensor_msgs::Image> depth_sub(nh, "camera/depth_registered/image_raw", 1);
message_filters::Subscriber<sensor_msgs::Image> rgb_sub(nh, "/zed2/zed_node/rgb/image_rect_color", 1);
message_filters::Subscriber<sensor_msgs::Image> depth_sub(nh, "/zed2/zed_node/depth/depth_registered", 1);
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> sync_pol;
message_filters::Synchronizer<sync_pol> sync(sync_pol(10), rgb_sub,depth_sub);
sync.registerCallback(boost::bind(&ImageGrabber::GrabRGBD,&igb,_1,_2));
Expand Down Expand Up @@ -108,7 +110,9 @@ void ImageGrabber::GrabRGBD(const sensor_msgs::ImageConstPtr& msgRGB,const senso
ROS_ERROR("cv_bridge exception: %s", e.what());
return;
}

//< remap from="/camera/aligned_depth_to_color/image_raw"to="/camera/depth_registered/image_raw" />
//< remap from="/camera/color/image_raw" to="/camera/rgb/image_raw" />

mpSLAM->TrackRGBD(cv_ptrRGB->image,cv_ptrD->image,cv_ptrRGB->header.stamp.toSec());
}

Expand Down
7 changes: 5 additions & 2 deletions Examples/ROS/ORB_SLAM2/src/ros_stereo.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include<algorithm>
#include<fstream>
#include<chrono>
#include "unistd.h"

#include<ros/ros.h>
#include <cv_bridge/cv_bridge.h>
Expand Down Expand Up @@ -109,8 +110,10 @@ int main(int argc, char **argv)

ros::NodeHandle nh;

message_filters::Subscriber<sensor_msgs::Image> left_sub(nh, "/camera/left/image_raw", 1);
message_filters::Subscriber<sensor_msgs::Image> right_sub(nh, "camera/right/image_raw", 1);
//message_filters::Subscriber<sensor_msgs::Image> left_sub(nh, "/camera/left/image_raw", 1);
//message_filters::Subscriber<sensor_msgs::Image> right_sub(nh, "camera/right/image_raw", 1);
message_filters::Subscriber<sensor_msgs::Image> left_sub(nh, "/zed2/zed_node/left/image_rect_color", 1);
message_filters::Subscriber<sensor_msgs::Image> right_sub(nh, "/zed2/zed_node/right/image_rect_color", 1);
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> sync_pol;
message_filters::Synchronizer<sync_pol> sync(sync_pol(10), left_sub,right_sub);
sync.registerCallback(boost::bind(&ImageGrabber::GrabStereo,&igb,_1,_2));
Expand Down
5 changes: 3 additions & 2 deletions Examples/Stereo/stereo_euroc.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include<fstream>
#include<iomanip>
#include<chrono>
#include "unistd.h"

#include<opencv2/core/core.hpp>

Expand Down Expand Up @@ -116,8 +117,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 Down
5 changes: 3 additions & 2 deletions Examples/Stereo/stereo_kitti.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include<fstream>
#include<iomanip>
#include<chrono>
#include "unistd.h"

#include<opencv2/core/core.hpp>

Expand Down Expand Up @@ -66,8 +67,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 Down
Loading