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

support opencv440 #1107

Open
wants to merge 1 commit 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: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ 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)
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 @@ -70,7 +70,8 @@ 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_LOAD_IMAGE_UNCHANGED);
im = cv::imread(vstrImageFilenames[ni],cv::IMREAD_UNCHANGED);
double tframe = vTimestamps[ni];

if(im.empty())
Expand Down
2 changes: 1 addition & 1 deletion 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 Down
2 changes: 1 addition & 1 deletion 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 Down
4 changes: 2 additions & 2 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 Down
4 changes: 2 additions & 2 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 Down
4 changes: 2 additions & 2 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 Down
2 changes: 1 addition & 1 deletion Thirdparty/DBoW2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ set(SRCS_DUTILS
DUtils/Random.cpp
DUtils/Timestamp.cpp)

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)
Expand Down
1 change: 1 addition & 0 deletions include/LocalMapping.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include "LoopClosing.h"
#include "Tracking.h"
#include "KeyFrameDatabase.h"
#include <unistd.h>

#include <mutex>

Expand Down
5 changes: 4 additions & 1 deletion include/LoopClosing.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,11 @@ class LoopClosing
public:

typedef pair<set<KeyFrame*>,int> ConsistentGroup;
// typedef map<KeyFrame*,g2o::Sim3,std::less<KeyFrame*>,
// Eigen::aligned_allocator<std::pair<const KeyFrame*, g2o::Sim3> > > KeyFrameAndPose;

typedef map<KeyFrame*,g2o::Sim3,std::less<KeyFrame*>,
Eigen::aligned_allocator<std::pair<const KeyFrame*, g2o::Sim3> > > KeyFrameAndPose;
Eigen::aligned_allocator<std::pair<KeyFrame *const, g2o::Sim3> > > KeyFrameAndPose;

public:

Expand Down
3 changes: 2 additions & 1 deletion include/ORBextractor.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,8 @@

#include <vector>
#include <list>
#include <opencv/cv.h>
//#include <opencv/cv.h> //opencv3
#include <opencv2/imgproc/types_c.h>


namespace ORB_SLAM2
Expand Down