Skip to content

Commit

Permalink
first commit
Browse files Browse the repository at this point in the history
  • Loading branch information
OldAAAA committed Aug 2, 2020
0 parents commit 1241026
Show file tree
Hide file tree
Showing 510 changed files with 72,734 additions and 0 deletions.
102 changes: 102 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,102 @@
cmake_minimum_required(VERSION 2.8)
project(DXSLAM)

add_definitions(-w)

IF(NOT CMAKE_BUILD_TYPE)
SET(CMAKE_BUILD_TYPE Release)
ENDIF()

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

set( Cnpy_INCLUDE_DIRS ${PROJECT_SOURCE_DIR}/Thirdparty/cnpy )
set( Cnpy_LIBS ${PROJECT_SOURCE_DIR}/Thirdparty/cnpy/build/libcnpy.so )

set( Fbow_INCLUDE_DIRS "${PROJECT_SOURCE_DIR}/Thirdparty/fbow/src/" )
set( Fbow_LIBS "${PROJECT_SOURCE_DIR}/Thirdparty/fbow/build/src/libfbow.so" )

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
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()

LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)

find_package(OpenCV 3.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(Pangolin REQUIRED)
find_package (Threads)

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

set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/lib)

add_library(${PROJECT_NAME} SHARED
src/System.cc
src/Tracking.cc
src/LocalMapping.cc
src/LoopClosing.cc
src/Matcher.cc
src/FrameDrawer.cc
src/Converter.cc
src/MapPoint.cc
src/KeyFrame.cc
src/Map.cc
src/MapDrawer.cc
src/Optimizer.cc
src/PnPsolver.cc
src/Frame.cc
src/KeyFrameDatabase.cc
src/Sim3Solver.cc
src/Initializer.cc
src/Viewer.cc
)



target_link_libraries(${PROJECT_NAME}
${OpenCV_LIBS}
${EIGEN3_LIBS}
${Pangolin_LIBRARIES}
${PROJECT_SOURCE_DIR}/Thirdparty/g2o/lib/libg2o.so
${PROJECT_SOURCE_DIR}/Thirdparty/DBoW2/lib/libDBoW2.so
${Cnpy_LIBS}
${Fbow_LIBS}
)

# Build examples

set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples/RGB-D)

add_executable(rgbd_tum Examples/RGB-D/rgbd_tum.cc)
target_link_libraries(rgbd_tum ${PROJECT_NAME})
target_link_libraries(rgbd_tum ${CMAKE_THREAD_LIBS_INIT})

44 changes: 44 additions & 0 deletions Dependencies.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
##List of Known Dependencies
###ORB-SLAM2 version 1.0

In this document we list all the pieces of code included by ORB-SLAM2 and linked libraries which are not property of the authors of ORB-SLAM2.


#####Code in **src** and **include** folders

* *ORBextractor.cc*.
This is a modified version of orb.cpp of OpenCV library. The original code is BSD licensed.

* *PnPsolver.h, PnPsolver.cc*.
This is a modified version of the epnp.h and epnp.cc of Vincent Lepetit.
This code can be found in popular BSD licensed computer vision libraries as [OpenCV](https://github.com/Itseez/opencv/blob/master/modules/calib3d/src/epnp.cpp) and [OpenGV](https://github.com/laurentkneip/opengv/blob/master/src/absolute_pose/modules/Epnp.cpp). The original code is FreeBSD.

* Function *ORBmatcher::DescriptorDistance* in *ORBmatcher.cc*.
The code is from: http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetParallel.
The code is in the public domain.

#####Code in Thirdparty folder

* All code in **DBoW2** folder.
This is a modified version of [DBoW2](https://github.com/dorian3d/DBoW2) and [DLib](https://github.com/dorian3d/DLib) library. All files included are BSD licensed.

* All code in **g2o** folder.
This is a modified version of [g2o](https://github.com/RainerKuemmerle/g2o). All files included are BSD licensed.

#####Library dependencies

* **Pangolin (visualization and user interface)**.
[MIT license](https://en.wikipedia.org/wiki/MIT_License).

* **OpenCV**.
BSD license.

* **Eigen3**.
For versions greater than 3.1.1 is MPL2, earlier versions are LGPLv3.

* **ROS (Optional, only if you build Examples/ROS)**.
BSD license. In the manifest.xml the only declared package dependencies are roscpp, tf, sensor_msgs, image_transport, cv_bridge, which are all BSD licensed.




Binary file added Examples/RGB-D/rgbd_tum
Binary file not shown.
203 changes: 203 additions & 0 deletions Examples/RGB-D/rgbd_tum.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,203 @@



#include<iostream>
#include<algorithm>
#include<fstream>
#include<chrono>
#include <unistd.h>
#include<opencv2/core/core.hpp>
#include <opencv2/features2d/features2d.hpp>
#include "cnpy.h"
#include<System.h>

using namespace std;

void LoadImages(const string &strAssociationFilename, vector<string> &vstrImageFilenamesRGB,
vector<string> &vstrImageFilenamesD, vector<double> &vTimestamps);

void getdescriptor(string filename,cv::Mat & descriptor,int nkeypoints);
void getGlobaldescriptor(string filename,cv::Mat & descriptor);
void getKeyPoint(string filename , vector<cv::KeyPoint> & keyPoints);

int main(int argc, char **argv)
{
if(argc != 6)
{
cerr << endl << "Usage: ./rgbd_tum path_to_vocabulary path_to_settings path_to_sequence path_to_association path_to_feature" << endl;
return 1;
}

// Retrieve paths to images
vector<string> vstrImageFilenamesRGB;
vector<string> vstrImageFilenamesD;
vector<double> vTimestamps;
string strSequenceFolder = string(argv[3]);
string strAssociationFilename = string(argv[4]);
string featureFolder = string(argv[5]);
LoadImages(strAssociationFilename, vstrImageFilenamesRGB, vstrImageFilenamesD, vTimestamps);

// Check consistency in the number of images and depthmaps
int nImages = vstrImageFilenamesRGB.size();
if(vstrImageFilenamesRGB.empty())
{
cerr << endl << "No images found in provided path." << endl;
return 1;
}
else if(vstrImageFilenamesD.size()!=vstrImageFilenamesRGB.size())
{
cerr << endl << "Different number of images for rgb and depth." << endl;
return 1;
}
// Create SLAM system. It initializes all system threads and gets ready to process frames.
DXSLAM::System SLAM(argv[1],argv[2],DXSLAM::System::RGBD, true);

// Vector for tracking time statistics
vector<float> vTimesTrack;
vTimesTrack.resize(nImages);

cout << endl << "-------" << endl;
cout << "Start processing sequence ..." << endl;
cout << "Images in the sequence: " << nImages << endl << endl;

//cat the image path
LoadImages(strAssociationFilename, vstrImageFilenamesRGB, vstrImageFilenamesD, vTimestamps);

//main loop
cv::Mat imRGB, imD;
for (int ni = 0; ni < vstrImageFilenamesRGB.size(); ni++) {
// Read image and depthmap from file
imRGB = cv::imread(strSequenceFolder + "/" + vstrImageFilenamesRGB[ni], CV_LOAD_IMAGE_UNCHANGED);
imD = cv::imread(strSequenceFolder+ "/" + vstrImageFilenamesD[ni], CV_LOAD_IMAGE_UNCHANGED);
double tframe = vTimestamps[ni];

if (imRGB.empty()) {
cerr << endl << "Failed to load image at: "
<< strSequenceFolder << "/" << vstrImageFilenamesRGB[ni] << endl;
return 1;
}

#ifdef COMPILEDWITHC11
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();
#endif

// Pass the image and hf-net output to the SLAM system
cv::Mat local_desc;
cv::Mat global_desc;
vector<cv::KeyPoint> keypoints;

// Get keyPoint,local descriptor and global descriptor
getKeyPoint(featureFolder + "/point-txt/" + to_string(vTimestamps[ni]) + ".txt" , keypoints);
local_desc.create(keypoints.size(), 256, CV_32F);
getdescriptor(featureFolder + "/des/" + to_string(vTimestamps[ni]) + ".npy" , local_desc , keypoints.size());
global_desc.create(4096, 1, CV_32F);
getGlobaldescriptor(featureFolder + "/glb/" + to_string(vTimestamps[ni]) + ".npy" , global_desc);

SLAM.TrackRGBD(imRGB, imD, tframe, keypoints , local_desc , global_desc);
#ifdef COMPILEDWITHC11
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();
#endif

double ttrack = std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
vTimesTrack[ni] = ttrack;

// Wait to load the next frame
usleep(1000 * 20);

}

// Stop all threads
SLAM.Shutdown();

// Tracking time statistics
sort(vTimesTrack.begin(),vTimesTrack.end());
float totaltime = 0;
for(int ni=0; ni<nImages; ni++)
{
totaltime+=vTimesTrack[ni];
}
cout << "-------" << endl << endl;
cout << "median tracking time: " << vTimesTrack[nImages/2] << endl;
cout << "mean tracking time: " << totaltime/nImages << endl;

// Save camera trajectory
SLAM.SaveTrajectoryTUM("CameraTrajectory.txt");
SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");

return 0;
}

void LoadImages(const string &strAssociationFilename, vector<string> &vstrImageFilenamesRGB,
vector<string> &vstrImageFilenamesD, vector<double> &vTimestamps)
{
vstrImageFilenamesD.clear();
vstrImageFilenamesRGB.clear();
vTimestamps.clear();
ifstream fAssociation;
fAssociation.open(strAssociationFilename.c_str());
while(!fAssociation.eof())
{
string s;
getline(fAssociation,s);
if(!s.empty())
{
stringstream ss;
ss << s;
double t;
string sRGB, sD;
ss >> t;
vTimestamps.push_back(t);
ss >> sRGB;
vstrImageFilenamesRGB.push_back(sRGB);
ss >> t;
ss >> sD;
vstrImageFilenamesD.push_back(sD);

}
}
}

void getdescriptor(string filename,cv::Mat & descriptor,int nkeypoints){
cnpy::NpyArray arr = cnpy::npy_load(filename);
for(int i = 0 ; i < nkeypoints ; i ++){
float* pdata= descriptor.ptr<float>(i);
for(int j = 0 ; j < 256 ; j ++ ){
float temp = arr.data<float>()[i *256 + j];
pdata[j]= temp;
}
}
}

void getGlobaldescriptor(string filename,cv::Mat & descriptor){
cnpy::NpyArray arr = cnpy::npy_load(filename);
float* pdata= descriptor.ptr<float>(0);
for(int j = 0 ; j < 4096 ; j ++ ){
pdata[j]= arr.data<float>()[j];
}
}

void getKeyPoint(string filename , vector<cv::KeyPoint> & keyPoints){
ifstream getfile(filename);

for(int i = 0 ; i < 550 && !getfile.eof() ; i++)
{
string s;
getline(getfile,s);
if(!s.empty())
{
stringstream ss;
ss << s;
double t_x;
double t_y;
ss >> t_x;
ss >> t_y;
cv::KeyPoint keyPoint (t_x,t_y,1);
keyPoint.octave = 0;
keyPoints.push_back(keyPoint);
}
}
}
11 changes: 11 additions & 0 deletions LICENSE.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
ORB-SLAM2 is released under a GPLv3 license (see License-gpl.txt).
Please see Dependencies.md for a list of all included code and library dependencies which are not property of the authors of ORB-SLAM2.

For a closed-source version of ORB-SLAM2 for commercial purposes, please contact the authors.

If you use ORB-SLAM in an academic work, please cite the most relevant publication associated by visiting:
https://github.com/raulmur/ORB_SLAM2




Loading

0 comments on commit 1241026

Please sign in to comment.