├── .gitignore
├── .idea
├── .gitignore
├── ORB_SLAM2.iml
├── misc.xml
└── vcs.xml
├── CMakeLists.txt
├── Dependencies.md
├── Examples
└── ROS
│ └── ORB_SLAM2
│ ├── CMakeLists.txt
│ ├── RGB.png
│ ├── depth.png
│ ├── depthrec.sh
│ ├── include
│ └── utils
│ │ └── tic_toc.h
│ ├── launch
│ └── octomap.launch
│ ├── manifest.xml
│ ├── orb_kitti_launch_mono.sh
│ ├── orb_kitti_launch_rgbd.sh
│ ├── orb_kitti_launch_stereo.sh
│ ├── package.xml
│ ├── raw.png
│ └── src
│ ├── ros_mono.cc
│ ├── ros_rgbd.cc
│ └── ros_stereo.cc
├── LICENSE.txt
├── License-gpl.txt
├── README.md
├── Thirdparty
├── DBoW2
│ ├── CMakeLists.txt
│ ├── DBoW2
│ │ ├── BowVector.cpp
│ │ ├── BowVector.h
│ │ ├── FClass.h
│ │ ├── FORB.cpp
│ │ ├── FORB.h
│ │ ├── FeatureVector.cpp
│ │ ├── FeatureVector.h
│ │ ├── ScoringObject.cpp
│ │ ├── ScoringObject.h
│ │ └── TemplatedVocabulary.h
│ ├── DUtils
│ │ ├── Random.cpp
│ │ ├── Random.h
│ │ ├── Timestamp.cpp
│ │ └── Timestamp.h
│ ├── LICENSE.txt
│ └── README.txt
└── g2o
│ ├── CMakeLists.txt
│ ├── README.txt
│ ├── cmake_modules
│ ├── FindBLAS.cmake
│ ├── FindEigen3.cmake
│ └── FindLAPACK.cmake
│ ├── config.h.in
│ ├── g2o
│ ├── core
│ │ ├── base_binary_edge.h
│ │ ├── base_binary_edge.hpp
│ │ ├── base_edge.h
│ │ ├── base_multi_edge.h
│ │ ├── base_multi_edge.hpp
│ │ ├── base_unary_edge.h
│ │ ├── base_unary_edge.hpp
│ │ ├── base_vertex.h
│ │ ├── base_vertex.hpp
│ │ ├── batch_stats.cpp
│ │ ├── batch_stats.h
│ │ ├── block_solver.h
│ │ ├── block_solver.hpp
│ │ ├── cache.cpp
│ │ ├── cache.h
│ │ ├── creators.h
│ │ ├── eigen_types.h
│ │ ├── estimate_propagator.cpp
│ │ ├── estimate_propagator.h
│ │ ├── factory.cpp
│ │ ├── factory.h
│ │ ├── hyper_dijkstra.cpp
│ │ ├── hyper_dijkstra.h
│ │ ├── hyper_graph.cpp
│ │ ├── hyper_graph.h
│ │ ├── hyper_graph_action.cpp
│ │ ├── hyper_graph_action.h
│ │ ├── jacobian_workspace.cpp
│ │ ├── jacobian_workspace.h
│ │ ├── linear_solver.h
│ │ ├── marginal_covariance_cholesky.cpp
│ │ ├── marginal_covariance_cholesky.h
│ │ ├── matrix_operations.h
│ │ ├── matrix_structure.cpp
│ │ ├── matrix_structure.h
│ │ ├── openmp_mutex.h
│ │ ├── optimizable_graph.cpp
│ │ ├── optimizable_graph.h
│ │ ├── optimization_algorithm.cpp
│ │ ├── optimization_algorithm.h
│ │ ├── optimization_algorithm_dogleg.cpp
│ │ ├── optimization_algorithm_dogleg.h
│ │ ├── optimization_algorithm_factory.cpp
│ │ ├── optimization_algorithm_factory.h
│ │ ├── optimization_algorithm_gauss_newton.cpp
│ │ ├── optimization_algorithm_gauss_newton.h
│ │ ├── optimization_algorithm_levenberg.cpp
│ │ ├── optimization_algorithm_levenberg.h
│ │ ├── optimization_algorithm_property.h
│ │ ├── optimization_algorithm_with_hessian.cpp
│ │ ├── optimization_algorithm_with_hessian.h
│ │ ├── parameter.cpp
│ │ ├── parameter.h
│ │ ├── parameter_container.cpp
│ │ ├── parameter_container.h
│ │ ├── robust_kernel.cpp
│ │ ├── robust_kernel.h
│ │ ├── robust_kernel_factory.cpp
│ │ ├── robust_kernel_factory.h
│ │ ├── robust_kernel_impl.cpp
│ │ ├── robust_kernel_impl.h
│ │ ├── solver.cpp
│ │ ├── solver.h
│ │ ├── sparse_block_matrix.h
│ │ ├── sparse_block_matrix.hpp
│ │ ├── sparse_block_matrix_ccs.h
│ │ ├── sparse_block_matrix_diagonal.h
│ │ ├── sparse_block_matrix_test.cpp
│ │ ├── sparse_optimizer.cpp
│ │ └── sparse_optimizer.h
│ ├── solvers
│ │ ├── linear_solver_dense.h
│ │ └── linear_solver_eigen.h
│ ├── stuff
│ │ ├── color_macros.h
│ │ ├── macros.h
│ │ ├── misc.h
│ │ ├── os_specific.c
│ │ ├── os_specific.h
│ │ ├── property.cpp
│ │ ├── property.h
│ │ ├── string_tools.cpp
│ │ ├── string_tools.h
│ │ ├── timeutil.cpp
│ │ └── timeutil.h
│ └── types
│ │ ├── se3_ops.h
│ │ ├── se3_ops.hpp
│ │ ├── se3quat.h
│ │ ├── sim3.h
│ │ ├── types_sba.cpp
│ │ ├── types_sba.h
│ │ ├── types_seven_dof_expmap.cpp
│ │ ├── types_seven_dof_expmap.h
│ │ ├── types_six_dof_expmap.cpp
│ │ └── types_six_dof_expmap.h
│ └── license-bsd.txt
├── Vocabulary
└── ORBvoc.txt.tar.gz
├── build.sh
├── build_ros.sh
├── cmake_modules
└── FindEigen3.cmake
├── config
├── 00.yaml
├── 09.yaml
├── KITTI0920RGBD.yaml
├── KITTI0930mono.yaml
└── KITTI0930stereo.yaml
├── include
├── Converter.h
├── Frame.h
├── FrameDrawer.h
├── Initializer.h
├── KeyFrame.h
├── KeyFrameDatabase.h
├── LocalMapping.h
├── LoopClosing.h
├── Map.h
├── MapDrawer.h
├── MapPoint.h
├── ORBVocabulary.h
├── ORBextractor.h
├── ORBmatcher.h
├── Optimizer.h
├── PnPsolver.h
├── PointCloudElement.h
├── SLIC.h
├── Sim3Solver.h
├── System.h
├── TicToc.h
├── Tracking.h
├── Viewer.h
├── pointcloudmapping.h
└── superpixel.h
├── pointcloud.png
├── res.png
└── src
├── Converter.cc
├── Frame.cc
├── FrameDrawer.cc
├── Initializer.cc
├── KeyFrame.cc
├── KeyFrameDatabase.cc
├── LocalMapping.cc
├── LoopClosing.cc
├── Map.cc
├── MapDrawer.cc
├── MapPoint.cc
├── ORBextractor.cc
├── ORBmatcher.cc
├── Optimizer.cc
├── PnPsolver.cc
├── SLIC.cpp
├── Sim3Solver.cc
├── System.cc
├── Tracking.cc
├── Viewer.cc
└── pointcloudmapping.cpp
/.gitignore:
--------------------------------------------------------------------------------
1 | CMakeLists.txt.user
2 | Examples/Monocular/mono_euroc
3 | Examples/Monocular/mono_kitti
4 | Examples/Monocular/mono_tum
5 | Examples/RGB-D/rgbd_tum
6 | Examples/ROS/ORB_SLAM2/CMakeLists.txt.user
7 | Examples/ROS/ORB_SLAM2/Mono
8 | Examples/ROS/ORB_SLAM2/MonoAR
9 | Examples/ROS/ORB_SLAM2/RGBD
10 | Examples/ROS/ORB_SLAM2/Stereo
11 | Examples/ROS/ORB_SLAM2/build/
12 | Examples/ROS/ORB_SLAM2/.idea/
13 | Examples/ROS/ORB_SLAM2/lib/
14 | Examples/ROS/ORB_SLAM2/cmake-build-debug/
15 | Examples/Stereo/stereo_euroc
16 | Examples/Stereo/stereo_kitti
17 | KeyFrameTrajectory.txt
18 | Thirdparty/DBoW2/build/
19 | Thirdparty/DBoW2/lib/
20 | Thirdparty/g2o/build/
21 | Thirdparty/g2o/config.h
22 | Thirdparty/g2o/lib/
23 | Vocabulary/ORBvoc.txt
24 | build/
25 | *~
26 | lib/
27 | .idea/
28 | .git/
29 | cmake-build-debug/
30 |
31 |
--------------------------------------------------------------------------------
/.idea/.gitignore:
--------------------------------------------------------------------------------
1 | # Default ignored files
2 | /workspace.xml
--------------------------------------------------------------------------------
/.idea/ORB_SLAM2.iml:
--------------------------------------------------------------------------------
1 |
2 |
--------------------------------------------------------------------------------
/.idea/misc.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
--------------------------------------------------------------------------------
/.idea/vcs.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
--------------------------------------------------------------------------------
/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8)
2 | project(ORB_SLAM2)
3 |
4 | IF(NOT CMAKE_BUILD_TYPE)
5 | SET(CMAKE_BUILD_TYPE Release)
6 | ENDIF()
7 |
8 | MESSAGE("Build type: " ${CMAKE_BUILD_TYPE})
9 |
10 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ")
11 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native")
12 |
13 | # Check C++11 or C++0x support
14 | include(CheckCXXCompilerFlag)
15 | CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
16 | CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
17 | if(COMPILER_SUPPORTS_CXX11)
18 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
19 | add_definitions(-DCOMPILEDWITHC11)
20 | message(STATUS "Using flag -std=c++11.")
21 | elseif(COMPILER_SUPPORTS_CXX0X)
22 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
23 | add_definitions(-DCOMPILEDWITHC0X)
24 | message(STATUS "Using flag -std=c++0x.")
25 | else()
26 | message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.")
27 | endif()
28 |
29 | LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)
30 |
31 | find_package(OpenCV 3.4 QUIET)
32 | if(NOT OpenCV_FOUND)
33 | find_package(OpenCV 2.4.3 QUIET)
34 | if(NOT OpenCV_FOUND)
35 | message(FATAL_ERROR "OpenCV > 2.4.3 not found.")
36 | endif()
37 | endif()
38 | find_package(PCL 1.7 REQUIRED)
39 | if(PCL_FOUND)
40 | message("PCL FOUND")
41 | endif()
42 | find_package(Eigen3 3.1.0 REQUIRED)
43 | find_package(Pangolin REQUIRED)
44 |
45 | find_package(catkin REQUIRED COMPONENTS
46 | roscpp
47 | sensor_msgs
48 | message_generation
49 | tf
50 | )
51 |
52 | include_directories(
53 | ${PROJECT_SOURCE_DIR}
54 | ${PROJECT_SOURCE_DIR}/include
55 | ${EIGEN3_INCLUDE_DIR}
56 | ${Pangolin_INCLUDE_DIRS}
57 | ${OpenCV_INCLUDE_DIRS}
58 | ${PCL_INCLUDE_DIRS}
59 | ${catkin_INCLUDE_DIRS}
60 | )
61 |
62 | add_definitions( ${PCL_DEFINITIONS} )
63 | link_directories( ${PCL_LIBRARY_DIRS} )
64 |
65 | set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/lib)
66 |
67 | add_library(${PROJECT_NAME} SHARED
68 | src/System.cc
69 | src/Tracking.cc
70 | src/LocalMapping.cc
71 | src/LoopClosing.cc
72 | src/ORBextractor.cc
73 | src/ORBmatcher.cc
74 | src/FrameDrawer.cc
75 | src/Converter.cc
76 | src/MapPoint.cc
77 | src/KeyFrame.cc
78 | src/Map.cc
79 | src/MapDrawer.cc
80 | src/Optimizer.cc
81 | src/PnPsolver.cc
82 | src/Frame.cc
83 | src/KeyFrameDatabase.cc
84 | src/Sim3Solver.cc
85 | src/Initializer.cc
86 | src/Viewer.cc
87 | src/pointcloudmapping.cpp
88 | src/SLIC.cpp
89 | )
90 |
91 | target_link_libraries(${PROJECT_NAME}
92 | /usr/lib/x86_64-linux-gnu/libtiff.so.5
93 | ${OpenCV_LIBS}
94 | ${EIGEN3_LIBS}
95 | ${Pangolin_LIBRARIES}
96 | ${PCL_LIBRARIES}
97 | ${catkin_LIBRARIES}
98 | ${PROJECT_SOURCE_DIR}/Thirdparty/DBoW2/lib/libDBoW2.so
99 | ${PROJECT_SOURCE_DIR}/Thirdparty/g2o/lib/libg2o.so
100 | /usr/lib/x86_64-linux-gnu/libglog.so
101 | -lboost_system
102 | )
103 |
104 |
--------------------------------------------------------------------------------
/Dependencies.md:
--------------------------------------------------------------------------------
1 | ##List of Known Dependencies
2 | ###ORB-SLAM2 version 1.0
3 |
4 | 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.
5 |
6 |
7 | #####Code in **src** and **include** folders
8 |
9 | * *ORBextractor.cc*.
10 | This is a modified version of orb.cpp of OpenCV library. The original code is BSD licensed.
11 |
12 | * *PnPsolver.h, PnPsolver.cc*.
13 | This is a modified version of the epnp.h and epnp.cc of Vincent Lepetit.
14 | 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.
15 |
16 | * Function *ORBmatcher::DescriptorDistance* in *ORBmatcher.cc*.
17 | The code is from: http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetParallel.
18 | The code is in the public domain.
19 |
20 | #####Code in Thirdparty folder
21 |
22 | * All code in **DBoW2** folder.
23 | 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.
24 |
25 | * All code in **g2o** folder.
26 | This is a modified version of [g2o](https://github.com/RainerKuemmerle/g2o). All files included are BSD licensed.
27 |
28 | #####Library dependencies
29 |
30 | * **Pangolin (visualization and user interface)**.
31 | [MIT license](https://en.wikipedia.org/wiki/MIT_License).
32 |
33 | * **OpenCV**.
34 | BSD license.
35 |
36 | * **Eigen3**.
37 | For versions greater than 3.1.1 is MPL2, earlier versions are LGPLv3.
38 |
39 | * **ROS (Optional, only if you build Examples/ROS)**.
40 | 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.
41 |
42 |
43 |
44 |
45 |
--------------------------------------------------------------------------------
/Examples/ROS/ORB_SLAM2/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.4.6)
2 |
3 | include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
4 |
5 | rosbuild_init()
6 |
7 | IF(NOT ROS_BUILD_TYPE)
8 | SET(ROS_BUILD_TYPE Release)
9 | ENDIF()
10 |
11 | MESSAGE("Build type: " ${ROS_BUILD_TYPE})
12 |
13 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ")
14 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native")
15 |
16 | # Check C++11 or C++0x support
17 | include(CheckCXXCompilerFlag)
18 | CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
19 | CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
20 | if(COMPILER_SUPPORTS_CXX11)
21 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
22 | add_definitions(-DCOMPILEDWITHC11)
23 | message(STATUS "Using flag -std=c++11.")
24 | elseif(COMPILER_SUPPORTS_CXX0X)
25 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
26 | add_definitions(-DCOMPILEDWITHC0X)
27 | message(STATUS "Using flag -std=c++0x.")
28 | else()
29 | message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.")
30 | endif()
31 |
32 | LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/../../../cmake_modules)
33 |
34 | find_package(catkin REQUIRED COMPONENTS
35 | roscpp
36 | std_msgs
37 | sensor_msgs
38 | geometry_msgs
39 | nav_msgs
40 | cv_bridge
41 | tf
42 | tf_conversions
43 | pcl_ros
44 | pcl_conversions
45 | )
46 |
47 | find_package(OpenCV 3.4 QUIET)
48 | if(OpenCV_FOUND)
49 | message("OPENCV 3 4 FOUND")
50 | endif()
51 | if(NOT OpenCV_FOUND)
52 | find_package(OpenCV 2.4.3 QUIET)
53 | if(NOT OpenCV_FOUND)
54 | message(FATAL_ERROR "OpenCV > 2.4.3 not found.")
55 | endif()
56 | endif()
57 | find_package(PCL REQUIRED)
58 | IF(PCL_FOUND)
59 | MESSAGE("FIND PCL")
60 | ENDIF()
61 |
62 |
63 | find_package(Eigen3 3.1.0 REQUIRED)
64 | find_package(Pangolin REQUIRED)
65 |
66 | catkin_package(
67 | INCLUDE_DIRS
68 | ${PROJECT_SOURCE_DIR}/../../../include
69 | # LIBRARIES nav_goal
70 | CATKIN_DEPENDS
71 | roscpp
72 | std_msgs
73 | sensor_msgs
74 | geometry_msgs
75 | cv_bridge
76 | tf
77 | # DEPENDS system_lib
78 | )
79 |
80 | include_directories(
81 | ${PROJECT_SOURCE_DIR}
82 | ${PROJECT_SOURCE_DIR}/../../../
83 | ${PROJECT_SOURCE_DIR}/../../../include
84 | ${Pangolin_INCLUDE_DIRS}
85 | ${catkin_INCLUDE_DIRS}
86 | ${PROJECT_SOURCE_DIR}/include
87 | ${PCL_INCLUDE_DIRS}
88 | )
89 |
90 | set(LIBS
91 | /usr/lib/x86_64-linux-gnu/libtiff.so.5
92 | ${OpenCV_LIBS}
93 | ${EIGEN3_LIBS}
94 | ${Pangolin_LIBRARIES}
95 | ${PROJECT_SOURCE_DIR}/../../../Thirdparty/DBoW2/lib/libDBoW2.so
96 | ${PROJECT_SOURCE_DIR}/../../../Thirdparty/g2o/lib/libg2o.so
97 | ${PROJECT_SOURCE_DIR}/../../../lib/libORB_SLAM2.so
98 | ${PCL_LIBRARIES}
99 | ${catkin_LIBRARIES}
100 | )
101 |
102 | set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ../)
103 |
104 | # Node for monocular camera
105 | rosbuild_add_executable(Mono
106 | src/ros_mono.cc
107 | )
108 |
109 | target_link_libraries(Mono
110 | ${LIBS}
111 | /usr/local/lib/libtiff.so.5
112 | boost_system boost_filesystem
113 | )
114 |
115 |
116 | # Node for stereo camera
117 | rosbuild_add_executable(Stereo
118 | src/ros_stereo.cc
119 | )
120 |
121 | target_link_libraries(Stereo
122 | ${LIBS}
123 | /usr/local/lib/libtiff.so.5
124 | boost_system boost_filesystem
125 | )
126 |
127 | # Node for RGB-D camera
128 | rosbuild_add_executable(RGBD
129 | src/ros_rgbd.cc
130 | # src/utils/message_utils.cpp
131 | )
132 |
133 | target_link_libraries(RGBD
134 | ${LIBS}
135 | /usr/local/lib/libtiff.so.5
136 | boost_system boost_filesystem
137 | )
138 |
139 |
--------------------------------------------------------------------------------
/Examples/ROS/ORB_SLAM2/RGB.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/834810269/DF-ORB-SLAM/462425d61903fa6efc71dde3011cbc3c920c2c16/Examples/ROS/ORB_SLAM2/RGB.png
--------------------------------------------------------------------------------
/Examples/ROS/ORB_SLAM2/depth.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/834810269/DF-ORB-SLAM/462425d61903fa6efc71dde3011cbc3c920c2c16/Examples/ROS/ORB_SLAM2/depth.png
--------------------------------------------------------------------------------
/Examples/ROS/ORB_SLAM2/depthrec.sh:
--------------------------------------------------------------------------------
1 | rosrun depth_recover depth_recover_node /pose_graph/keyframe_image:=/kitti/camera_color_right/image_raw
2 |
--------------------------------------------------------------------------------
/Examples/ROS/ORB_SLAM2/include/utils/tic_toc.h:
--------------------------------------------------------------------------------
1 | //
2 | // Created by yonghui on 19-10-31.
3 | //
4 |
5 | #ifndef ORB_SLAM2_DENSE_TIC_TOC_H
6 | #define ORB_SLAM2_DENSE_TIC_TOC_H
7 |
8 | #include
9 |
10 | namespace ORB_SLAM2_DENSE
11 | {
12 | class TicToc
13 | {
14 | public:
15 | TicToc()
16 | {
17 | tic();
18 | }
19 |
20 | void tic()
21 | {
22 | t_start = ros::Time::now();
23 | }
24 |
25 | double toc()
26 | {
27 | ros::Time t_end = ros::Time::now();
28 | return t_end.toSec() - t_start.toSec();
29 | }
30 |
31 | protected:
32 | ros::Time t_start;
33 |
34 | };
35 | }
36 |
37 | #endif //ORB_SLAM2_DENSE_TIC_TOC_H
38 |
--------------------------------------------------------------------------------
/Examples/ROS/ORB_SLAM2/launch/octomap.launch:
--------------------------------------------------------------------------------
1 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
--------------------------------------------------------------------------------
/Examples/ROS/ORB_SLAM2/manifest.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | ORB_SLAM2
5 |
6 |
7 | Raul Mur-Artal
8 | GPLv3
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
--------------------------------------------------------------------------------
/Examples/ROS/ORB_SLAM2/orb_kitti_launch_mono.sh:
--------------------------------------------------------------------------------
1 | rosrun ORB_SLAM2 Mono /home/wang/ROS_WS/orbslam_ws/src/ORB_SLAM2/Vocabulary/ORBvoc.txt /home/wang/ROS_WS/orbslam_ws/src/ORB_SLAM2/config/KITTI0930mono.yaml /camera/image_raw:=/kitti/camera_color_left/image_raw
2 |
--------------------------------------------------------------------------------
/Examples/ROS/ORB_SLAM2/orb_kitti_launch_rgbd.sh:
--------------------------------------------------------------------------------
1 | rosrun ORB_SLAM2 RGBD /home/wang/ROS_WS/orbslam_ws/src/ORB_SLAM2/Vocabulary/ORBvoc.txt ../../../config/09.yaml /camera/rgb/image_raw:=/depth_node/reference_image /camera/depth_registered/image_raw:=/depth_node/depth_image
2 |
--------------------------------------------------------------------------------
/Examples/ROS/ORB_SLAM2/orb_kitti_launch_stereo.sh:
--------------------------------------------------------------------------------
1 | rosrun ORB_SLAM2 Stereo /home/wang/ROS_WS/orbslam_ws/src/ORB_SLAM2/Vocabulary/ORBvoc.txt /home/wang/ROS_WS/orbslam_ws/src/ORB_SLAM2/config/KITTI0930stereo.yaml false /camera/left/image_raw:=/kitti/camera_color_left/image_raw /camera/right/image_raw:=/kitti/camera_color_right/image_raw
2 |
--------------------------------------------------------------------------------
/Examples/ROS/ORB_SLAM2/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | ORB_SLAM2
4 |
5 | 0.1.0
6 |
7 | ROS package of ORB_SLAM2 dense point cloud version
8 | wang
9 |
10 | TODO
11 |
12 | catkin
13 | geometry_msgs
14 | nav_msgs
15 | roscpp
16 | sensor_msgs
17 | std_msgs
18 | cv_bridge
19 | tf
20 | tf_conversions
21 | pcl_ros
22 | pcl_conversions
23 |
24 | geometry_msgs
25 | nav_msgs
26 | roscpp
27 | sensor_msgs
28 | std_msgs
29 | cv_bridge
30 | tf
31 | tf_conversions
32 | pcl_ros
33 | pcl_conversions
34 |
35 | geometry_msgs
36 | nav_msgs
37 | roscpp
38 | sensor_msgs
39 | std_msgs
40 | cv_bridge
41 | tf
42 | tf_conversions
43 | pcl_ros
44 | pcl_conversions
45 |
--------------------------------------------------------------------------------
/Examples/ROS/ORB_SLAM2/raw.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/834810269/DF-ORB-SLAM/462425d61903fa6efc71dde3011cbc3c920c2c16/Examples/ROS/ORB_SLAM2/raw.png
--------------------------------------------------------------------------------
/Examples/ROS/ORB_SLAM2/src/ros_mono.cc:
--------------------------------------------------------------------------------
1 | /**
2 | * This file is part of ORB-SLAM2.
3 | *
4 | * Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza)
5 | * For more information see
6 | *
7 | * ORB-SLAM2 is free software: you can redistribute it and/or modify
8 | * it under the terms of the GNU General Public License as published by
9 | * the Free Software Foundation, either version 3 of the License, or
10 | * (at your option) any later version.
11 | *
12 | * ORB-SLAM2 is distributed in the hope that it will be useful,
13 | * but WITHOUT ANY WARRANTY; without even the implied warranty of
14 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 | * GNU General Public License for more details.
16 | *
17 | * You should have received a copy of the GNU General Public License
18 | * along with ORB-SLAM2. If not, see .
19 | */
20 |
21 |
22 | #include
23 | #include
24 | #include
25 | #include
26 |
27 | #include
28 | #include
29 |
30 | #include
31 |
32 | #include"../../../include/System.h"
33 |
34 | using namespace std;
35 |
36 | class ImageGrabber
37 | {
38 | public:
39 | ImageGrabber(ORB_SLAM2::System* pSLAM):mpSLAM(pSLAM){}
40 |
41 | void GrabImage(const sensor_msgs::ImageConstPtr& msg);
42 |
43 | ORB_SLAM2::System* mpSLAM;
44 | };
45 |
46 | int main(int argc, char **argv)
47 | {
48 | ros::init(argc, argv, "Mono");
49 | ros::start();
50 |
51 | if(argc != 3)
52 | {
53 | cerr << endl << "Usage: rosrun ORB_SLAM2 Mono path_to_vocabulary path_to_settings" << endl;
54 | ros::shutdown();
55 | return 1;
56 | }
57 |
58 | // Create SLAM system. It initializes all system threads and gets ready to process frames.
59 | ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true,false);
60 |
61 | ImageGrabber igb(&SLAM);
62 |
63 | ros::NodeHandle nodeHandler;
64 | ros::Subscriber sub = nodeHandler.subscribe("/camera/image_raw", 1, &ImageGrabber::GrabImage,&igb);
65 |
66 | ros::spin();
67 |
68 | // Stop all threads
69 | SLAM.Shutdown();
70 |
71 | // Save camera trajectory
72 | SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
73 |
74 | ros::shutdown();
75 |
76 | return 0;
77 | }
78 |
79 | void ImageGrabber::GrabImage(const sensor_msgs::ImageConstPtr& msg)
80 | {
81 | // Copy the ros image message to cv::Mat.
82 | cv_bridge::CvImageConstPtr cv_ptr;
83 | try
84 | {
85 | cv_ptr = cv_bridge::toCvShare(msg);
86 | }
87 | catch (cv_bridge::Exception& e)
88 | {
89 | ROS_ERROR("cv_bridge exception: %s", e.what());
90 | return;
91 | }
92 |
93 | mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec());
94 | }
95 |
96 |
97 |
--------------------------------------------------------------------------------
/LICENSE.txt:
--------------------------------------------------------------------------------
1 | ORB-SLAM2 is released under a GPLv3 license (see License-gpl.txt).
2 | Please see Dependencies.md for a list of all included code and library dependencies which are not property of the authors of ORB-SLAM2.
3 |
4 | For a closed-source version of ORB-SLAM2 for commercial purposes, please contact the authors.
5 |
6 | If you use ORB-SLAM in an academic work, please cite the most relevant publication associated by visiting:
7 | https://github.com/raulmur/ORB_SLAM2
8 |
9 |
10 |
11 |
12 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # DF-ORB-SLAM
2 |
3 | 
4 | 
5 |
--------------------------------------------------------------------------------
/Thirdparty/DBoW2/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8)
2 | project(DBoW2)
3 |
4 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ")
5 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native")
6 |
7 | set(HDRS_DBOW2
8 | DBoW2/BowVector.h
9 | DBoW2/FORB.h
10 | DBoW2/FClass.h
11 | DBoW2/FeatureVector.h
12 | DBoW2/ScoringObject.h
13 | DBoW2/TemplatedVocabulary.h)
14 | set(SRCS_DBOW2
15 | DBoW2/BowVector.cpp
16 | DBoW2/FORB.cpp
17 | DBoW2/FeatureVector.cpp
18 | DBoW2/ScoringObject.cpp)
19 |
20 | set(HDRS_DUTILS
21 | DUtils/Random.h
22 | DUtils/Timestamp.h)
23 | set(SRCS_DUTILS
24 | DUtils/Random.cpp
25 | DUtils/Timestamp.cpp)
26 |
27 | find_package(OpenCV 3.0 QUIET)
28 | if(NOT OpenCV_FOUND)
29 | find_package(OpenCV 2.4.3 QUIET)
30 | if(NOT OpenCV_FOUND)
31 | message(FATAL_ERROR "OpenCV > 2.4.3 not found.")
32 | endif()
33 | endif()
34 |
35 | set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
36 |
37 | include_directories(${OpenCV_INCLUDE_DIRS})
38 | add_library(DBoW2 SHARED ${SRCS_DBOW2} ${SRCS_DUTILS})
39 | target_link_libraries(DBoW2 ${OpenCV_LIBS})
40 |
41 |
--------------------------------------------------------------------------------
/Thirdparty/DBoW2/DBoW2/BowVector.cpp:
--------------------------------------------------------------------------------
1 | /**
2 | * File: BowVector.cpp
3 | * Date: March 2011
4 | * Author: Dorian Galvez-Lopez
5 | * Description: bag of words vector
6 | * License: see the LICENSE.txt file
7 | *
8 | */
9 |
10 | #include
11 | #include
12 | #include
13 | #include
14 | #include
15 |
16 | #include "BowVector.h"
17 |
18 | namespace DBoW2 {
19 |
20 | // --------------------------------------------------------------------------
21 |
22 | BowVector::BowVector(void)
23 | {
24 | }
25 |
26 | // --------------------------------------------------------------------------
27 |
28 | BowVector::~BowVector(void)
29 | {
30 | }
31 |
32 | // --------------------------------------------------------------------------
33 |
34 | void BowVector::addWeight(WordId id, WordValue v)
35 | {
36 | BowVector::iterator vit = this->lower_bound(id);
37 |
38 | if(vit != this->end() && !(this->key_comp()(id, vit->first)))
39 | {
40 | vit->second += v;
41 | }
42 | else
43 | {
44 | this->insert(vit, BowVector::value_type(id, v));
45 | }
46 | }
47 |
48 | // --------------------------------------------------------------------------
49 |
50 | void BowVector::addIfNotExist(WordId id, WordValue v)
51 | {
52 | BowVector::iterator vit = this->lower_bound(id);
53 |
54 | if(vit == this->end() || (this->key_comp()(id, vit->first)))
55 | {
56 | this->insert(vit, BowVector::value_type(id, v));
57 | }
58 | }
59 |
60 | // --------------------------------------------------------------------------
61 |
62 | void BowVector::normalize(LNorm norm_type)
63 | {
64 | double norm = 0.0;
65 | BowVector::iterator it;
66 |
67 | if(norm_type == DBoW2::L1)
68 | {
69 | for(it = begin(); it != end(); ++it)
70 | norm += fabs(it->second);
71 | }
72 | else
73 | {
74 | for(it = begin(); it != end(); ++it)
75 | norm += it->second * it->second;
76 | norm = sqrt(norm);
77 | }
78 |
79 | if(norm > 0.0)
80 | {
81 | for(it = begin(); it != end(); ++it)
82 | it->second /= norm;
83 | }
84 | }
85 |
86 | // --------------------------------------------------------------------------
87 |
88 | std::ostream& operator<< (std::ostream &out, const BowVector &v)
89 | {
90 | BowVector::const_iterator vit;
91 | std::vector::const_iterator iit;
92 | unsigned int i = 0;
93 | const unsigned int N = v.size();
94 | for(vit = v.begin(); vit != v.end(); ++vit, ++i)
95 | {
96 | out << "<" << vit->first << ", " << vit->second << ">";
97 |
98 | if(i < N-1) out << ", ";
99 | }
100 | return out;
101 | }
102 |
103 | // --------------------------------------------------------------------------
104 |
105 | void BowVector::saveM(const std::string &filename, size_t W) const
106 | {
107 | std::fstream f(filename.c_str(), std::ios::out);
108 |
109 | WordId last = 0;
110 | BowVector::const_iterator bit;
111 | for(bit = this->begin(); bit != this->end(); ++bit)
112 | {
113 | for(; last < bit->first; ++last)
114 | {
115 | f << "0 ";
116 | }
117 | f << bit->second << " ";
118 |
119 | last = bit->first + 1;
120 | }
121 | for(; last < (WordId)W; ++last)
122 | f << "0 ";
123 |
124 | f.close();
125 | }
126 |
127 | // --------------------------------------------------------------------------
128 |
129 | } // namespace DBoW2
130 |
131 |
--------------------------------------------------------------------------------
/Thirdparty/DBoW2/DBoW2/BowVector.h:
--------------------------------------------------------------------------------
1 | /**
2 | * File: BowVector.h
3 | * Date: March 2011
4 | * Author: Dorian Galvez-Lopez
5 | * Description: bag of words vector
6 | * License: see the LICENSE.txt file
7 | *
8 | */
9 |
10 | #ifndef __D_T_BOW_VECTOR__
11 | #define __D_T_BOW_VECTOR__
12 |
13 | #include
14 | #include