├── CMakeLists.txt ├── Examples ├── ICRA21-teasear.png ├── OFF1.png ├── R1.png ├── RGB-D │ ├── ICL.yaml │ ├── Planar_SLAM │ ├── TAMU.yaml │ ├── TUM1.yaml │ ├── TUM2.yaml │ ├── TUM3.yaml │ └── main.cc ├── planarReconstruction.png └── sphere.gif ├── 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 │ ├── build │ │ ├── CMakeCache.txt │ │ ├── CMakeFiles │ │ │ ├── 3.10.2 │ │ │ │ ├── CMakeCCompiler.cmake │ │ │ │ ├── CMakeCXXCompiler.cmake │ │ │ │ ├── CMakeDetermineCompilerABI_C.bin │ │ │ │ ├── CMakeDetermineCompilerABI_CXX.bin │ │ │ │ ├── CMakeSystem.cmake │ │ │ │ ├── CompilerIdC │ │ │ │ │ ├── CMakeCCompilerId.c │ │ │ │ │ └── a.out │ │ │ │ └── CompilerIdCXX │ │ │ │ │ ├── CMakeCXXCompilerId.cpp │ │ │ │ │ └── a.out │ │ │ ├── 3.18.4 │ │ │ │ ├── CMakeCCompiler.cmake │ │ │ │ ├── CMakeCXXCompiler.cmake │ │ │ │ ├── CMakeDetermineCompilerABI_C.bin │ │ │ │ ├── CMakeDetermineCompilerABI_CXX.bin │ │ │ │ ├── CMakeSystem.cmake │ │ │ │ ├── CompilerIdC │ │ │ │ │ ├── CMakeCCompilerId.c │ │ │ │ │ └── a.out │ │ │ │ └── CompilerIdCXX │ │ │ │ │ ├── CMakeCXXCompilerId.cpp │ │ │ │ │ └── a.out │ │ │ ├── CMakeDirectoryInformation.cmake │ │ │ ├── CMakeOutput.log │ │ │ ├── DBoW2.dir │ │ │ │ ├── CXX.includecache │ │ │ │ ├── DBoW2 │ │ │ │ │ ├── BowVector.cpp.o │ │ │ │ │ ├── FORB.cpp.o │ │ │ │ │ ├── FeatureVector.cpp.o │ │ │ │ │ └── ScoringObject.cpp.o │ │ │ │ ├── DUtils │ │ │ │ │ ├── Random.cpp.o │ │ │ │ │ └── Timestamp.cpp.o │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ ├── depend.internal │ │ │ │ ├── depend.make │ │ │ │ ├── flags.make │ │ │ │ ├── link.txt │ │ │ │ └── progress.make │ │ │ ├── Makefile.cmake │ │ │ ├── Makefile2 │ │ │ ├── TargetDirectories.txt │ │ │ ├── cmake.check_cache │ │ │ ├── feature_tests.bin │ │ │ ├── feature_tests.c │ │ │ ├── feature_tests.cxx │ │ │ └── progress.marks │ │ ├── Makefile │ │ └── cmake_install.cmake │ └── lib │ │ └── libDBoW2.so ├── g2o │ ├── CMakeLists.txt │ ├── README.txt │ ├── build │ │ ├── CMakeCache.txt │ │ ├── CMakeFiles │ │ │ ├── 3.10.2 │ │ │ │ ├── CMakeCCompiler.cmake │ │ │ │ ├── CMakeCXXCompiler.cmake │ │ │ │ ├── CMakeDetermineCompilerABI_C.bin │ │ │ │ ├── CMakeDetermineCompilerABI_CXX.bin │ │ │ │ ├── CMakeSystem.cmake │ │ │ │ ├── CompilerIdC │ │ │ │ │ ├── CMakeCCompilerId.c │ │ │ │ │ └── a.out │ │ │ │ └── CompilerIdCXX │ │ │ │ │ ├── CMakeCXXCompilerId.cpp │ │ │ │ │ └── a.out │ │ │ ├── 3.18.4 │ │ │ │ ├── CMakeCCompiler.cmake │ │ │ │ ├── CMakeCXXCompiler.cmake │ │ │ │ ├── CMakeDetermineCompilerABI_C.bin │ │ │ │ ├── CMakeDetermineCompilerABI_CXX.bin │ │ │ │ ├── CMakeSystem.cmake │ │ │ │ ├── CompilerIdC │ │ │ │ │ ├── CMakeCCompilerId.c │ │ │ │ │ └── a.out │ │ │ │ └── CompilerIdCXX │ │ │ │ │ ├── CMakeCXXCompilerId.cpp │ │ │ │ │ └── a.out │ │ │ ├── CMakeDirectoryInformation.cmake │ │ │ ├── CMakeOutput.log │ │ │ ├── FindOpenMP │ │ │ │ ├── OpenMPCheckVersion.c │ │ │ │ ├── OpenMPCheckVersion.cpp │ │ │ │ ├── OpenMPTryFlag.c │ │ │ │ ├── OpenMPTryFlag.cpp │ │ │ │ ├── ompver_C.bin │ │ │ │ └── ompver_CXX.bin │ │ │ ├── Makefile.cmake │ │ │ ├── Makefile2 │ │ │ ├── TargetDirectories.txt │ │ │ ├── cmake.check_cache │ │ │ ├── feature_tests.bin │ │ │ ├── feature_tests.c │ │ │ ├── feature_tests.cxx │ │ │ ├── g2o.dir │ │ │ │ ├── C.includecache │ │ │ │ ├── CXX.includecache │ │ │ │ ├── DependInfo.cmake │ │ │ │ ├── build.make │ │ │ │ ├── cmake_clean.cmake │ │ │ │ ├── depend.internal │ │ │ │ ├── depend.make │ │ │ │ ├── flags.make │ │ │ │ ├── g2o │ │ │ │ │ ├── core │ │ │ │ │ │ ├── batch_stats.cpp.o │ │ │ │ │ │ ├── cache.cpp.o │ │ │ │ │ │ ├── estimate_propagator.cpp.o │ │ │ │ │ │ ├── factory.cpp.o │ │ │ │ │ │ ├── hyper_dijkstra.cpp.o │ │ │ │ │ │ ├── hyper_graph.cpp.o │ │ │ │ │ │ ├── hyper_graph_action.cpp.o │ │ │ │ │ │ ├── jacobian_workspace.cpp.o │ │ │ │ │ │ ├── marginal_covariance_cholesky.cpp.o │ │ │ │ │ │ ├── matrix_structure.cpp.o │ │ │ │ │ │ ├── optimizable_graph.cpp.o │ │ │ │ │ │ ├── optimization_algorithm.cpp.o │ │ │ │ │ │ ├── optimization_algorithm_factory.cpp.o │ │ │ │ │ │ ├── optimization_algorithm_levenberg.cpp.o │ │ │ │ │ │ ├── optimization_algorithm_with_hessian.cpp.o │ │ │ │ │ │ ├── parameter.cpp.o │ │ │ │ │ │ ├── parameter_container.cpp.o │ │ │ │ │ │ ├── robust_kernel.cpp.o │ │ │ │ │ │ ├── robust_kernel_factory.cpp.o │ │ │ │ │ │ ├── robust_kernel_impl.cpp.o │ │ │ │ │ │ ├── solver.cpp.o │ │ │ │ │ │ └── sparse_optimizer.cpp.o │ │ │ │ │ ├── stuff │ │ │ │ │ │ ├── os_specific.c.o │ │ │ │ │ │ ├── property.cpp.o │ │ │ │ │ │ ├── string_tools.cpp.o │ │ │ │ │ │ └── timeutil.cpp.o │ │ │ │ │ └── types │ │ │ │ │ │ ├── types_sba.cpp.o │ │ │ │ │ │ ├── types_seven_dof_expmap.cpp.o │ │ │ │ │ │ └── types_six_dof_expmap.cpp.o │ │ │ │ ├── link.txt │ │ │ │ └── progress.make │ │ │ └── progress.marks │ │ ├── Makefile │ │ └── cmake_install.cmake │ ├── cmake_modules │ │ ├── FindBLAS.cmake │ │ ├── FindEigen3.cmake │ │ └── FindLAPACK.cmake │ ├── config.h │ ├── 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 │ ├── lib │ │ └── libg2o.so │ └── license-bsd.txt └── triangle │ ├── triangle.cpp │ └── triangle.h ├── Vocabulary └── ORBvoc.txt.tar.gz ├── build.sh ├── cmake_modules └── FindEigen3.cmake ├── g2oAddition ├── EdgeParallelPlane.h ├── EdgePlane.h ├── EdgePlanePoint.h ├── EdgeVerticalPlane.h ├── Plane3D.h └── VertexPlane.h ├── include ├── Config.h ├── Converter.h ├── EdgeLine.h ├── Frame.h ├── FrameDrawer.h ├── Initializer.h ├── KeyFrame.h ├── KeyFrameDatabase.h ├── LSDextractor.h ├── LSDmatcher.h ├── LevenbergMarquardt.h ├── LocalMapping.h ├── LoopClosing.h ├── Map.h ├── MapDrawer.h ├── MapLine.h ├── MapPlane.h ├── MapPoint.h ├── Mesh.h ├── MeshViewer.h ├── ORBVocabulary.h ├── ORBextractor.h ├── ORBmatcher.h ├── Optimizer.h ├── PlaneExtractor.h ├── PlaneMatcher.h ├── PnPsolver.h ├── Sim3Solver.h ├── System.h ├── Tracking.h ├── Viewer.h ├── auxiliar.h └── peac │ ├── AHCParamSet.hpp │ ├── AHCPlaneFitter.hpp │ ├── AHCPlaneSeg.hpp │ ├── AHCTypes.hpp │ ├── AHCUtils.hpp │ ├── DisjointSet.hpp │ └── eig33sym.hpp └── src ├── Config.cc ├── Converter.cc ├── Frame.cc ├── FrameDrawer.cc ├── Initializer.cc ├── KeyFrame.cc ├── KeyFrameDatabase.cc ├── LSDextractor.cpp ├── LSDmatcher.cpp ├── LineExtractor.cpp ├── LocalMapping.cc ├── LoopClosing.cc ├── Map.cc ├── MapDrawer.cc ├── MapLine.cpp ├── MapPlane.cc ├── MapPoint.cc ├── MeshViewer.cc ├── ORBextractor.cc ├── ORBmatcher.cc ├── Optimizer.cc ├── PlaneExtractor.cpp ├── PlaneMatcher.cpp ├── PnPsolver.cc ├── Sim3Solver.cc ├── System.cc ├── Tracking.cc └── Viewer.cc /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8) 2 | project(PlanarSLAM) 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 | #set(CMAKE_CXX_STANDARD 14) 13 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 14 | # Check C++11 or C++0x support 15 | include(CheckCXXCompilerFlag) 16 | CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11) 17 | CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X) 18 | if (COMPILER_SUPPORTS_CXX11) 19 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") 20 | add_definitions(-DCOMPILEDWITHC11) 21 | message(STATUS "Using flag -std=c++11.") 22 | elseif (COMPILER_SUPPORTS_CXX0X) 23 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x") 24 | add_definitions(-DCOMPILEDWITHC0X) 25 | message(STATUS "Using flag -std=c++0x.") 26 | else () 27 | message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.") 28 | endif () 29 | 30 | LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules) 31 | 32 | find_package(OpenCV 3.0 QUIET) 33 | if (NOT OpenCV_FOUND) 34 | find_package(OpenCV 2.4.3 QUIET) 35 | if (NOT OpenCV_FOUND) 36 | message(FATAL_ERROR "OpenCV > 2.4.3 not found.") 37 | endif () 38 | endif () 39 | 40 | message(OPENCV_VERSION) 41 | 42 | find_package(Eigen3 3.1.0 REQUIRED) 43 | find_package(Pangolin REQUIRED) 44 | find_package(PCL 1.7 REQUIRED) 45 | 46 | include_directories( 47 | ${PROJECT_SOURCE_DIR} 48 | ${PROJECT_SOURCE_DIR}/include 49 | ${PROJECT_SOURCE_DIR}/g2oAddition 50 | ${EIGEN3_INCLUDE_DIR} 51 | ${Pangolin_INCLUDE_DIRS} 52 | ${PCL_INCLUDE_DIRS} 53 | ) 54 | 55 | include_directories(include/peac) 56 | add_definitions(${PCL_DEFINITIONS}) 57 | link_directories(${PCL_LIBRARY_DIRS}) 58 | 59 | set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/lib) 60 | 61 | add_library(${PROJECT_NAME} SHARED 62 | src/System.cc 63 | src/Tracking.cc 64 | src/LocalMapping.cc 65 | src/LoopClosing.cc 66 | src/ORBextractor.cc 67 | src/ORBmatcher.cc 68 | src/FrameDrawer.cc 69 | src/Converter.cc 70 | src/MapPoint.cc 71 | src/MapLine.cpp 72 | src/KeyFrame.cc 73 | src/Map.cc 74 | src/MapDrawer.cc 75 | src/Optimizer.cc 76 | src/PnPsolver.cc 77 | src/Frame.cc 78 | src/KeyFrameDatabase.cc 79 | src/Sim3Solver.cc 80 | src/Initializer.cc 81 | src/Viewer.cc 82 | src/LineExtractor.cpp 83 | src/LSDextractor.cpp 84 | src/LSDmatcher.cpp 85 | src/PlaneExtractor.cpp 86 | src/Config.cc 87 | src/MapPlane.cc 88 | src/MeshViewer.cc 89 | src/PlaneMatcher.cpp 90 | Thirdparty/triangle/triangle.cpp 91 | ) 92 | file(GLOB sources "*.cpp") 93 | target_link_libraries(${PROJECT_NAME} 94 | ${OpenCV_LIBS} 95 | ${EIGEN3_LIBS} 96 | ${Pangolin_LIBRARIES} 97 | ${PROJECT_SOURCE_DIR}/Thirdparty/DBoW2/lib/libDBoW2.so 98 | ${PROJECT_SOURCE_DIR}/Thirdparty/g2o/lib/libg2o.so 99 | ${PCL_LIBRARIES} 100 | ) 101 | 102 | # Build examples 103 | 104 | set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples/RGB-D) 105 | add_executable(Planar_SLAM Examples/RGB-D/main.cc) 106 | target_link_libraries(Planar_SLAM ${PROJECT_NAME}) 107 | 108 | 109 | 110 | 111 | 112 | -------------------------------------------------------------------------------- /Examples/ICRA21-teasear.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Examples/ICRA21-teasear.png -------------------------------------------------------------------------------- /Examples/OFF1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Examples/OFF1.png -------------------------------------------------------------------------------- /Examples/R1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Examples/R1.png -------------------------------------------------------------------------------- /Examples/RGB-D/ICL.yaml: -------------------------------------------------------------------------------- 1 | %YAML:1.0 2 | 3 | #-------------------------------------------------------------------------------------------- 4 | # Camera Parameters. Adjust them! 5 | #-------------------------------------------------------------------------------------------- 6 | 7 | # Camera calibration and distortion parameters (OpenCV) 8 | Camera.fx: 481.2 9 | Camera.fy: -480.0 10 | Camera.cx: 319.5 11 | Camera.cy: 239.50 12 | 13 | Camera.k1: 0.0 14 | Camera.k2: 0.0 15 | Camera.p1: 0.0 16 | Camera.p2: 0.0 17 | 18 | Camera.width: 640 19 | Camera.height: 480 20 | 21 | # Camera frames per second 22 | Camera.fps: 30.0 23 | 24 | # IR projector baseline times fx (aprox.) 25 | Camera.bf: 40.0 26 | 27 | # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) 28 | Camera.RGB: 1 29 | 30 | # Close/Far threshold. Baseline times. 31 | ThDepth: 40.0 32 | 33 | # Deptmap values factor 34 | DepthMapFactor: 5000.0 35 | 36 | #-------------------------------------------------------------------------------------------- 37 | # ORB Parameters 38 | #-------------------------------------------------------------------------------------------- 39 | 40 | # ORB Extractor: Number of features per image 41 | ORBextractor.nFeatures: 1000 42 | 43 | # ORB Extractor: Scale factor between levels in the scale pyramid 44 | ORBextractor.scaleFactor: 1.2 45 | 46 | # ORB Extractor: Number of levels in the scale pyramid 47 | ORBextractor.nLevels: 8 48 | 49 | # ORB Extractor: Fast threshold 50 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. 51 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST 52 | # You can lower these values if your images have low contrast 53 | ORBextractor.iniThFAST: 20 54 | ORBextractor.minThFAST: 7 55 | 56 | #-------------------------------------------------------------------------------------------- 57 | # Viewer Parameters 58 | #-------------------------------------------------------------------------------------------- 59 | Viewer.KeyFrameSize: 0.05 60 | Viewer.KeyFrameLineWidth: 1 61 | Viewer.GraphLineWidth: 1 62 | Viewer.PointSize: 4 63 | Viewer.CameraSize: 0.08 64 | Viewer.CameraLineWidth: 3 65 | Viewer.ViewpointX: 0 66 | Viewer.ViewpointY: -0.7 67 | Viewer.ViewpointZ: -1.8 68 | Viewer.ViewpointF: 500 69 | 70 | Plane.MinSize: 500 71 | Plane.AngleThreshold: 3.0 72 | Plane.DistanceThreshold: 0.03 73 | 74 | Plane.LeafSize: 0.01 75 | Plane.MaxDistance: 10.0 76 | 77 | Plane.AssociationDisRef: 0.05 78 | Plane.AssociationDisMon: 0.05 79 | #Plane.AssociationAngRef: 0.8 # 30 degree 80 | #Plane.AssociationAngMon: 0.8 # 30 degree 81 | #Plane.AssociationAngRef: 0.6428 # 50 degree 82 | #Plane.AssociationAngMon: 0.6428 # 50 degree 83 | #Plane.AssociationAngRef: 0.965 # 15 degree 84 | #Plane.AssociationAngMon: 0.965 # 15 degree 85 | Plane.AssociationAngRef: 0.985 # 10 degree 86 | Plane.AssociationAngMon: 0.985 # 10 degree 87 | 88 | 89 | #Plane.VerticalThreshold: 0.0523 # 87 degree 90 | Plane.VerticalThreshold: 0.08716 # 85 degree 91 | #Plane.VerticalThreshold: 0.17365 # 80 degree 92 | #Plane.VerticalThreshold: 0.0 # no vertical constraint 93 | #Plane.ParallelThreshold: 0.98481 # 10 degree 94 | #Plane.ParallelThreshold: 1.9962 # no parallel constraint 95 | Plane.ParallelThreshold: 0.9962 # 5 degree 96 | 97 | #Plane.AngleInfo: 57.3 # 1 degree 98 | #Plane.AngleInfo: 19.1 # 3 degree 99 | Plane.AngleInfo: 0.5 100 | Plane.DistanceInfo: 50 101 | 102 | Plane.Chi: 100 103 | Plane.VPChi: 50 104 | 105 | Plane.ParallelInfo: 0.1 106 | Plane.VerticalInfo: 0.1 107 | 108 | SavePath.Frame: "CameraTrajectory.txt" 109 | SavePath.Keyframe: "KeyFrameTrajectory.txt" -------------------------------------------------------------------------------- /Examples/RGB-D/Planar_SLAM: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Examples/RGB-D/Planar_SLAM -------------------------------------------------------------------------------- /Examples/planarReconstruction.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Examples/planarReconstruction.png -------------------------------------------------------------------------------- /Examples/sphere.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Examples/sphere.gif -------------------------------------------------------------------------------- /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 15 | #include 16 | 17 | namespace DBoW2 { 18 | 19 | /// Id of words 20 | typedef unsigned int WordId; 21 | 22 | /// Value of a word 23 | typedef double WordValue; 24 | 25 | /// Id of nodes in the vocabulary treee 26 | typedef unsigned int NodeId; 27 | 28 | /// L-norms for normalization 29 | enum LNorm 30 | { 31 | L1, 32 | L2 33 | }; 34 | 35 | /// Weighting type 36 | enum WeightingType 37 | { 38 | TF_IDF, 39 | TF, 40 | IDF, 41 | BINARY 42 | }; 43 | 44 | /// Scoring type 45 | enum ScoringType 46 | { 47 | L1_NORM, 48 | L2_NORM, 49 | CHI_SQUARE, 50 | KL, 51 | BHATTACHARYYA, 52 | DOT_PRODUCT, 53 | }; 54 | 55 | /// Vector of words to represent images 56 | class BowVector: 57 | public std::map 58 | { 59 | public: 60 | 61 | /** 62 | * Constructor 63 | */ 64 | BowVector(void); 65 | 66 | /** 67 | * Destructor 68 | */ 69 | ~BowVector(void); 70 | 71 | /** 72 | * Adds a value to a word value existing in the vector, or creates a new 73 | * word with the given value 74 | * @param id word id to look for 75 | * @param v value to create the word with, or to add to existing word 76 | */ 77 | void addWeight(WordId id, WordValue v); 78 | 79 | /** 80 | * Adds a word with a value to the vector only if this does not exist yet 81 | * @param id word id to look for 82 | * @param v value to give to the word if this does not exist 83 | */ 84 | void addIfNotExist(WordId id, WordValue v); 85 | 86 | /** 87 | * L1-Normalizes the values in the vector 88 | * @param norm_type norm used 89 | */ 90 | void normalize(LNorm norm_type); 91 | 92 | /** 93 | * Prints the content of the bow vector 94 | * @param out stream 95 | * @param v 96 | */ 97 | friend std::ostream& operator<<(std::ostream &out, const BowVector &v); 98 | 99 | /** 100 | * Saves the bow vector as a vector in a matlab file 101 | * @param filename 102 | * @param W number of words in the vocabulary 103 | */ 104 | void saveM(const std::string &filename, size_t W) const; 105 | }; 106 | 107 | } // namespace DBoW2 108 | 109 | #endif 110 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/DBoW2/FClass.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FClass.h 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: generic FClass to instantiate templated classes 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_FCLASS__ 11 | #define __D_T_FCLASS__ 12 | 13 | #include 14 | #include 15 | #include 16 | 17 | namespace DBoW2 { 18 | 19 | /// Generic class to encapsulate functions to manage descriptors. 20 | /** 21 | * This class must be inherited. Derived classes can be used as the 22 | * parameter F when creating Templated structures 23 | * (TemplatedVocabulary, TemplatedDatabase, ...) 24 | */ 25 | class FClass 26 | { 27 | class TDescriptor; 28 | typedef const TDescriptor *pDescriptor; 29 | 30 | /** 31 | * Calculates the mean value of a set of descriptors 32 | * @param descriptors 33 | * @param mean mean descriptor 34 | */ 35 | virtual void meanValue(const std::vector &descriptors, 36 | TDescriptor &mean) = 0; 37 | 38 | /** 39 | * Calculates the distance between two descriptors 40 | * @param a 41 | * @param b 42 | * @return distance 43 | */ 44 | static double distance(const TDescriptor &a, const TDescriptor &b); 45 | 46 | /** 47 | * Returns a string version of the descriptor 48 | * @param a descriptor 49 | * @return string version 50 | */ 51 | static std::string toString(const TDescriptor &a); 52 | 53 | /** 54 | * Returns a descriptor from a string 55 | * @param a descriptor 56 | * @param s string version 57 | */ 58 | static void fromString(TDescriptor &a, const std::string &s); 59 | 60 | /** 61 | * Returns a mat with the descriptors in float format 62 | * @param descriptors 63 | * @param mat (out) NxL 32F matrix 64 | */ 65 | static void toMat32F(const std::vector &descriptors, 66 | cv::Mat &mat); 67 | }; 68 | 69 | } // namespace DBoW2 70 | 71 | #endif 72 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/DBoW2/FORB.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FORB.h 3 | * Date: June 2012 4 | * Author: Dorian Galvez-Lopez 5 | * Description: functions for ORB descriptors 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_F_ORB__ 11 | #define __D_T_F_ORB__ 12 | 13 | #include 14 | #include 15 | #include 16 | 17 | #include "FClass.h" 18 | 19 | namespace DBoW2 { 20 | 21 | /// Functions to manipulate ORB descriptors 22 | class FORB: protected FClass 23 | { 24 | public: 25 | 26 | /// Descriptor type 27 | typedef cv::Mat TDescriptor; // CV_8U 28 | /// Pointer to a single descriptor 29 | typedef const TDescriptor *pDescriptor; 30 | /// Descriptor length (in bytes) 31 | static const int L; 32 | 33 | /** 34 | * Calculates the mean value of a set of descriptors 35 | * @param descriptors 36 | * @param mean mean descriptor 37 | */ 38 | static void meanValue(const std::vector &descriptors, 39 | TDescriptor &mean); 40 | 41 | /** 42 | * Calculates the distance between two descriptors 43 | * @param a 44 | * @param b 45 | * @return distance 46 | */ 47 | static int distance(const TDescriptor &a, const TDescriptor &b); 48 | 49 | /** 50 | * Returns a string version of the descriptor 51 | * @param a descriptor 52 | * @return string version 53 | */ 54 | static std::string toString(const TDescriptor &a); 55 | 56 | /** 57 | * Returns a descriptor from a string 58 | * @param a descriptor 59 | * @param s string version 60 | */ 61 | static void fromString(TDescriptor &a, const std::string &s); 62 | 63 | /** 64 | * Returns a mat with the descriptors in float format 65 | * @param descriptors 66 | * @param mat (out) NxL 32F matrix 67 | */ 68 | static void toMat32F(const std::vector &descriptors, 69 | cv::Mat &mat); 70 | 71 | static void toMat8U(const std::vector &descriptors, 72 | cv::Mat &mat); 73 | 74 | }; 75 | 76 | } // namespace DBoW2 77 | 78 | #endif 79 | 80 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/DBoW2/FeatureVector.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FeatureVector.cpp 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: feature vector 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #include "FeatureVector.h" 11 | #include 12 | #include 13 | #include 14 | 15 | namespace DBoW2 { 16 | 17 | // --------------------------------------------------------------------------- 18 | 19 | FeatureVector::FeatureVector(void) 20 | { 21 | } 22 | 23 | // --------------------------------------------------------------------------- 24 | 25 | FeatureVector::~FeatureVector(void) 26 | { 27 | } 28 | 29 | // --------------------------------------------------------------------------- 30 | 31 | void FeatureVector::addFeature(NodeId id, unsigned int i_feature) 32 | { 33 | FeatureVector::iterator vit = this->lower_bound(id); 34 | 35 | if(vit != this->end() && vit->first == id) 36 | { 37 | vit->second.push_back(i_feature); 38 | } 39 | else 40 | { 41 | vit = this->insert(vit, FeatureVector::value_type(id, 42 | std::vector() )); 43 | vit->second.push_back(i_feature); 44 | } 45 | } 46 | 47 | // --------------------------------------------------------------------------- 48 | 49 | std::ostream& operator<<(std::ostream &out, 50 | const FeatureVector &v) 51 | { 52 | if(!v.empty()) 53 | { 54 | FeatureVector::const_iterator vit = v.begin(); 55 | 56 | const std::vector* f = &vit->second; 57 | 58 | out << "<" << vit->first << ": ["; 59 | if(!f->empty()) out << (*f)[0]; 60 | for(unsigned int i = 1; i < f->size(); ++i) 61 | { 62 | out << ", " << (*f)[i]; 63 | } 64 | out << "]>"; 65 | 66 | for(++vit; vit != v.end(); ++vit) 67 | { 68 | f = &vit->second; 69 | 70 | out << ", <" << vit->first << ": ["; 71 | if(!f->empty()) out << (*f)[0]; 72 | for(unsigned int i = 1; i < f->size(); ++i) 73 | { 74 | out << ", " << (*f)[i]; 75 | } 76 | out << "]>"; 77 | } 78 | } 79 | 80 | return out; 81 | } 82 | 83 | // --------------------------------------------------------------------------- 84 | 85 | } // namespace DBoW2 86 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/DBoW2/FeatureVector.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FeatureVector.h 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: feature vector 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_FEATURE_VECTOR__ 11 | #define __D_T_FEATURE_VECTOR__ 12 | 13 | #include "BowVector.h" 14 | #include 15 | #include 16 | #include 17 | 18 | namespace DBoW2 { 19 | 20 | /// Vector of nodes with indexes of local features 21 | class FeatureVector: 22 | public std::map > 23 | { 24 | public: 25 | 26 | /** 27 | * Constructor 28 | */ 29 | FeatureVector(void); 30 | 31 | /** 32 | * Destructor 33 | */ 34 | ~FeatureVector(void); 35 | 36 | /** 37 | * Adds a feature to an existing node, or adds a new node with an initial 38 | * feature 39 | * @param id node id to add or to modify 40 | * @param i_feature index of feature to add to the given node 41 | */ 42 | void addFeature(NodeId id, unsigned int i_feature); 43 | 44 | /** 45 | * Sends a string versions of the feature vector through the stream 46 | * @param out stream 47 | * @param v feature vector 48 | */ 49 | friend std::ostream& operator<<(std::ostream &out, const FeatureVector &v); 50 | 51 | }; 52 | 53 | } // namespace DBoW2 54 | 55 | #endif 56 | 57 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/DBoW2/ScoringObject.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: ScoringObject.h 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: functions to compute bow scores 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_SCORING_OBJECT__ 11 | #define __D_T_SCORING_OBJECT__ 12 | 13 | #include "BowVector.h" 14 | 15 | namespace DBoW2 { 16 | 17 | /// Base class of scoring functions 18 | class GeneralScoring 19 | { 20 | public: 21 | /** 22 | * Computes the score between two vectors. Vectors must be sorted and 23 | * normalized if necessary 24 | * @param v (in/out) 25 | * @param w (in/out) 26 | * @return score 27 | */ 28 | virtual double score(const BowVector &v, const BowVector &w) const = 0; 29 | 30 | /** 31 | * Returns whether a vector must be normalized before scoring according 32 | * to the scoring scheme 33 | * @param norm norm to use 34 | * @return true iff must normalize 35 | */ 36 | virtual bool mustNormalize(LNorm &norm) const = 0; 37 | 38 | /// Log of epsilon 39 | static const double LOG_EPS; 40 | // If you change the type of WordValue, make sure you change also the 41 | // epsilon value (this is needed by the KL method) 42 | 43 | virtual ~GeneralScoring() {} //!< Required for virtual base classes 44 | 45 | }; 46 | 47 | /** 48 | * Macro for defining Scoring classes 49 | * @param NAME name of class 50 | * @param MUSTNORMALIZE if vectors must be normalized to compute the score 51 | * @param NORM type of norm to use when MUSTNORMALIZE 52 | */ 53 | #define __SCORING_CLASS(NAME, MUSTNORMALIZE, NORM) \ 54 | NAME: public GeneralScoring \ 55 | { public: \ 56 | /** \ 57 | * Computes score between two vectors \ 58 | * @param v \ 59 | * @param w \ 60 | * @return score between v and w \ 61 | */ \ 62 | virtual double score(const BowVector &v, const BowVector &w) const; \ 63 | \ 64 | /** \ 65 | * Says if a vector must be normalized according to the scoring function \ 66 | * @param norm (out) if true, norm to use 67 | * @return true iff vectors must be normalized \ 68 | */ \ 69 | virtual inline bool mustNormalize(LNorm &norm) const \ 70 | { norm = NORM; return MUSTNORMALIZE; } \ 71 | } 72 | 73 | /// L1 Scoring object 74 | class __SCORING_CLASS(L1Scoring, true, L1); 75 | 76 | /// L2 Scoring object 77 | class __SCORING_CLASS(L2Scoring, true, L2); 78 | 79 | /// Chi square Scoring object 80 | class __SCORING_CLASS(ChiSquareScoring, true, L1); 81 | 82 | /// KL divergence Scoring object 83 | class __SCORING_CLASS(KLScoring, true, L1); 84 | 85 | /// Bhattacharyya Scoring object 86 | class __SCORING_CLASS(BhattacharyyaScoring, true, L1); 87 | 88 | /// Dot product Scoring object 89 | class __SCORING_CLASS(DotProductScoring, false, L1); 90 | 91 | #undef __SCORING_CLASS 92 | 93 | } // namespace DBoW2 94 | 95 | #endif 96 | 97 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/DUtils/Random.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * File: Random.cpp 3 | * Project: DUtils library 4 | * Author: Dorian Galvez-Lopez 5 | * Date: April 2010 6 | * Description: manages pseudo-random numbers 7 | * License: see the LICENSE.txt file 8 | * 9 | */ 10 | 11 | #include "Random.h" 12 | #include "Timestamp.h" 13 | #include 14 | using namespace std; 15 | 16 | bool DUtils::Random::m_already_seeded = false; 17 | 18 | void DUtils::Random::SeedRand(){ 19 | Timestamp time; 20 | time.setToCurrentTime(); 21 | srand((unsigned)time.getFloatTime()); 22 | } 23 | 24 | void DUtils::Random::SeedRandOnce() 25 | { 26 | if(!m_already_seeded) 27 | { 28 | DUtils::Random::SeedRand(); 29 | m_already_seeded = true; 30 | } 31 | } 32 | 33 | void DUtils::Random::SeedRand(int seed) 34 | { 35 | srand(seed); 36 | } 37 | 38 | void DUtils::Random::SeedRandOnce(int seed) 39 | { 40 | if(!m_already_seeded) 41 | { 42 | DUtils::Random::SeedRand(seed); 43 | m_already_seeded = true; 44 | } 45 | } 46 | 47 | int DUtils::Random::RandomInt(int min, int max){ 48 | int d = max - min + 1; 49 | return int(((double)rand()/((double)RAND_MAX + 1.0)) * d) + min; 50 | } 51 | 52 | // --------------------------------------------------------------------------- 53 | // --------------------------------------------------------------------------- 54 | 55 | DUtils::Random::UnrepeatedRandomizer::UnrepeatedRandomizer(int min, int max) 56 | { 57 | if(min <= max) 58 | { 59 | m_min = min; 60 | m_max = max; 61 | } 62 | else 63 | { 64 | m_min = max; 65 | m_max = min; 66 | } 67 | 68 | createValues(); 69 | } 70 | 71 | // --------------------------------------------------------------------------- 72 | 73 | DUtils::Random::UnrepeatedRandomizer::UnrepeatedRandomizer 74 | (const DUtils::Random::UnrepeatedRandomizer& rnd) 75 | { 76 | *this = rnd; 77 | } 78 | 79 | // --------------------------------------------------------------------------- 80 | 81 | int DUtils::Random::UnrepeatedRandomizer::get() 82 | { 83 | if(empty()) createValues(); 84 | 85 | DUtils::Random::SeedRandOnce(); 86 | 87 | int k = DUtils::Random::RandomInt(0, m_values.size()-1); 88 | int ret = m_values[k]; 89 | m_values[k] = m_values.back(); 90 | m_values.pop_back(); 91 | 92 | return ret; 93 | } 94 | 95 | // --------------------------------------------------------------------------- 96 | 97 | void DUtils::Random::UnrepeatedRandomizer::createValues() 98 | { 99 | int n = m_max - m_min + 1; 100 | 101 | m_values.resize(n); 102 | for(int i = 0; i < n; ++i) m_values[i] = m_min + i; 103 | } 104 | 105 | // --------------------------------------------------------------------------- 106 | 107 | void DUtils::Random::UnrepeatedRandomizer::reset() 108 | { 109 | if((int)m_values.size() != m_max - m_min + 1) createValues(); 110 | } 111 | 112 | // --------------------------------------------------------------------------- 113 | 114 | DUtils::Random::UnrepeatedRandomizer& 115 | DUtils::Random::UnrepeatedRandomizer::operator= 116 | (const DUtils::Random::UnrepeatedRandomizer& rnd) 117 | { 118 | if(this != &rnd) 119 | { 120 | this->m_min = rnd.m_min; 121 | this->m_max = rnd.m_max; 122 | this->m_values = rnd.m_values; 123 | } 124 | return *this; 125 | } 126 | 127 | // --------------------------------------------------------------------------- 128 | 129 | 130 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/LICENSE.txt: -------------------------------------------------------------------------------- 1 | DBoW2: bag-of-words library for C++ with generic descriptors 2 | 3 | Copyright (c) 2015 Dorian Galvez-Lopez (Universidad de Zaragoza) 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions 8 | are met: 9 | 1. Redistributions of source code must retain the above copyright 10 | notice, this list of conditions and the following disclaimer. 11 | 2. Redistributions in binary form must reproduce the above copyright 12 | notice, this list of conditions and the following disclaimer in the 13 | documentation and/or other materials provided with the distribution. 14 | 3. Neither the name of copyright holders nor the names of its 15 | contributors may be used to endorse or promote products derived 16 | from this software without specific prior written permission. 17 | 18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 19 | ''AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 20 | TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 21 | PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS OR CONTRIBUTORS 22 | BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 23 | CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 24 | SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 25 | INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 26 | CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 27 | ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 28 | POSSIBILITY OF SUCH DAMAGE. 29 | 30 | If you use it in an academic work, please cite: 31 | 32 | @ARTICLE{GalvezTRO12, 33 | author={G\'alvez-L\'opez, Dorian and Tard\'os, J. D.}, 34 | journal={IEEE Transactions on Robotics}, 35 | title={Bags of Binary Words for Fast Place Recognition in Image Sequences}, 36 | year={2012}, 37 | month={October}, 38 | volume={28}, 39 | number={5}, 40 | pages={1188--1197}, 41 | doi={10.1109/TRO.2012.2197158}, 42 | ISSN={1552-3098} 43 | } 44 | 45 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/README.txt: -------------------------------------------------------------------------------- 1 | You should have received this DBoW2 version along with ORB-SLAM2 (https://github.com/raulmur/Planar_SLAM). 2 | See the original DBoW2 library at: https://github.com/dorian3d/DBoW2 3 | All files included in this version are BSD, see LICENSE.txt 4 | 5 | We also use Random.h, Random.cpp, Timestamp.pp and Timestamp.h from DLib/DUtils. 6 | See the original DLib library at: https://github.com/dorian3d/DLib 7 | All files included in this version are BSD, see LICENSE.txt 8 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/3.10.2/CMakeCCompiler.cmake: -------------------------------------------------------------------------------- 1 | set(CMAKE_C_COMPILER "/usr/bin/cc") 2 | set(CMAKE_C_COMPILER_ARG1 "") 3 | set(CMAKE_C_COMPILER_ID "GNU") 4 | set(CMAKE_C_COMPILER_VERSION "7.5.0") 5 | set(CMAKE_C_COMPILER_VERSION_INTERNAL "") 6 | set(CMAKE_C_COMPILER_WRAPPER "") 7 | set(CMAKE_C_STANDARD_COMPUTED_DEFAULT "11") 8 | set(CMAKE_C_COMPILE_FEATURES "c_std_90;c_function_prototypes;c_std_99;c_restrict;c_variadic_macros;c_std_11;c_static_assert") 9 | set(CMAKE_C90_COMPILE_FEATURES "c_std_90;c_function_prototypes") 10 | set(CMAKE_C99_COMPILE_FEATURES "c_std_99;c_restrict;c_variadic_macros") 11 | set(CMAKE_C11_COMPILE_FEATURES "c_std_11;c_static_assert") 12 | 13 | set(CMAKE_C_PLATFORM_ID "Linux") 14 | set(CMAKE_C_SIMULATE_ID "") 15 | set(CMAKE_C_SIMULATE_VERSION "") 16 | 17 | 18 | 19 | set(CMAKE_AR "/usr/bin/ar") 20 | set(CMAKE_C_COMPILER_AR "/usr/bin/gcc-ar-7") 21 | set(CMAKE_RANLIB "/usr/bin/ranlib") 22 | set(CMAKE_C_COMPILER_RANLIB "/usr/bin/gcc-ranlib-7") 23 | set(CMAKE_LINKER "/usr/bin/ld") 24 | set(CMAKE_COMPILER_IS_GNUCC 1) 25 | set(CMAKE_C_COMPILER_LOADED 1) 26 | set(CMAKE_C_COMPILER_WORKS TRUE) 27 | set(CMAKE_C_ABI_COMPILED TRUE) 28 | set(CMAKE_COMPILER_IS_MINGW ) 29 | set(CMAKE_COMPILER_IS_CYGWIN ) 30 | if(CMAKE_COMPILER_IS_CYGWIN) 31 | set(CYGWIN 1) 32 | set(UNIX 1) 33 | endif() 34 | 35 | set(CMAKE_C_COMPILER_ENV_VAR "CC") 36 | 37 | if(CMAKE_COMPILER_IS_MINGW) 38 | set(MINGW 1) 39 | endif() 40 | set(CMAKE_C_COMPILER_ID_RUN 1) 41 | set(CMAKE_C_SOURCE_FILE_EXTENSIONS c;m) 42 | set(CMAKE_C_IGNORE_EXTENSIONS h;H;o;O;obj;OBJ;def;DEF;rc;RC) 43 | set(CMAKE_C_LINKER_PREFERENCE 10) 44 | 45 | # Save compiler ABI information. 46 | set(CMAKE_C_SIZEOF_DATA_PTR "8") 47 | set(CMAKE_C_COMPILER_ABI "ELF") 48 | set(CMAKE_C_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") 49 | 50 | if(CMAKE_C_SIZEOF_DATA_PTR) 51 | set(CMAKE_SIZEOF_VOID_P "${CMAKE_C_SIZEOF_DATA_PTR}") 52 | endif() 53 | 54 | if(CMAKE_C_COMPILER_ABI) 55 | set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_C_COMPILER_ABI}") 56 | endif() 57 | 58 | if(CMAKE_C_LIBRARY_ARCHITECTURE) 59 | set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") 60 | endif() 61 | 62 | set(CMAKE_C_CL_SHOWINCLUDES_PREFIX "") 63 | if(CMAKE_C_CL_SHOWINCLUDES_PREFIX) 64 | set(CMAKE_CL_SHOWINCLUDES_PREFIX "${CMAKE_C_CL_SHOWINCLUDES_PREFIX}") 65 | endif() 66 | 67 | 68 | 69 | 70 | 71 | set(CMAKE_C_IMPLICIT_LINK_LIBRARIES "gcc;gcc_s;c;gcc;gcc_s") 72 | set(CMAKE_C_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/7;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") 73 | set(CMAKE_C_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") 74 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/3.10.2/CMakeDetermineCompilerABI_C.bin: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/DBoW2/build/CMakeFiles/3.10.2/CMakeDetermineCompilerABI_C.bin -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/3.10.2/CMakeDetermineCompilerABI_CXX.bin: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/DBoW2/build/CMakeFiles/3.10.2/CMakeDetermineCompilerABI_CXX.bin -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/3.10.2/CMakeSystem.cmake: -------------------------------------------------------------------------------- 1 | set(CMAKE_HOST_SYSTEM "Linux-5.4.0-58-generic") 2 | set(CMAKE_HOST_SYSTEM_NAME "Linux") 3 | set(CMAKE_HOST_SYSTEM_VERSION "5.4.0-58-generic") 4 | set(CMAKE_HOST_SYSTEM_PROCESSOR "x86_64") 5 | 6 | 7 | 8 | set(CMAKE_SYSTEM "Linux-5.4.0-58-generic") 9 | set(CMAKE_SYSTEM_NAME "Linux") 10 | set(CMAKE_SYSTEM_VERSION "5.4.0-58-generic") 11 | set(CMAKE_SYSTEM_PROCESSOR "x86_64") 12 | 13 | set(CMAKE_CROSSCOMPILING "FALSE") 14 | 15 | set(CMAKE_SYSTEM_LOADED 1) 16 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/3.10.2/CompilerIdC/a.out: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/DBoW2/build/CMakeFiles/3.10.2/CompilerIdC/a.out -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/3.10.2/CompilerIdCXX/a.out: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/DBoW2/build/CMakeFiles/3.10.2/CompilerIdCXX/a.out -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/3.18.4/CMakeCCompiler.cmake: -------------------------------------------------------------------------------- 1 | set(CMAKE_C_COMPILER "/usr/bin/cc") 2 | set(CMAKE_C_COMPILER_ARG1 "") 3 | set(CMAKE_C_COMPILER_ID "GNU") 4 | set(CMAKE_C_COMPILER_VERSION "7.5.0") 5 | set(CMAKE_C_COMPILER_VERSION_INTERNAL "") 6 | set(CMAKE_C_COMPILER_WRAPPER "") 7 | set(CMAKE_C_STANDARD_COMPUTED_DEFAULT "11") 8 | set(CMAKE_C_COMPILE_FEATURES "c_std_90;c_function_prototypes;c_std_99;c_restrict;c_variadic_macros;c_std_11;c_static_assert") 9 | set(CMAKE_C90_COMPILE_FEATURES "c_std_90;c_function_prototypes") 10 | set(CMAKE_C99_COMPILE_FEATURES "c_std_99;c_restrict;c_variadic_macros") 11 | set(CMAKE_C11_COMPILE_FEATURES "c_std_11;c_static_assert") 12 | 13 | set(CMAKE_C_PLATFORM_ID "Linux") 14 | set(CMAKE_C_SIMULATE_ID "") 15 | set(CMAKE_C_COMPILER_FRONTEND_VARIANT "") 16 | set(CMAKE_C_SIMULATE_VERSION "") 17 | 18 | 19 | 20 | 21 | set(CMAKE_AR "/usr/bin/ar") 22 | set(CMAKE_C_COMPILER_AR "/usr/bin/gcc-ar-7") 23 | set(CMAKE_RANLIB "/usr/bin/ranlib") 24 | set(CMAKE_C_COMPILER_RANLIB "/usr/bin/gcc-ranlib-7") 25 | set(CMAKE_LINKER "/usr/bin/ld") 26 | set(CMAKE_MT "") 27 | set(CMAKE_COMPILER_IS_GNUCC 1) 28 | set(CMAKE_C_COMPILER_LOADED 1) 29 | set(CMAKE_C_COMPILER_WORKS TRUE) 30 | set(CMAKE_C_ABI_COMPILED TRUE) 31 | set(CMAKE_COMPILER_IS_MINGW ) 32 | set(CMAKE_COMPILER_IS_CYGWIN ) 33 | if(CMAKE_COMPILER_IS_CYGWIN) 34 | set(CYGWIN 1) 35 | set(UNIX 1) 36 | endif() 37 | 38 | set(CMAKE_C_COMPILER_ENV_VAR "CC") 39 | 40 | if(CMAKE_COMPILER_IS_MINGW) 41 | set(MINGW 1) 42 | endif() 43 | set(CMAKE_C_COMPILER_ID_RUN 1) 44 | set(CMAKE_C_SOURCE_FILE_EXTENSIONS c;m) 45 | set(CMAKE_C_IGNORE_EXTENSIONS h;H;o;O;obj;OBJ;def;DEF;rc;RC) 46 | set(CMAKE_C_LINKER_PREFERENCE 10) 47 | 48 | # Save compiler ABI information. 49 | set(CMAKE_C_SIZEOF_DATA_PTR "8") 50 | set(CMAKE_C_COMPILER_ABI "ELF") 51 | set(CMAKE_C_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") 52 | 53 | if(CMAKE_C_SIZEOF_DATA_PTR) 54 | set(CMAKE_SIZEOF_VOID_P "${CMAKE_C_SIZEOF_DATA_PTR}") 55 | endif() 56 | 57 | if(CMAKE_C_COMPILER_ABI) 58 | set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_C_COMPILER_ABI}") 59 | endif() 60 | 61 | if(CMAKE_C_LIBRARY_ARCHITECTURE) 62 | set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") 63 | endif() 64 | 65 | set(CMAKE_C_CL_SHOWINCLUDES_PREFIX "") 66 | if(CMAKE_C_CL_SHOWINCLUDES_PREFIX) 67 | set(CMAKE_CL_SHOWINCLUDES_PREFIX "${CMAKE_C_CL_SHOWINCLUDES_PREFIX}") 68 | endif() 69 | 70 | 71 | 72 | 73 | 74 | set(CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/7/include;/usr/local/include;/usr/lib/gcc/x86_64-linux-gnu/7/include-fixed;/usr/include/x86_64-linux-gnu;/usr/include") 75 | set(CMAKE_C_IMPLICIT_LINK_LIBRARIES "gcc;gcc_s;c;gcc;gcc_s") 76 | set(CMAKE_C_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/7;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") 77 | set(CMAKE_C_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") 78 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/3.18.4/CMakeDetermineCompilerABI_C.bin: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/DBoW2/build/CMakeFiles/3.18.4/CMakeDetermineCompilerABI_C.bin -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/3.18.4/CMakeDetermineCompilerABI_CXX.bin: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/DBoW2/build/CMakeFiles/3.18.4/CMakeDetermineCompilerABI_CXX.bin -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/3.18.4/CMakeSystem.cmake: -------------------------------------------------------------------------------- 1 | set(CMAKE_HOST_SYSTEM "Linux-5.4.0-73-generic") 2 | set(CMAKE_HOST_SYSTEM_NAME "Linux") 3 | set(CMAKE_HOST_SYSTEM_VERSION "5.4.0-73-generic") 4 | set(CMAKE_HOST_SYSTEM_PROCESSOR "x86_64") 5 | 6 | 7 | 8 | set(CMAKE_SYSTEM "Linux-5.4.0-73-generic") 9 | set(CMAKE_SYSTEM_NAME "Linux") 10 | set(CMAKE_SYSTEM_VERSION "5.4.0-73-generic") 11 | set(CMAKE_SYSTEM_PROCESSOR "x86_64") 12 | 13 | set(CMAKE_CROSSCOMPILING "FALSE") 14 | 15 | set(CMAKE_SYSTEM_LOADED 1) 16 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/3.18.4/CompilerIdC/a.out: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/DBoW2/build/CMakeFiles/3.18.4/CompilerIdC/a.out -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/3.18.4/CompilerIdCXX/a.out: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/DBoW2/build/CMakeFiles/3.18.4/CompilerIdCXX/a.out -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/CMakeDirectoryInformation.cmake: -------------------------------------------------------------------------------- 1 | # CMAKE generated file: DO NOT EDIT! 2 | # Generated by "Unix Makefiles" Generator, CMake Version 3.18 3 | 4 | # Relative path conversion top directories. 5 | set(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2") 6 | set(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/build") 7 | 8 | # Force unix paths in dependencies. 9 | set(CMAKE_FORCE_UNIX_PATHS 1) 10 | 11 | 12 | # The C and CXX include file regular expressions for this directory. 13 | set(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") 14 | set(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") 15 | set(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) 16 | set(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) 17 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DBoW2/BowVector.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DBoW2/BowVector.cpp.o -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DBoW2/FORB.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DBoW2/FORB.cpp.o -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DBoW2/FeatureVector.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DBoW2/FeatureVector.cpp.o -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DBoW2/ScoringObject.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DBoW2/ScoringObject.cpp.o -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DUtils/Random.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DUtils/Random.cpp.o -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DUtils/Timestamp.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DUtils/Timestamp.cpp.o -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DependInfo.cmake: -------------------------------------------------------------------------------- 1 | # The set of languages for which implicit dependencies are needed: 2 | set(CMAKE_DEPENDS_LANGUAGES 3 | "CXX" 4 | ) 5 | # The set of files for implicit dependencies of each language: 6 | set(CMAKE_DEPENDS_CHECK_CXX 7 | "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DBoW2/BowVector.cpp" "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DBoW2/BowVector.cpp.o" 8 | "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DBoW2/FORB.cpp" "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DBoW2/FORB.cpp.o" 9 | "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DBoW2/FeatureVector.cpp" "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DBoW2/FeatureVector.cpp.o" 10 | "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DBoW2/ScoringObject.cpp" "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DBoW2/ScoringObject.cpp.o" 11 | "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DUtils/Random.cpp" "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DUtils/Random.cpp.o" 12 | "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DUtils/Timestamp.cpp" "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/DUtils/Timestamp.cpp.o" 13 | ) 14 | set(CMAKE_CXX_COMPILER_ID "GNU") 15 | 16 | # Preprocessor definitions for this target. 17 | set(CMAKE_TARGET_DEFINITIONS_CXX 18 | "DBoW2_EXPORTS" 19 | ) 20 | 21 | # The include file search paths: 22 | set(CMAKE_CXX_TARGET_INCLUDE_PATH 23 | "/usr/local/include/opencv" 24 | ) 25 | 26 | # Targets to which this target links. 27 | set(CMAKE_TARGET_LINKED_INFO_FILES 28 | ) 29 | 30 | # Fortran module output directory. 31 | set(CMAKE_Fortran_TARGET_MODULE_DIR "") 32 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/cmake_clean.cmake: -------------------------------------------------------------------------------- 1 | file(REMOVE_RECURSE 2 | "../lib/libDBoW2.pdb" 3 | "../lib/libDBoW2.so" 4 | "CMakeFiles/DBoW2.dir/DBoW2/BowVector.cpp.o" 5 | "CMakeFiles/DBoW2.dir/DBoW2/FORB.cpp.o" 6 | "CMakeFiles/DBoW2.dir/DBoW2/FeatureVector.cpp.o" 7 | "CMakeFiles/DBoW2.dir/DBoW2/ScoringObject.cpp.o" 8 | "CMakeFiles/DBoW2.dir/DUtils/Random.cpp.o" 9 | "CMakeFiles/DBoW2.dir/DUtils/Timestamp.cpp.o" 10 | ) 11 | 12 | # Per-language clean rules from dependency scanning. 13 | foreach(lang CXX) 14 | include(CMakeFiles/DBoW2.dir/cmake_clean_${lang}.cmake OPTIONAL) 15 | endforeach() 16 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/depend.internal: -------------------------------------------------------------------------------- 1 | # CMAKE generated file: DO NOT EDIT! 2 | # Generated by "Unix Makefiles" Generator, CMake Version 3.18 3 | 4 | CMakeFiles/DBoW2.dir/DBoW2/BowVector.cpp.o 5 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DBoW2/BowVector.cpp 6 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DBoW2/BowVector.h 7 | CMakeFiles/DBoW2.dir/DBoW2/FORB.cpp.o 8 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DBoW2/FClass.h 9 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DBoW2/FORB.cpp 10 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DBoW2/FORB.h 11 | CMakeFiles/DBoW2.dir/DBoW2/FeatureVector.cpp.o 12 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DBoW2/BowVector.h 13 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DBoW2/FeatureVector.cpp 14 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DBoW2/FeatureVector.h 15 | CMakeFiles/DBoW2.dir/DBoW2/ScoringObject.cpp.o 16 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DBoW2/BowVector.h 17 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DBoW2/FeatureVector.h 18 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DBoW2/ScoringObject.cpp 19 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DBoW2/ScoringObject.h 20 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h 21 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DUtils/Random.h 22 | CMakeFiles/DBoW2.dir/DUtils/Random.cpp.o 23 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DUtils/Random.cpp 24 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DUtils/Random.h 25 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DUtils/Timestamp.h 26 | CMakeFiles/DBoW2.dir/DUtils/Timestamp.cpp.o 27 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DUtils/Timestamp.cpp 28 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/DUtils/Timestamp.h 29 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/depend.make: -------------------------------------------------------------------------------- 1 | # CMAKE generated file: DO NOT EDIT! 2 | # Generated by "Unix Makefiles" Generator, CMake Version 3.18 3 | 4 | CMakeFiles/DBoW2.dir/DBoW2/BowVector.cpp.o: ../DBoW2/BowVector.cpp 5 | CMakeFiles/DBoW2.dir/DBoW2/BowVector.cpp.o: ../DBoW2/BowVector.h 6 | 7 | CMakeFiles/DBoW2.dir/DBoW2/FORB.cpp.o: ../DBoW2/FClass.h 8 | CMakeFiles/DBoW2.dir/DBoW2/FORB.cpp.o: ../DBoW2/FORB.cpp 9 | CMakeFiles/DBoW2.dir/DBoW2/FORB.cpp.o: ../DBoW2/FORB.h 10 | 11 | CMakeFiles/DBoW2.dir/DBoW2/FeatureVector.cpp.o: ../DBoW2/BowVector.h 12 | CMakeFiles/DBoW2.dir/DBoW2/FeatureVector.cpp.o: ../DBoW2/FeatureVector.cpp 13 | CMakeFiles/DBoW2.dir/DBoW2/FeatureVector.cpp.o: ../DBoW2/FeatureVector.h 14 | 15 | CMakeFiles/DBoW2.dir/DBoW2/ScoringObject.cpp.o: ../DBoW2/BowVector.h 16 | CMakeFiles/DBoW2.dir/DBoW2/ScoringObject.cpp.o: ../DBoW2/FeatureVector.h 17 | CMakeFiles/DBoW2.dir/DBoW2/ScoringObject.cpp.o: ../DBoW2/ScoringObject.cpp 18 | CMakeFiles/DBoW2.dir/DBoW2/ScoringObject.cpp.o: ../DBoW2/ScoringObject.h 19 | CMakeFiles/DBoW2.dir/DBoW2/ScoringObject.cpp.o: ../DBoW2/TemplatedVocabulary.h 20 | CMakeFiles/DBoW2.dir/DBoW2/ScoringObject.cpp.o: ../DUtils/Random.h 21 | 22 | CMakeFiles/DBoW2.dir/DUtils/Random.cpp.o: ../DUtils/Random.cpp 23 | CMakeFiles/DBoW2.dir/DUtils/Random.cpp.o: ../DUtils/Random.h 24 | CMakeFiles/DBoW2.dir/DUtils/Random.cpp.o: ../DUtils/Timestamp.h 25 | 26 | CMakeFiles/DBoW2.dir/DUtils/Timestamp.cpp.o: ../DUtils/Timestamp.cpp 27 | CMakeFiles/DBoW2.dir/DUtils/Timestamp.cpp.o: ../DUtils/Timestamp.h 28 | 29 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/flags.make: -------------------------------------------------------------------------------- 1 | # CMAKE generated file: DO NOT EDIT! 2 | # Generated by "Unix Makefiles" Generator, CMake Version 3.18 3 | 4 | # compile CXX with /usr/bin/c++ 5 | CXX_DEFINES = -DDBoW2_EXPORTS 6 | 7 | CXX_INCLUDES = -isystem /usr/local/include/opencv 8 | 9 | CXX_FLAGS = -Wall -O3 -march=native -O3 -DNDEBUG -fPIC 10 | 11 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/link.txt: -------------------------------------------------------------------------------- 1 | /usr/bin/c++ -fPIC -Wall -O3 -march=native -O3 -DNDEBUG -shared -Wl,-soname,libDBoW2.so -o ../lib/libDBoW2.so CMakeFiles/DBoW2.dir/DBoW2/BowVector.cpp.o CMakeFiles/DBoW2.dir/DBoW2/FORB.cpp.o CMakeFiles/DBoW2.dir/DBoW2/FeatureVector.cpp.o CMakeFiles/DBoW2.dir/DBoW2/ScoringObject.cpp.o CMakeFiles/DBoW2.dir/DUtils/Random.cpp.o CMakeFiles/DBoW2.dir/DUtils/Timestamp.cpp.o -Wl,-rpath,/usr/local/lib /usr/local/lib/libopencv_stitching.so.3.4.1 /usr/local/lib/libopencv_superres.so.3.4.1 /usr/local/lib/libopencv_videostab.so.3.4.1 /usr/local/lib/libopencv_aruco.so.3.4.1 /usr/local/lib/libopencv_bgsegm.so.3.4.1 /usr/local/lib/libopencv_bioinspired.so.3.4.1 /usr/local/lib/libopencv_ccalib.so.3.4.1 /usr/local/lib/libopencv_dnn_objdetect.so.3.4.1 /usr/local/lib/libopencv_dpm.so.3.4.1 /usr/local/lib/libopencv_face.so.3.4.1 /usr/local/lib/libopencv_freetype.so.3.4.1 /usr/local/lib/libopencv_fuzzy.so.3.4.1 /usr/local/lib/libopencv_hfs.so.3.4.1 /usr/local/lib/libopencv_img_hash.so.3.4.1 /usr/local/lib/libopencv_line_descriptor.so.3.4.1 /usr/local/lib/libopencv_optflow.so.3.4.1 /usr/local/lib/libopencv_reg.so.3.4.1 /usr/local/lib/libopencv_rgbd.so.3.4.1 /usr/local/lib/libopencv_saliency.so.3.4.1 /usr/local/lib/libopencv_stereo.so.3.4.1 /usr/local/lib/libopencv_structured_light.so.3.4.1 /usr/local/lib/libopencv_surface_matching.so.3.4.1 /usr/local/lib/libopencv_tracking.so.3.4.1 /usr/local/lib/libopencv_xfeatures2d.so.3.4.1 /usr/local/lib/libopencv_ximgproc.so.3.4.1 /usr/local/lib/libopencv_xobjdetect.so.3.4.1 /usr/local/lib/libopencv_xphoto.so.3.4.1 /usr/local/lib/libopencv_shape.so.3.4.1 /usr/local/lib/libopencv_photo.so.3.4.1 /usr/local/lib/libopencv_datasets.so.3.4.1 /usr/local/lib/libopencv_plot.so.3.4.1 /usr/local/lib/libopencv_text.so.3.4.1 /usr/local/lib/libopencv_dnn.so.3.4.1 /usr/local/lib/libopencv_ml.so.3.4.1 /usr/local/lib/libopencv_video.so.3.4.1 /usr/local/lib/libopencv_calib3d.so.3.4.1 /usr/local/lib/libopencv_features2d.so.3.4.1 /usr/local/lib/libopencv_highgui.so.3.4.1 /usr/local/lib/libopencv_videoio.so.3.4.1 /usr/local/lib/libopencv_phase_unwrapping.so.3.4.1 /usr/local/lib/libopencv_flann.so.3.4.1 /usr/local/lib/libopencv_imgcodecs.so.3.4.1 /usr/local/lib/libopencv_objdetect.so.3.4.1 /usr/local/lib/libopencv_imgproc.so.3.4.1 /usr/local/lib/libopencv_core.so.3.4.1 2 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir/progress.make: -------------------------------------------------------------------------------- 1 | CMAKE_PROGRESS_1 = 1 2 | CMAKE_PROGRESS_2 = 2 3 | CMAKE_PROGRESS_3 = 3 4 | CMAKE_PROGRESS_4 = 4 5 | CMAKE_PROGRESS_5 = 5 6 | CMAKE_PROGRESS_6 = 6 7 | CMAKE_PROGRESS_7 = 7 8 | 9 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/TargetDirectories.txt: -------------------------------------------------------------------------------- 1 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/build/CMakeFiles/rebuild_cache.dir 2 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/build/CMakeFiles/edit_cache.dir 3 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/build/CMakeFiles/DBoW2.dir 4 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/cmake.check_cache: -------------------------------------------------------------------------------- 1 | # This file is generated by cmake for dependency checking of the CMakeCache.txt file 2 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/feature_tests.bin: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/DBoW2/build/CMakeFiles/feature_tests.bin -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/feature_tests.c: -------------------------------------------------------------------------------- 1 | 2 | const char features[] = {"\n" 3 | "C_FEATURE:" 4 | #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 304 5 | "1" 6 | #else 7 | "0" 8 | #endif 9 | "c_function_prototypes\n" 10 | "C_FEATURE:" 11 | #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 304 && defined(__STDC_VERSION__) && __STDC_VERSION__ >= 199901L 12 | "1" 13 | #else 14 | "0" 15 | #endif 16 | "c_restrict\n" 17 | "C_FEATURE:" 18 | #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && defined(__STDC_VERSION__) && __STDC_VERSION__ >= 201000L 19 | "1" 20 | #else 21 | "0" 22 | #endif 23 | "c_static_assert\n" 24 | "C_FEATURE:" 25 | #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 304 && defined(__STDC_VERSION__) && __STDC_VERSION__ >= 199901L 26 | "1" 27 | #else 28 | "0" 29 | #endif 30 | "c_variadic_macros\n" 31 | 32 | }; 33 | 34 | int main(int argc, char** argv) { (void)argv; return features[argc]; } 35 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/CMakeFiles/progress.marks: -------------------------------------------------------------------------------- 1 | 7 2 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/build/cmake_install.cmake: -------------------------------------------------------------------------------- 1 | # Install script for directory: /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2 2 | 3 | # Set the install prefix 4 | if(NOT DEFINED CMAKE_INSTALL_PREFIX) 5 | set(CMAKE_INSTALL_PREFIX "/usr/local") 6 | endif() 7 | string(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") 8 | 9 | # Set the install configuration name. 10 | if(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) 11 | if(BUILD_TYPE) 12 | string(REGEX REPLACE "^[^A-Za-z0-9_]+" "" 13 | CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") 14 | else() 15 | set(CMAKE_INSTALL_CONFIG_NAME "Release") 16 | endif() 17 | message(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") 18 | endif() 19 | 20 | # Set the component getting installed. 21 | if(NOT CMAKE_INSTALL_COMPONENT) 22 | if(COMPONENT) 23 | message(STATUS "Install component: \"${COMPONENT}\"") 24 | set(CMAKE_INSTALL_COMPONENT "${COMPONENT}") 25 | else() 26 | set(CMAKE_INSTALL_COMPONENT) 27 | endif() 28 | endif() 29 | 30 | # Install shared libraries without execute permission? 31 | if(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) 32 | set(CMAKE_INSTALL_SO_NO_EXE "1") 33 | endif() 34 | 35 | # Is this installation the result of a crosscompile? 36 | if(NOT DEFINED CMAKE_CROSSCOMPILING) 37 | set(CMAKE_CROSSCOMPILING "FALSE") 38 | endif() 39 | 40 | # Set default install directory permissions. 41 | if(NOT DEFINED CMAKE_OBJDUMP) 42 | set(CMAKE_OBJDUMP "/usr/bin/objdump") 43 | endif() 44 | 45 | if(CMAKE_INSTALL_COMPONENT) 46 | set(CMAKE_INSTALL_MANIFEST "install_manifest_${CMAKE_INSTALL_COMPONENT}.txt") 47 | else() 48 | set(CMAKE_INSTALL_MANIFEST "install_manifest.txt") 49 | endif() 50 | 51 | string(REPLACE ";" "\n" CMAKE_INSTALL_MANIFEST_CONTENT 52 | "${CMAKE_INSTALL_MANIFEST_FILES}") 53 | file(WRITE "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/DBoW2/build/${CMAKE_INSTALL_MANIFEST}" 54 | "${CMAKE_INSTALL_MANIFEST_CONTENT}") 55 | -------------------------------------------------------------------------------- /Thirdparty/DBoW2/lib/libDBoW2.so: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/DBoW2/lib/libDBoW2.so -------------------------------------------------------------------------------- /Thirdparty/g2o/README.txt: -------------------------------------------------------------------------------- 1 | You should have received this g2o version along with ORB-SLAM2 (https://github.com/raulmur/Planar_SLAM). 2 | See the original g2o library at: https://github.com/RainerKuemmerle/g2o 3 | All files included in this g2o version are BSD, see license-bsd.txt 4 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/3.10.2/CMakeCCompiler.cmake: -------------------------------------------------------------------------------- 1 | set(CMAKE_C_COMPILER "/usr/bin/cc") 2 | set(CMAKE_C_COMPILER_ARG1 "") 3 | set(CMAKE_C_COMPILER_ID "GNU") 4 | set(CMAKE_C_COMPILER_VERSION "7.5.0") 5 | set(CMAKE_C_COMPILER_VERSION_INTERNAL "") 6 | set(CMAKE_C_COMPILER_WRAPPER "") 7 | set(CMAKE_C_STANDARD_COMPUTED_DEFAULT "11") 8 | set(CMAKE_C_COMPILE_FEATURES "c_std_90;c_function_prototypes;c_std_99;c_restrict;c_variadic_macros;c_std_11;c_static_assert") 9 | set(CMAKE_C90_COMPILE_FEATURES "c_std_90;c_function_prototypes") 10 | set(CMAKE_C99_COMPILE_FEATURES "c_std_99;c_restrict;c_variadic_macros") 11 | set(CMAKE_C11_COMPILE_FEATURES "c_std_11;c_static_assert") 12 | 13 | set(CMAKE_C_PLATFORM_ID "Linux") 14 | set(CMAKE_C_SIMULATE_ID "") 15 | set(CMAKE_C_SIMULATE_VERSION "") 16 | 17 | 18 | 19 | set(CMAKE_AR "/usr/bin/ar") 20 | set(CMAKE_C_COMPILER_AR "/usr/bin/gcc-ar-7") 21 | set(CMAKE_RANLIB "/usr/bin/ranlib") 22 | set(CMAKE_C_COMPILER_RANLIB "/usr/bin/gcc-ranlib-7") 23 | set(CMAKE_LINKER "/usr/bin/ld") 24 | set(CMAKE_COMPILER_IS_GNUCC 1) 25 | set(CMAKE_C_COMPILER_LOADED 1) 26 | set(CMAKE_C_COMPILER_WORKS TRUE) 27 | set(CMAKE_C_ABI_COMPILED TRUE) 28 | set(CMAKE_COMPILER_IS_MINGW ) 29 | set(CMAKE_COMPILER_IS_CYGWIN ) 30 | if(CMAKE_COMPILER_IS_CYGWIN) 31 | set(CYGWIN 1) 32 | set(UNIX 1) 33 | endif() 34 | 35 | set(CMAKE_C_COMPILER_ENV_VAR "CC") 36 | 37 | if(CMAKE_COMPILER_IS_MINGW) 38 | set(MINGW 1) 39 | endif() 40 | set(CMAKE_C_COMPILER_ID_RUN 1) 41 | set(CMAKE_C_SOURCE_FILE_EXTENSIONS c;m) 42 | set(CMAKE_C_IGNORE_EXTENSIONS h;H;o;O;obj;OBJ;def;DEF;rc;RC) 43 | set(CMAKE_C_LINKER_PREFERENCE 10) 44 | 45 | # Save compiler ABI information. 46 | set(CMAKE_C_SIZEOF_DATA_PTR "8") 47 | set(CMAKE_C_COMPILER_ABI "ELF") 48 | set(CMAKE_C_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") 49 | 50 | if(CMAKE_C_SIZEOF_DATA_PTR) 51 | set(CMAKE_SIZEOF_VOID_P "${CMAKE_C_SIZEOF_DATA_PTR}") 52 | endif() 53 | 54 | if(CMAKE_C_COMPILER_ABI) 55 | set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_C_COMPILER_ABI}") 56 | endif() 57 | 58 | if(CMAKE_C_LIBRARY_ARCHITECTURE) 59 | set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") 60 | endif() 61 | 62 | set(CMAKE_C_CL_SHOWINCLUDES_PREFIX "") 63 | if(CMAKE_C_CL_SHOWINCLUDES_PREFIX) 64 | set(CMAKE_CL_SHOWINCLUDES_PREFIX "${CMAKE_C_CL_SHOWINCLUDES_PREFIX}") 65 | endif() 66 | 67 | 68 | 69 | 70 | 71 | set(CMAKE_C_IMPLICIT_LINK_LIBRARIES "gcc;gcc_s;c;gcc;gcc_s") 72 | set(CMAKE_C_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/7;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") 73 | set(CMAKE_C_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") 74 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/3.10.2/CMakeDetermineCompilerABI_C.bin: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/3.10.2/CMakeDetermineCompilerABI_C.bin -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/3.10.2/CMakeDetermineCompilerABI_CXX.bin: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/3.10.2/CMakeDetermineCompilerABI_CXX.bin -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/3.10.2/CMakeSystem.cmake: -------------------------------------------------------------------------------- 1 | set(CMAKE_HOST_SYSTEM "Linux-5.4.0-58-generic") 2 | set(CMAKE_HOST_SYSTEM_NAME "Linux") 3 | set(CMAKE_HOST_SYSTEM_VERSION "5.4.0-58-generic") 4 | set(CMAKE_HOST_SYSTEM_PROCESSOR "x86_64") 5 | 6 | 7 | 8 | set(CMAKE_SYSTEM "Linux-5.4.0-58-generic") 9 | set(CMAKE_SYSTEM_NAME "Linux") 10 | set(CMAKE_SYSTEM_VERSION "5.4.0-58-generic") 11 | set(CMAKE_SYSTEM_PROCESSOR "x86_64") 12 | 13 | set(CMAKE_CROSSCOMPILING "FALSE") 14 | 15 | set(CMAKE_SYSTEM_LOADED 1) 16 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/3.10.2/CompilerIdC/a.out: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/3.10.2/CompilerIdC/a.out -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/3.10.2/CompilerIdCXX/a.out: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/3.10.2/CompilerIdCXX/a.out -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/3.18.4/CMakeCCompiler.cmake: -------------------------------------------------------------------------------- 1 | set(CMAKE_C_COMPILER "/usr/bin/cc") 2 | set(CMAKE_C_COMPILER_ARG1 "") 3 | set(CMAKE_C_COMPILER_ID "GNU") 4 | set(CMAKE_C_COMPILER_VERSION "7.5.0") 5 | set(CMAKE_C_COMPILER_VERSION_INTERNAL "") 6 | set(CMAKE_C_COMPILER_WRAPPER "") 7 | set(CMAKE_C_STANDARD_COMPUTED_DEFAULT "11") 8 | set(CMAKE_C_COMPILE_FEATURES "c_std_90;c_function_prototypes;c_std_99;c_restrict;c_variadic_macros;c_std_11;c_static_assert") 9 | set(CMAKE_C90_COMPILE_FEATURES "c_std_90;c_function_prototypes") 10 | set(CMAKE_C99_COMPILE_FEATURES "c_std_99;c_restrict;c_variadic_macros") 11 | set(CMAKE_C11_COMPILE_FEATURES "c_std_11;c_static_assert") 12 | 13 | set(CMAKE_C_PLATFORM_ID "Linux") 14 | set(CMAKE_C_SIMULATE_ID "") 15 | set(CMAKE_C_COMPILER_FRONTEND_VARIANT "") 16 | set(CMAKE_C_SIMULATE_VERSION "") 17 | 18 | 19 | 20 | 21 | set(CMAKE_AR "/usr/bin/ar") 22 | set(CMAKE_C_COMPILER_AR "/usr/bin/gcc-ar-7") 23 | set(CMAKE_RANLIB "/usr/bin/ranlib") 24 | set(CMAKE_C_COMPILER_RANLIB "/usr/bin/gcc-ranlib-7") 25 | set(CMAKE_LINKER "/usr/bin/ld") 26 | set(CMAKE_MT "") 27 | set(CMAKE_COMPILER_IS_GNUCC 1) 28 | set(CMAKE_C_COMPILER_LOADED 1) 29 | set(CMAKE_C_COMPILER_WORKS TRUE) 30 | set(CMAKE_C_ABI_COMPILED TRUE) 31 | set(CMAKE_COMPILER_IS_MINGW ) 32 | set(CMAKE_COMPILER_IS_CYGWIN ) 33 | if(CMAKE_COMPILER_IS_CYGWIN) 34 | set(CYGWIN 1) 35 | set(UNIX 1) 36 | endif() 37 | 38 | set(CMAKE_C_COMPILER_ENV_VAR "CC") 39 | 40 | if(CMAKE_COMPILER_IS_MINGW) 41 | set(MINGW 1) 42 | endif() 43 | set(CMAKE_C_COMPILER_ID_RUN 1) 44 | set(CMAKE_C_SOURCE_FILE_EXTENSIONS c;m) 45 | set(CMAKE_C_IGNORE_EXTENSIONS h;H;o;O;obj;OBJ;def;DEF;rc;RC) 46 | set(CMAKE_C_LINKER_PREFERENCE 10) 47 | 48 | # Save compiler ABI information. 49 | set(CMAKE_C_SIZEOF_DATA_PTR "8") 50 | set(CMAKE_C_COMPILER_ABI "ELF") 51 | set(CMAKE_C_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") 52 | 53 | if(CMAKE_C_SIZEOF_DATA_PTR) 54 | set(CMAKE_SIZEOF_VOID_P "${CMAKE_C_SIZEOF_DATA_PTR}") 55 | endif() 56 | 57 | if(CMAKE_C_COMPILER_ABI) 58 | set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_C_COMPILER_ABI}") 59 | endif() 60 | 61 | if(CMAKE_C_LIBRARY_ARCHITECTURE) 62 | set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") 63 | endif() 64 | 65 | set(CMAKE_C_CL_SHOWINCLUDES_PREFIX "") 66 | if(CMAKE_C_CL_SHOWINCLUDES_PREFIX) 67 | set(CMAKE_CL_SHOWINCLUDES_PREFIX "${CMAKE_C_CL_SHOWINCLUDES_PREFIX}") 68 | endif() 69 | 70 | 71 | 72 | 73 | 74 | set(CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/7/include;/usr/local/include;/usr/lib/gcc/x86_64-linux-gnu/7/include-fixed;/usr/include/x86_64-linux-gnu;/usr/include") 75 | set(CMAKE_C_IMPLICIT_LINK_LIBRARIES "gcc;gcc_s;c;gcc;gcc_s") 76 | set(CMAKE_C_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/7;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") 77 | set(CMAKE_C_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") 78 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/3.18.4/CMakeDetermineCompilerABI_C.bin: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/3.18.4/CMakeDetermineCompilerABI_C.bin -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/3.18.4/CMakeDetermineCompilerABI_CXX.bin: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/3.18.4/CMakeDetermineCompilerABI_CXX.bin -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/3.18.4/CMakeSystem.cmake: -------------------------------------------------------------------------------- 1 | set(CMAKE_HOST_SYSTEM "Linux-5.4.0-73-generic") 2 | set(CMAKE_HOST_SYSTEM_NAME "Linux") 3 | set(CMAKE_HOST_SYSTEM_VERSION "5.4.0-73-generic") 4 | set(CMAKE_HOST_SYSTEM_PROCESSOR "x86_64") 5 | 6 | 7 | 8 | set(CMAKE_SYSTEM "Linux-5.4.0-73-generic") 9 | set(CMAKE_SYSTEM_NAME "Linux") 10 | set(CMAKE_SYSTEM_VERSION "5.4.0-73-generic") 11 | set(CMAKE_SYSTEM_PROCESSOR "x86_64") 12 | 13 | set(CMAKE_CROSSCOMPILING "FALSE") 14 | 15 | set(CMAKE_SYSTEM_LOADED 1) 16 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/3.18.4/CompilerIdC/a.out: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/3.18.4/CompilerIdC/a.out -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/3.18.4/CompilerIdCXX/a.out: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/3.18.4/CompilerIdCXX/a.out -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/CMakeDirectoryInformation.cmake: -------------------------------------------------------------------------------- 1 | # CMAKE generated file: DO NOT EDIT! 2 | # Generated by "Unix Makefiles" Generator, CMake Version 3.18 3 | 4 | # Relative path conversion top directories. 5 | set(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/g2o") 6 | set(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/g2o/build") 7 | 8 | # Force unix paths in dependencies. 9 | set(CMAKE_FORCE_UNIX_PATHS 1) 10 | 11 | 12 | # The C and CXX include file regular expressions for this directory. 13 | set(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") 14 | set(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") 15 | set(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) 16 | set(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) 17 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/FindOpenMP/OpenMPCheckVersion.c: -------------------------------------------------------------------------------- 1 | 2 | #include 3 | #include 4 | const char ompver_str[] = { 'I', 'N', 'F', 'O', ':', 'O', 'p', 'e', 'n', 'M', 5 | 'P', '-', 'd', 'a', 't', 'e', '[', 6 | ('0' + ((_OPENMP/100000)%10)), 7 | ('0' + ((_OPENMP/10000)%10)), 8 | ('0' + ((_OPENMP/1000)%10)), 9 | ('0' + ((_OPENMP/100)%10)), 10 | ('0' + ((_OPENMP/10)%10)), 11 | ('0' + ((_OPENMP/1)%10)), 12 | ']', '\0' }; 13 | int main(void) 14 | { 15 | puts(ompver_str); 16 | return 0; 17 | } 18 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/FindOpenMP/OpenMPCheckVersion.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include 3 | #include 4 | const char ompver_str[] = { 'I', 'N', 'F', 'O', ':', 'O', 'p', 'e', 'n', 'M', 5 | 'P', '-', 'd', 'a', 't', 'e', '[', 6 | ('0' + ((_OPENMP/100000)%10)), 7 | ('0' + ((_OPENMP/10000)%10)), 8 | ('0' + ((_OPENMP/1000)%10)), 9 | ('0' + ((_OPENMP/100)%10)), 10 | ('0' + ((_OPENMP/10)%10)), 11 | ('0' + ((_OPENMP/1)%10)), 12 | ']', '\0' }; 13 | int main(void) 14 | { 15 | puts(ompver_str); 16 | return 0; 17 | } 18 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/FindOpenMP/OpenMPTryFlag.c: -------------------------------------------------------------------------------- 1 | 2 | #include 3 | int main() { 4 | #ifdef _OPENMP 5 | return 0; 6 | #else 7 | breaks_on_purpose 8 | #endif 9 | } 10 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/FindOpenMP/OpenMPTryFlag.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include 3 | int main() { 4 | #ifdef _OPENMP 5 | return 0; 6 | #else 7 | breaks_on_purpose 8 | #endif 9 | } 10 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/FindOpenMP/ompver_C.bin: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/FindOpenMP/ompver_C.bin -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/FindOpenMP/ompver_CXX.bin: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/FindOpenMP/ompver_CXX.bin -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/TargetDirectories.txt: -------------------------------------------------------------------------------- 1 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/g2o/build/CMakeFiles/rebuild_cache.dir 2 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/g2o/build/CMakeFiles/edit_cache.dir 3 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/g2o/build/CMakeFiles/g2o.dir 4 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/cmake.check_cache: -------------------------------------------------------------------------------- 1 | # This file is generated by cmake for dependency checking of the CMakeCache.txt file 2 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/feature_tests.bin: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/feature_tests.bin -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/feature_tests.c: -------------------------------------------------------------------------------- 1 | 2 | const char features[] = {"\n" 3 | "C_FEATURE:" 4 | #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 304 5 | "1" 6 | #else 7 | "0" 8 | #endif 9 | "c_function_prototypes\n" 10 | "C_FEATURE:" 11 | #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 304 && defined(__STDC_VERSION__) && __STDC_VERSION__ >= 199901L 12 | "1" 13 | #else 14 | "0" 15 | #endif 16 | "c_restrict\n" 17 | "C_FEATURE:" 18 | #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && defined(__STDC_VERSION__) && __STDC_VERSION__ >= 201000L 19 | "1" 20 | #else 21 | "0" 22 | #endif 23 | "c_static_assert\n" 24 | "C_FEATURE:" 25 | #if (__GNUC__ * 100 + __GNUC_MINOR__) >= 304 && defined(__STDC_VERSION__) && __STDC_VERSION__ >= 199901L 26 | "1" 27 | #else 28 | "0" 29 | #endif 30 | "c_variadic_macros\n" 31 | 32 | }; 33 | 34 | int main(int argc, char** argv) { (void)argv; return features[argc]; } 35 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/C.includecache: -------------------------------------------------------------------------------- 1 | #IncludeRegexLine: ^[ ]*[#%][ ]*(include|import)[ ]*[<"]([^">]+)([">]) 2 | 3 | #IncludeRegexScan: ^.*$ 4 | 5 | #IncludeRegexComplain: ^$ 6 | 7 | #IncludeRegexTransform: 8 | 9 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/g2o/g2o/stuff/os_specific.c 10 | os_specific.h 11 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/g2o/g2o/stuff/os_specific.h 12 | 13 | /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/g2o/g2o/stuff/os_specific.h 14 | stdio.h 15 | - 16 | stdlib.h 17 | - 18 | stdarg.h 19 | - 20 | sys/time.h 21 | - 22 | sys/time.h 23 | - 24 | 25 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/cmake_clean.cmake: -------------------------------------------------------------------------------- 1 | file(REMOVE_RECURSE 2 | "../lib/libg2o.pdb" 3 | "../lib/libg2o.so" 4 | "CMakeFiles/g2o.dir/g2o/core/batch_stats.cpp.o" 5 | "CMakeFiles/g2o.dir/g2o/core/cache.cpp.o" 6 | "CMakeFiles/g2o.dir/g2o/core/estimate_propagator.cpp.o" 7 | "CMakeFiles/g2o.dir/g2o/core/factory.cpp.o" 8 | "CMakeFiles/g2o.dir/g2o/core/hyper_dijkstra.cpp.o" 9 | "CMakeFiles/g2o.dir/g2o/core/hyper_graph.cpp.o" 10 | "CMakeFiles/g2o.dir/g2o/core/hyper_graph_action.cpp.o" 11 | "CMakeFiles/g2o.dir/g2o/core/jacobian_workspace.cpp.o" 12 | "CMakeFiles/g2o.dir/g2o/core/marginal_covariance_cholesky.cpp.o" 13 | "CMakeFiles/g2o.dir/g2o/core/matrix_structure.cpp.o" 14 | "CMakeFiles/g2o.dir/g2o/core/optimizable_graph.cpp.o" 15 | "CMakeFiles/g2o.dir/g2o/core/optimization_algorithm.cpp.o" 16 | "CMakeFiles/g2o.dir/g2o/core/optimization_algorithm_factory.cpp.o" 17 | "CMakeFiles/g2o.dir/g2o/core/optimization_algorithm_levenberg.cpp.o" 18 | "CMakeFiles/g2o.dir/g2o/core/optimization_algorithm_with_hessian.cpp.o" 19 | "CMakeFiles/g2o.dir/g2o/core/parameter.cpp.o" 20 | "CMakeFiles/g2o.dir/g2o/core/parameter_container.cpp.o" 21 | "CMakeFiles/g2o.dir/g2o/core/robust_kernel.cpp.o" 22 | "CMakeFiles/g2o.dir/g2o/core/robust_kernel_factory.cpp.o" 23 | "CMakeFiles/g2o.dir/g2o/core/robust_kernel_impl.cpp.o" 24 | "CMakeFiles/g2o.dir/g2o/core/solver.cpp.o" 25 | "CMakeFiles/g2o.dir/g2o/core/sparse_optimizer.cpp.o" 26 | "CMakeFiles/g2o.dir/g2o/stuff/os_specific.c.o" 27 | "CMakeFiles/g2o.dir/g2o/stuff/property.cpp.o" 28 | "CMakeFiles/g2o.dir/g2o/stuff/string_tools.cpp.o" 29 | "CMakeFiles/g2o.dir/g2o/stuff/timeutil.cpp.o" 30 | "CMakeFiles/g2o.dir/g2o/types/types_sba.cpp.o" 31 | "CMakeFiles/g2o.dir/g2o/types/types_seven_dof_expmap.cpp.o" 32 | "CMakeFiles/g2o.dir/g2o/types/types_six_dof_expmap.cpp.o" 33 | ) 34 | 35 | # Per-language clean rules from dependency scanning. 36 | foreach(lang C CXX) 37 | include(CMakeFiles/g2o.dir/cmake_clean_${lang}.cmake OPTIONAL) 38 | endforeach() 39 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/flags.make: -------------------------------------------------------------------------------- 1 | # CMAKE generated file: DO NOT EDIT! 2 | # Generated by "Unix Makefiles" Generator, CMake Version 3.18 3 | 4 | # compile C with /usr/bin/cc 5 | # compile CXX with /usr/bin/c++ 6 | C_DEFINES = -DUNIX -Dg2o_EXPORTS 7 | 8 | C_INCLUDES = -I/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/g2o/core -I/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/g2o/types -I/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/g2o/stuff -I/usr/include/eigen3 9 | 10 | C_FLAGS = -Wall -W -O3 -DNDEBUG -O3 -march=native -fPIC 11 | 12 | CXX_DEFINES = -DUNIX -Dg2o_EXPORTS 13 | 14 | CXX_INCLUDES = -I/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/g2o/core -I/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/g2o/types -I/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/g2o/stuff -I/usr/include/eigen3 15 | 16 | CXX_FLAGS = -Wall -W -O3 -DNDEBUG -O3 -march=native -fPIC 17 | 18 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/batch_stats.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/batch_stats.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/cache.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/cache.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/estimate_propagator.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/estimate_propagator.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/factory.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/factory.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/hyper_dijkstra.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/hyper_dijkstra.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/hyper_graph.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/hyper_graph.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/hyper_graph_action.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/hyper_graph_action.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/jacobian_workspace.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/jacobian_workspace.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/marginal_covariance_cholesky.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/marginal_covariance_cholesky.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/matrix_structure.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/matrix_structure.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/optimizable_graph.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/optimizable_graph.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/optimization_algorithm.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/optimization_algorithm.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/optimization_algorithm_factory.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/optimization_algorithm_factory.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/optimization_algorithm_levenberg.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/optimization_algorithm_levenberg.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/optimization_algorithm_with_hessian.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/optimization_algorithm_with_hessian.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/parameter.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/parameter.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/parameter_container.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/parameter_container.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/robust_kernel.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/robust_kernel.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/robust_kernel_factory.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/robust_kernel_factory.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/robust_kernel_impl.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/robust_kernel_impl.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/solver.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/solver.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/sparse_optimizer.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/core/sparse_optimizer.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/stuff/os_specific.c.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/stuff/os_specific.c.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/stuff/property.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/stuff/property.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/stuff/string_tools.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/stuff/string_tools.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/stuff/timeutil.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/stuff/timeutil.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/types/types_sba.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/types/types_sba.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/types/types_seven_dof_expmap.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/types/types_seven_dof_expmap.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/types/types_six_dof_expmap.cpp.o: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/build/CMakeFiles/g2o.dir/g2o/types/types_six_dof_expmap.cpp.o -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/link.txt: -------------------------------------------------------------------------------- 1 | /usr/bin/c++ -fPIC -Wall -W -O3 -DNDEBUG -O3 -march=native -shared -Wl,-soname,libg2o.so -o ../lib/libg2o.so CMakeFiles/g2o.dir/g2o/types/types_sba.cpp.o CMakeFiles/g2o.dir/g2o/types/types_six_dof_expmap.cpp.o CMakeFiles/g2o.dir/g2o/types/types_seven_dof_expmap.cpp.o CMakeFiles/g2o.dir/g2o/core/hyper_graph_action.cpp.o CMakeFiles/g2o.dir/g2o/core/hyper_graph.cpp.o CMakeFiles/g2o.dir/g2o/core/marginal_covariance_cholesky.cpp.o CMakeFiles/g2o.dir/g2o/core/matrix_structure.cpp.o CMakeFiles/g2o.dir/g2o/core/batch_stats.cpp.o CMakeFiles/g2o.dir/g2o/core/parameter.cpp.o CMakeFiles/g2o.dir/g2o/core/cache.cpp.o CMakeFiles/g2o.dir/g2o/core/optimizable_graph.cpp.o CMakeFiles/g2o.dir/g2o/core/solver.cpp.o CMakeFiles/g2o.dir/g2o/core/optimization_algorithm_factory.cpp.o CMakeFiles/g2o.dir/g2o/core/estimate_propagator.cpp.o CMakeFiles/g2o.dir/g2o/core/factory.cpp.o CMakeFiles/g2o.dir/g2o/core/sparse_optimizer.cpp.o CMakeFiles/g2o.dir/g2o/core/hyper_dijkstra.cpp.o CMakeFiles/g2o.dir/g2o/core/parameter_container.cpp.o CMakeFiles/g2o.dir/g2o/core/optimization_algorithm.cpp.o CMakeFiles/g2o.dir/g2o/core/optimization_algorithm_with_hessian.cpp.o CMakeFiles/g2o.dir/g2o/core/optimization_algorithm_levenberg.cpp.o CMakeFiles/g2o.dir/g2o/core/jacobian_workspace.cpp.o CMakeFiles/g2o.dir/g2o/core/robust_kernel.cpp.o CMakeFiles/g2o.dir/g2o/core/robust_kernel_factory.cpp.o CMakeFiles/g2o.dir/g2o/core/robust_kernel_impl.cpp.o CMakeFiles/g2o.dir/g2o/stuff/timeutil.cpp.o CMakeFiles/g2o.dir/g2o/stuff/os_specific.c.o CMakeFiles/g2o.dir/g2o/stuff/string_tools.cpp.o CMakeFiles/g2o.dir/g2o/stuff/property.cpp.o 2 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/g2o.dir/progress.make: -------------------------------------------------------------------------------- 1 | CMAKE_PROGRESS_1 = 1 2 | CMAKE_PROGRESS_2 = 2 3 | CMAKE_PROGRESS_3 = 3 4 | CMAKE_PROGRESS_4 = 4 5 | CMAKE_PROGRESS_5 = 5 6 | CMAKE_PROGRESS_6 = 6 7 | CMAKE_PROGRESS_7 = 7 8 | CMAKE_PROGRESS_8 = 8 9 | CMAKE_PROGRESS_9 = 9 10 | CMAKE_PROGRESS_10 = 10 11 | CMAKE_PROGRESS_11 = 11 12 | CMAKE_PROGRESS_12 = 12 13 | CMAKE_PROGRESS_13 = 13 14 | CMAKE_PROGRESS_14 = 14 15 | CMAKE_PROGRESS_15 = 15 16 | CMAKE_PROGRESS_16 = 16 17 | CMAKE_PROGRESS_17 = 17 18 | CMAKE_PROGRESS_18 = 18 19 | CMAKE_PROGRESS_19 = 19 20 | CMAKE_PROGRESS_20 = 20 21 | CMAKE_PROGRESS_21 = 21 22 | CMAKE_PROGRESS_22 = 22 23 | CMAKE_PROGRESS_23 = 23 24 | CMAKE_PROGRESS_24 = 24 25 | CMAKE_PROGRESS_25 = 25 26 | CMAKE_PROGRESS_26 = 26 27 | CMAKE_PROGRESS_27 = 27 28 | CMAKE_PROGRESS_28 = 28 29 | CMAKE_PROGRESS_29 = 29 30 | CMAKE_PROGRESS_30 = 30 31 | 32 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/CMakeFiles/progress.marks: -------------------------------------------------------------------------------- 1 | 30 2 | -------------------------------------------------------------------------------- /Thirdparty/g2o/build/cmake_install.cmake: -------------------------------------------------------------------------------- 1 | # Install script for directory: /home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/g2o 2 | 3 | # Set the install prefix 4 | if(NOT DEFINED CMAKE_INSTALL_PREFIX) 5 | set(CMAKE_INSTALL_PREFIX "/usr/local") 6 | endif() 7 | string(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") 8 | 9 | # Set the install configuration name. 10 | if(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) 11 | if(BUILD_TYPE) 12 | string(REGEX REPLACE "^[^A-Za-z0-9_]+" "" 13 | CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") 14 | else() 15 | set(CMAKE_INSTALL_CONFIG_NAME "Release") 16 | endif() 17 | message(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") 18 | endif() 19 | 20 | # Set the component getting installed. 21 | if(NOT CMAKE_INSTALL_COMPONENT) 22 | if(COMPONENT) 23 | message(STATUS "Install component: \"${COMPONENT}\"") 24 | set(CMAKE_INSTALL_COMPONENT "${COMPONENT}") 25 | else() 26 | set(CMAKE_INSTALL_COMPONENT) 27 | endif() 28 | endif() 29 | 30 | # Install shared libraries without execute permission? 31 | if(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) 32 | set(CMAKE_INSTALL_SO_NO_EXE "1") 33 | endif() 34 | 35 | # Is this installation the result of a crosscompile? 36 | if(NOT DEFINED CMAKE_CROSSCOMPILING) 37 | set(CMAKE_CROSSCOMPILING "FALSE") 38 | endif() 39 | 40 | # Set default install directory permissions. 41 | if(NOT DEFINED CMAKE_OBJDUMP) 42 | set(CMAKE_OBJDUMP "/usr/bin/objdump") 43 | endif() 44 | 45 | if(CMAKE_INSTALL_COMPONENT) 46 | set(CMAKE_INSTALL_MANIFEST "install_manifest_${CMAKE_INSTALL_COMPONENT}.txt") 47 | else() 48 | set(CMAKE_INSTALL_MANIFEST "install_manifest.txt") 49 | endif() 50 | 51 | string(REPLACE ";" "\n" CMAKE_INSTALL_MANIFEST_CONTENT 52 | "${CMAKE_INSTALL_MANIFEST_FILES}") 53 | file(WRITE "/home/yanyan/Documents/research/open/PlanarSLAM/Thirdparty/g2o/build/${CMAKE_INSTALL_MANIFEST}" 54 | "${CMAKE_INSTALL_MANIFEST_CONTENT}") 55 | -------------------------------------------------------------------------------- /Thirdparty/g2o/cmake_modules/FindEigen3.cmake: -------------------------------------------------------------------------------- 1 | # - Try to find Eigen3 lib 2 | # 3 | # This module supports requiring a minimum version, e.g. you can do 4 | # find_package(Eigen3 3.1.2) 5 | # to require version 3.1.2 or newer of Eigen3. 6 | # 7 | # Once done this will define 8 | # 9 | # EIGEN3_FOUND - system has eigen lib with correct version 10 | # EIGEN3_INCLUDE_DIR - the eigen include directory 11 | # EIGEN3_VERSION - eigen version 12 | 13 | # Copyright (c) 2006, 2007 Montel Laurent, 14 | # Copyright (c) 2008, 2009 Gael Guennebaud, 15 | # Copyright (c) 2009 Benoit Jacob 16 | # Redistribution and use is allowed according to the terms of the 2-clause BSD license. 17 | 18 | if(NOT Eigen3_FIND_VERSION) 19 | if(NOT Eigen3_FIND_VERSION_MAJOR) 20 | set(Eigen3_FIND_VERSION_MAJOR 2) 21 | endif(NOT Eigen3_FIND_VERSION_MAJOR) 22 | if(NOT Eigen3_FIND_VERSION_MINOR) 23 | set(Eigen3_FIND_VERSION_MINOR 91) 24 | endif(NOT Eigen3_FIND_VERSION_MINOR) 25 | if(NOT Eigen3_FIND_VERSION_PATCH) 26 | set(Eigen3_FIND_VERSION_PATCH 0) 27 | endif(NOT Eigen3_FIND_VERSION_PATCH) 28 | 29 | set(Eigen3_FIND_VERSION "${Eigen3_FIND_VERSION_MAJOR}.${Eigen3_FIND_VERSION_MINOR}.${Eigen3_FIND_VERSION_PATCH}") 30 | endif(NOT Eigen3_FIND_VERSION) 31 | 32 | macro(_eigen3_check_version) 33 | file(READ "${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _eigen3_version_header) 34 | 35 | string(REGEX MATCH "define[ \t]+EIGEN_WORLD_VERSION[ \t]+([0-9]+)" _eigen3_world_version_match "${_eigen3_version_header}") 36 | set(EIGEN3_WORLD_VERSION "${CMAKE_MATCH_1}") 37 | string(REGEX MATCH "define[ \t]+EIGEN_MAJOR_VERSION[ \t]+([0-9]+)" _eigen3_major_version_match "${_eigen3_version_header}") 38 | set(EIGEN3_MAJOR_VERSION "${CMAKE_MATCH_1}") 39 | string(REGEX MATCH "define[ \t]+EIGEN_MINOR_VERSION[ \t]+([0-9]+)" _eigen3_minor_version_match "${_eigen3_version_header}") 40 | set(EIGEN3_MINOR_VERSION "${CMAKE_MATCH_1}") 41 | 42 | set(EIGEN3_VERSION ${EIGEN3_WORLD_VERSION}.${EIGEN3_MAJOR_VERSION}.${EIGEN3_MINOR_VERSION}) 43 | if(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) 44 | set(EIGEN3_VERSION_OK FALSE) 45 | else(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) 46 | set(EIGEN3_VERSION_OK TRUE) 47 | endif(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) 48 | 49 | if(NOT EIGEN3_VERSION_OK) 50 | 51 | message(STATUS "Eigen3 version ${EIGEN3_VERSION} found in ${EIGEN3_INCLUDE_DIR}, " 52 | "but at least version ${Eigen3_FIND_VERSION} is required") 53 | endif(NOT EIGEN3_VERSION_OK) 54 | endmacro(_eigen3_check_version) 55 | 56 | if (EIGEN3_INCLUDE_DIR) 57 | 58 | # in cache already 59 | _eigen3_check_version() 60 | set(EIGEN3_FOUND ${EIGEN3_VERSION_OK}) 61 | 62 | else (EIGEN3_INCLUDE_DIR) 63 | 64 | # specific additional paths for some OS 65 | if (WIN32) 66 | set(EIGEN_ADDITIONAL_SEARCH_PATHS ${EIGEN_ADDITIONAL_SEARCH_PATHS} "C:/Program Files/Eigen/include" "C:/Program Files (x86)/Eigen/include") 67 | endif(WIN32) 68 | 69 | find_path(EIGEN3_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library 70 | PATHS 71 | ${CMAKE_INSTALL_PREFIX}/include 72 | ${EIGEN_ADDITIONAL_SEARCH_PATHS} 73 | ${KDE4_INCLUDE_DIR} 74 | PATH_SUFFIXES eigen3 eigen 75 | ) 76 | 77 | if(EIGEN3_INCLUDE_DIR) 78 | _eigen3_check_version() 79 | endif(EIGEN3_INCLUDE_DIR) 80 | 81 | include(FindPackageHandleStandardArgs) 82 | find_package_handle_standard_args(Eigen3 DEFAULT_MSG EIGEN3_INCLUDE_DIR EIGEN3_VERSION_OK) 83 | 84 | mark_as_advanced(EIGEN3_INCLUDE_DIR) 85 | 86 | endif(EIGEN3_INCLUDE_DIR) 87 | 88 | -------------------------------------------------------------------------------- /Thirdparty/g2o/config.h: -------------------------------------------------------------------------------- 1 | #ifndef G2O_CONFIG_H 2 | #define G2O_CONFIG_H 3 | 4 | /* #undef G2O_OPENMP */ 5 | /* #undef G2O_SHARED_LIBS */ 6 | 7 | // give a warning if Eigen defaults to row-major matrices. 8 | // We internally assume column-major matrices throughout the code. 9 | #ifdef EIGEN_DEFAULT_TO_ROW_MAJOR 10 | # error "g2o requires column major Eigen matrices (see http://eigen.tuxfamily.org/bz/show_bug.cgi?id=422)" 11 | #endif 12 | 13 | #endif 14 | -------------------------------------------------------------------------------- /Thirdparty/g2o/config.h.in: -------------------------------------------------------------------------------- 1 | #ifndef G2O_CONFIG_H 2 | #define G2O_CONFIG_H 3 | 4 | #cmakedefine G2O_OPENMP 1 5 | #cmakedefine G2O_SHARED_LIBS 1 6 | 7 | // give a warning if Eigen defaults to row-major matrices. 8 | // We internally assume column-major matrices throughout the code. 9 | #ifdef EIGEN_DEFAULT_TO_ROW_MAJOR 10 | # error "g2o requires column major Eigen matrices (see http://eigen.tuxfamily.org/bz/show_bug.cgi?id=422)" 11 | #endif 12 | 13 | #endif 14 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/core/base_vertex.hpp: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | template 28 | BaseVertex::BaseVertex() : 29 | OptimizableGraph::Vertex(), 30 | _hessian(0, D, D) 31 | { 32 | _dimension = D; 33 | } 34 | 35 | template 36 | double BaseVertex::solveDirect(double lambda) { 37 | Matrix tempA=_hessian + Matrix ::Identity()*lambda; 38 | double det=tempA.determinant(); 39 | if (g2o_isnan(det) || det < std::numeric_limits::epsilon()) 40 | return det; 41 | Matrix dx=tempA.llt().solve(_b); 42 | oplus(&dx[0]); 43 | return det; 44 | } 45 | 46 | template 47 | void BaseVertex::clearQuadraticForm() { 48 | _b.setZero(); 49 | } 50 | 51 | template 52 | void BaseVertex::mapHessianMemory(double* d) 53 | { 54 | new (&_hessian) HessianBlockType(d, D, D); 55 | } 56 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/core/batch_stats.cpp: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #include "batch_stats.h" 28 | #include 29 | 30 | namespace g2o { 31 | using namespace std; 32 | 33 | G2OBatchStatistics* G2OBatchStatistics::_globalStats=0; 34 | 35 | #ifndef PTHING 36 | #define PTHING(s) \ 37 | #s << "= " << (st.s) << "\t " 38 | #endif 39 | 40 | G2OBatchStatistics::G2OBatchStatistics(){ 41 | // zero all. 42 | memset (this, 0, sizeof(G2OBatchStatistics)); 43 | 44 | // set the iteration to -1 to show that it isn't valid 45 | iteration = -1; 46 | } 47 | 48 | std::ostream& operator << (std::ostream& os , const G2OBatchStatistics& st) 49 | { 50 | os << PTHING(iteration); 51 | 52 | os << PTHING( numVertices ); // how many vertices are involved 53 | os << PTHING( numEdges ); // hoe many edges 54 | os << PTHING( chi2 ); // total chi2 55 | 56 | /** timings **/ 57 | // nonlinear part 58 | os << PTHING( timeResiduals ); 59 | os << PTHING( timeLinearize ); // jacobians 60 | os << PTHING( timeQuadraticForm ); // construct the quadratic form in the graph 61 | 62 | // block_solver (constructs Ax=b, plus maybe schur); 63 | os << PTHING( timeSchurComplement ); // compute schur complement (0 if not done); 64 | 65 | // linear solver (computes Ax=b); ); 66 | os << PTHING( timeSymbolicDecomposition ); // symbolic decomposition (0 if not done); 67 | os << PTHING( timeNumericDecomposition ); // numeric decomposition (0 if not done); 68 | os << PTHING( timeLinearSolution ); // total time for solving Ax=b 69 | os << PTHING( iterationsLinearSolver ); // iterations of PCG 70 | os << PTHING( timeUpdate ); // oplus 71 | os << PTHING( timeIteration ); // total time ); 72 | 73 | os << PTHING( levenbergIterations ); 74 | os << PTHING( timeLinearSolver); 75 | 76 | os << PTHING(hessianDimension); 77 | os << PTHING(hessianPoseDimension); 78 | os << PTHING(hessianLandmarkDimension); 79 | os << PTHING(choleskyNNZ); 80 | os << PTHING(timeMarginals); 81 | 82 | return os; 83 | }; 84 | 85 | void G2OBatchStatistics::setGlobalStats(G2OBatchStatistics* b) 86 | { 87 | _globalStats = b; 88 | } 89 | 90 | } // end namespace 91 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/core/creators.h: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #ifndef G2O_CREATORS_H 28 | #define G2O_CREATORS_H 29 | 30 | #include "hyper_graph.h" 31 | 32 | #include 33 | #include 34 | 35 | namespace g2o 36 | { 37 | 38 | /** 39 | * \brief Abstract interface for allocating HyperGraphElement 40 | */ 41 | class AbstractHyperGraphElementCreator 42 | { 43 | public: 44 | /** 45 | * create a hyper graph element. Has to implemented in derived class. 46 | */ 47 | virtual HyperGraph::HyperGraphElement* construct() = 0; 48 | /** 49 | * name of the class to be created. Has to implemented in derived class. 50 | */ 51 | virtual const std::string& name() const = 0; 52 | 53 | virtual ~AbstractHyperGraphElementCreator() { } 54 | }; 55 | 56 | /** 57 | * \brief templatized creator class which creates graph elements 58 | */ 59 | template 60 | class HyperGraphElementCreator : public AbstractHyperGraphElementCreator 61 | { 62 | public: 63 | HyperGraphElementCreator() : _name(typeid(T).name()) {} 64 | #if defined (WINDOWS) && defined(__GNUC__) // force stack alignment on Windows with GCC 65 | __attribute__((force_align_arg_pointer)) 66 | #endif 67 | HyperGraph::HyperGraphElement* construct() { return new T;} 68 | virtual const std::string& name() const { return _name;} 69 | protected: 70 | std::string _name; 71 | }; 72 | 73 | } // end namespace 74 | 75 | #endif 76 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/core/jacobian_workspace.h: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #ifndef JACOBIAN_WORKSPACE_H 28 | #define JACOBIAN_WORKSPACE_H 29 | 30 | #include 31 | #include 32 | 33 | #include 34 | #include 35 | 36 | #include "hyper_graph.h" 37 | 38 | namespace g2o { 39 | 40 | struct OptimizableGraph; 41 | 42 | /** 43 | * \brief provide memory workspace for computing the Jacobians 44 | * 45 | * The workspace is used by an OptimizableGraph to provide temporary memory 46 | * for computing the Jacobian of the error functions. 47 | * Before calling linearizeOplus on an edge, the workspace needs to be allocated 48 | * by calling allocate(). 49 | */ 50 | class JacobianWorkspace 51 | { 52 | public: 53 | typedef std::vector > WorkspaceVector; 54 | 55 | public: 56 | JacobianWorkspace(); 57 | ~JacobianWorkspace(); 58 | 59 | /** 60 | * allocate the workspace 61 | */ 62 | bool allocate(); 63 | 64 | /** 65 | * update the maximum required workspace needed by taking into account this edge 66 | */ 67 | void updateSize(const HyperGraph::Edge* e); 68 | 69 | /** 70 | * update the required workspace by looking at a full graph 71 | */ 72 | void updateSize(const OptimizableGraph& graph); 73 | 74 | /** 75 | * manually update with the given parameters 76 | */ 77 | void updateSize(int numVertices, int dimension); 78 | 79 | /** 80 | * return the workspace for a vertex in an edge 81 | */ 82 | double* workspaceForVertex(int vertexIndex) 83 | { 84 | assert(vertexIndex >= 0 && (size_t)vertexIndex < _workspace.size() && "Index out of bounds"); 85 | return _workspace[vertexIndex].data(); 86 | } 87 | 88 | protected: 89 | WorkspaceVector _workspace; ///< the memory pre-allocated for computing the Jacobians 90 | int _maxNumVertices; ///< the maximum number of vertices connected by a hyper-edge 91 | int _maxDimension; ///< the maximum dimension (number of elements) for a Jacobian 92 | }; 93 | 94 | } // end namespace 95 | 96 | #endif 97 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/core/matrix_operations.h: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #ifndef G2O_CORE_MATRIX_OPERATIONS_H 28 | #define G2O_CORE_MATRIX_OPERATIONS_H 29 | 30 | #include 31 | 32 | namespace g2o { 33 | namespace internal { 34 | 35 | template 36 | inline void axpy(const MatrixType& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) 37 | { 38 | y.segment(yoff) += A * x.segment(xoff); 39 | } 40 | 41 | template 42 | inline void axpy(const Eigen::Matrix& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) 43 | { 44 | y.segment(yoff, A.rows()) += A * x.segment::ColsAtCompileTime>(xoff); 45 | } 46 | 47 | template<> 48 | inline void axpy(const Eigen::MatrixXd& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) 49 | { 50 | y.segment(yoff, A.rows()) += A * x.segment(xoff, A.cols()); 51 | } 52 | 53 | template 54 | inline void atxpy(const MatrixType& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) 55 | { 56 | y.segment(yoff) += A.transpose() * x.segment(xoff); 57 | } 58 | 59 | template 60 | inline void atxpy(const Eigen::Matrix& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) 61 | { 62 | y.segment::ColsAtCompileTime>(yoff) += A.transpose() * x.segment(xoff, A.rows()); 63 | } 64 | 65 | template<> 66 | inline void atxpy(const Eigen::MatrixXd& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) 67 | { 68 | y.segment(yoff, A.cols()) += A.transpose() * x.segment(xoff, A.rows()); 69 | } 70 | 71 | } // end namespace internal 72 | } // end namespace g2o 73 | 74 | #endif 75 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/core/matrix_structure.h: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #ifndef G2O_MATRIX_STRUCTURE_H 28 | #define G2O_MATRIX_STRUCTURE_H 29 | 30 | 31 | namespace g2o { 32 | 33 | /** 34 | * \brief representing the structure of a matrix in column compressed structure (only the upper triangular part of the matrix) 35 | */ 36 | class MatrixStructure 37 | { 38 | public: 39 | MatrixStructure(); 40 | ~MatrixStructure(); 41 | /** 42 | * allocate space for the Matrix Structure. You may call this on an already allocated struct, it will 43 | * then reallocate the memory + additional space (double the required space). 44 | */ 45 | void alloc(int n_, int nz); 46 | 47 | void free(); 48 | 49 | /** 50 | * Write the matrix pattern to a file. File is also loadable by octave, e.g., then use spy(matrix) 51 | */ 52 | bool write(const char* filename) const; 53 | 54 | int n; ///< A is m-by-n. n must be >= 0. 55 | int m; ///< A is m-by-n. m must be >= 0. 56 | int* Ap; ///< column pointers for A, of size n+1 57 | int* Aii; ///< row indices of A, of size nz = Ap [n] 58 | 59 | //! max number of non-zeros blocks 60 | int nzMax() const { return maxNz;} 61 | 62 | protected: 63 | int maxN; ///< size of the allocated memory 64 | int maxNz; ///< size of the allocated memory 65 | }; 66 | 67 | } // end namespace 68 | 69 | #endif 70 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/core/openmp_mutex.h: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #ifndef G2O_OPENMP_MUTEX 28 | #define G2O_OPENMP_MUTEX 29 | 30 | #include "../../config.h" 31 | 32 | #ifdef G2O_OPENMP 33 | #include 34 | #else 35 | #include 36 | #endif 37 | 38 | namespace g2o { 39 | 40 | #ifdef G2O_OPENMP 41 | 42 | /** 43 | * \brief Mutex realized via OpenMP 44 | */ 45 | class OpenMPMutex 46 | { 47 | public: 48 | OpenMPMutex() { omp_init_lock(&_lock); } 49 | ~OpenMPMutex() { omp_destroy_lock(&_lock); } 50 | void lock() { omp_set_lock(&_lock); } 51 | void unlock() { omp_unset_lock(&_lock); } 52 | protected: 53 | omp_lock_t _lock; 54 | }; 55 | 56 | #else 57 | 58 | /* 59 | * dummy which does nothing in case we don't have OpenMP support. 60 | * In debug mode, the mutex allows to verify the correct lock and unlock behavior 61 | */ 62 | class OpenMPMutex 63 | { 64 | public: 65 | #ifdef NDEBUG 66 | OpenMPMutex() {} 67 | #else 68 | OpenMPMutex() : _cnt(0) {} 69 | #endif 70 | ~OpenMPMutex() { assert(_cnt == 0 && "Freeing locked mutex");} 71 | void lock() { assert(++_cnt == 1 && "Locking already locked mutex");} 72 | void unlock() { assert(--_cnt == 0 && "Trying to unlock a mutex which is not locked");} 73 | protected: 74 | #ifndef NDEBUG 75 | char _cnt; 76 | #endif 77 | }; 78 | 79 | #endif 80 | 81 | /** 82 | * \brief lock a mutex within a scope 83 | */ 84 | class ScopedOpenMPMutex 85 | { 86 | public: 87 | explicit ScopedOpenMPMutex(OpenMPMutex* mutex) : _mutex(mutex) { _mutex->lock(); } 88 | ~ScopedOpenMPMutex() { _mutex->unlock(); } 89 | private: 90 | OpenMPMutex* const _mutex; 91 | ScopedOpenMPMutex(const ScopedOpenMPMutex&); 92 | void operator=(const ScopedOpenMPMutex&); 93 | }; 94 | 95 | } 96 | 97 | #endif 98 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/core/optimization_algorithm.cpp: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #include "optimization_algorithm.h" 28 | 29 | using namespace std; 30 | 31 | namespace g2o { 32 | 33 | OptimizationAlgorithm::OptimizationAlgorithm() : 34 | _optimizer(0) 35 | { 36 | } 37 | 38 | OptimizationAlgorithm::~OptimizationAlgorithm() 39 | { 40 | } 41 | 42 | void OptimizationAlgorithm::printProperties(std::ostream& os) const 43 | { 44 | os << "------------- Algorithm Properties -------------" << endl; 45 | for (PropertyMap::const_iterator it = _properties.begin(); it != _properties.end(); ++it) { 46 | BaseProperty* p = it->second; 47 | os << it->first << "\t" << p->toString() << endl; 48 | } 49 | os << "------------------------------------------------" << endl; 50 | } 51 | 52 | bool OptimizationAlgorithm::updatePropertiesFromString(const std::string& propString) 53 | { 54 | return _properties.updateMapFromString(propString); 55 | } 56 | 57 | void OptimizationAlgorithm::setOptimizer(SparseOptimizer* optimizer) 58 | { 59 | _optimizer = optimizer; 60 | } 61 | 62 | } // end namespace 63 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/core/optimization_algorithm_gauss_newton.h: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #ifndef G2O_OPTIMIZATION_ALGORITHM_GAUSS_NEWTON_H 28 | #define G2O_OPTIMIZATION_ALGORITHM_GAUSS_NEWTON_H 29 | 30 | #include "optimization_algorithm_with_hessian.h" 31 | 32 | namespace g2o { 33 | 34 | /** 35 | * \brief Implementation of the Gauss Newton Algorithm 36 | */ 37 | class OptimizationAlgorithmGaussNewton : public OptimizationAlgorithmWithHessian 38 | { 39 | public: 40 | /** 41 | * construct the Gauss Newton algorithm, which use the given Solver for solving the 42 | * linearized system. 43 | */ 44 | explicit OptimizationAlgorithmGaussNewton(Solver* solver); 45 | virtual ~OptimizationAlgorithmGaussNewton(); 46 | 47 | virtual SolverResult solve(int iteration, bool online = false); 48 | 49 | virtual void printVerbose(std::ostream& os) const; 50 | }; 51 | 52 | } // end namespace 53 | 54 | #endif 55 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/core/optimization_algorithm_property.h: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #ifndef G2O_OPTIMIZATION_ALGORITHM_PROPERTY_H 28 | #define G2O_OPTIMIZATION_ALGORITHM_PROPERTY_H 29 | 30 | #include 31 | 32 | namespace g2o { 33 | 34 | /** 35 | * \brief describe the properties of a solver 36 | */ 37 | struct OptimizationAlgorithmProperty 38 | { 39 | std::string name; ///< name of the solver, e.g., var 40 | std::string desc; ///< short description of the solver 41 | std::string type; ///< type of solver, e.g., "CSparse Cholesky", "PCG" 42 | bool requiresMarginalize; ///< whether the solver requires marginalization of landmarks 43 | int poseDim; ///< dimension of the pose vertices (-1 if variable) 44 | int landmarkDim; ///< dimension of the landmar vertices (-1 if variable) 45 | OptimizationAlgorithmProperty() : 46 | name(), desc(), type(), requiresMarginalize(false), poseDim(-1), landmarkDim(-1) 47 | { 48 | } 49 | OptimizationAlgorithmProperty(const std::string& name_, const std::string& desc_, const std::string& type_, bool requiresMarginalize_, int poseDim_, int landmarkDim_) : 50 | name(name_), desc(desc_), type(type_), requiresMarginalize(requiresMarginalize_), poseDim(poseDim_), landmarkDim(landmarkDim_) 51 | { 52 | } 53 | }; 54 | 55 | } // end namespace 56 | 57 | #endif 58 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/core/optimization_algorithm_with_hessian.h: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #ifndef G2O_OPTIMIZATION_ALGORITHM_WITH_HESSIAN_H 28 | #define G2O_OPTIMIZATION_ALGORITHM_WITH_HESSIAN_H 29 | 30 | #include "optimization_algorithm.h" 31 | 32 | namespace g2o { 33 | 34 | class Solver; 35 | 36 | /** 37 | * \brief Base for solvers operating on the approximated Hessian, e.g., Gauss-Newton, Levenberg 38 | */ 39 | class OptimizationAlgorithmWithHessian : public OptimizationAlgorithm 40 | { 41 | public: 42 | explicit OptimizationAlgorithmWithHessian(Solver* solver); 43 | virtual ~OptimizationAlgorithmWithHessian(); 44 | 45 | virtual bool init(bool online = false); 46 | 47 | virtual bool computeMarginals(SparseBlockMatrix& spinv, const std::vector >& blockIndices); 48 | 49 | virtual bool buildLinearStructure(); 50 | 51 | virtual void updateLinearSystem(); 52 | 53 | virtual bool updateStructure(const std::vector& vset, const HyperGraph::EdgeSet& edges); 54 | 55 | //! return the underlying solver used to solve the linear system 56 | Solver* solver() { return _solver;} 57 | 58 | /** 59 | * write debug output of the Hessian if system is not positive definite 60 | */ 61 | virtual void setWriteDebug(bool writeDebug); 62 | virtual bool writeDebug() const { return _writeDebug->value();} 63 | 64 | protected: 65 | Solver* _solver; 66 | Property* _writeDebug; 67 | 68 | }; 69 | 70 | }// end namespace 71 | 72 | #endif 73 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/core/parameter.cpp: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #include "parameter.h" 28 | 29 | namespace g2o { 30 | 31 | Parameter::Parameter() : _id(-1) 32 | { 33 | } 34 | 35 | void Parameter::setId(int id_) 36 | { 37 | _id = id_; 38 | } 39 | 40 | } // end namespace 41 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/core/parameter.h: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #ifndef G2O_GRAPH_PARAMETER_HH_ 28 | #define G2O_GRAPH_PARAMETER_HH_ 29 | 30 | #include 31 | 32 | #include "hyper_graph.h" 33 | 34 | namespace g2o { 35 | 36 | class Parameter : public HyperGraph::HyperGraphElement 37 | { 38 | public: 39 | Parameter(); 40 | virtual ~Parameter() {}; 41 | //! read the data from a stream 42 | virtual bool read(std::istream& is) = 0; 43 | //! write the data to a stream 44 | virtual bool write(std::ostream& os) const = 0; 45 | int id() const {return _id;} 46 | void setId(int id_); 47 | virtual HyperGraph::HyperGraphElementType elementType() const { return HyperGraph::HGET_PARAMETER;} 48 | protected: 49 | int _id; 50 | }; 51 | 52 | typedef std::vector ParameterVector; 53 | 54 | } // end namespace 55 | 56 | #endif 57 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/core/parameter_container.h: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #ifndef G2O_GRAPH_PARAMETER_CONTAINER_HH_ 28 | #define G2O_GRAPH_PARAMETER_CONTAINER_HH_ 29 | 30 | #include 31 | #include 32 | #include 33 | 34 | namespace g2o { 35 | 36 | class Parameter; 37 | 38 | /** 39 | * \brief map id to parameters 40 | */ 41 | class ParameterContainer : protected std::map 42 | { 43 | public: 44 | typedef std::map BaseClass; 45 | 46 | /** 47 | * create a container for the parameters. 48 | * @param isMainStorage_ pointers to the parameters are owned by this container, i.e., freed in its constructor 49 | */ 50 | ParameterContainer(bool isMainStorage_=true); 51 | virtual ~ParameterContainer(); 52 | //! add parameter to the container 53 | bool addParameter(Parameter* p); 54 | //! return a parameter based on its ID 55 | Parameter* getParameter(int id); 56 | //! remove a parameter from the container, i.e., the user now owns the pointer 57 | Parameter* detachParameter(int id); 58 | //! read parameters from a stream 59 | virtual bool read(std::istream& is, const std::map* renamedMap =0); 60 | //! write the data to a stream 61 | virtual bool write(std::ostream& os) const; 62 | bool isMainStorage() const {return _isMainStorage;} 63 | void clear(); 64 | 65 | // stuff of the base class that should re-appear 66 | using BaseClass::size; 67 | 68 | protected: 69 | bool _isMainStorage; 70 | }; 71 | 72 | } // end namespace 73 | 74 | #endif 75 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/core/robust_kernel.cpp: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #include "robust_kernel.h" 28 | 29 | namespace g2o { 30 | 31 | RobustKernel::RobustKernel() : 32 | _delta(1.) 33 | { 34 | } 35 | 36 | RobustKernel::RobustKernel(double delta) : 37 | _delta(delta) 38 | { 39 | } 40 | 41 | void RobustKernel::setDelta(double delta) 42 | { 43 | _delta = delta; 44 | } 45 | 46 | } // end namespace g2o 47 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/core/robust_kernel.h: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #ifndef G2O_ROBUST_KERNEL_H 28 | #define G2O_ROBUST_KERNEL_H 29 | 30 | #ifdef _MSC_VER 31 | #include 32 | #else 33 | #include 34 | #endif 35 | #include 36 | 37 | 38 | namespace g2o { 39 | 40 | /** 41 | * \brief base for all robust cost functions 42 | * 43 | * Note in all the implementations for the other cost functions the e in the 44 | * funtions corresponds to the sqaured errors, i.e., the robustification 45 | * functions gets passed the squared error. 46 | * 47 | * e.g. the robustified least squares function is 48 | * 49 | * chi^2 = sum_{e} rho( e^T Omega e ) 50 | */ 51 | class RobustKernel 52 | { 53 | public: 54 | RobustKernel(); 55 | explicit RobustKernel(double delta); 56 | virtual ~RobustKernel() {} 57 | /** 58 | * compute the scaling factor for a error: 59 | * The error is e^T Omega e 60 | * The output rho is 61 | * rho[0]: The actual scaled error value 62 | * rho[1]: First derivative of the scaling function 63 | * rho[2]: Second derivative of the scaling function 64 | */ 65 | virtual void robustify(double squaredError, Eigen::Vector3d& rho) const = 0; 66 | 67 | /** 68 | * set the window size of the error. A squared error above delta^2 is considered 69 | * as outlier in the data. 70 | */ 71 | virtual void setDelta(double delta); 72 | double delta() const { return _delta;} 73 | 74 | protected: 75 | double _delta; 76 | }; 77 | typedef std::tr1::shared_ptr RobustKernelPtr; 78 | 79 | } // end namespace g2o 80 | 81 | #endif 82 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/core/solver.cpp: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #include "solver.h" 28 | 29 | #include 30 | #include 31 | 32 | namespace g2o { 33 | 34 | Solver::Solver() : 35 | _optimizer(0), _x(0), _b(0), _xSize(0), _maxXSize(0), 36 | _isLevenberg(false), _additionalVectorSpace(0) 37 | { 38 | } 39 | 40 | Solver::~Solver() 41 | { 42 | delete[] _x; 43 | delete[] _b; 44 | } 45 | 46 | void Solver::resizeVector(size_t sx) 47 | { 48 | size_t oldSize = _xSize; 49 | _xSize = sx; 50 | sx += _additionalVectorSpace; // allocate some additional space if requested 51 | if (_maxXSize < sx) { 52 | _maxXSize = 2*sx; 53 | delete[] _x; 54 | _x = new double[_maxXSize]; 55 | #ifndef NDEBUG 56 | memset(_x, 0, _maxXSize * sizeof(double)); 57 | #endif 58 | if (_b) { // backup the former b, might still be needed for online processing 59 | memcpy(_x, _b, oldSize * sizeof(double)); 60 | delete[] _b; 61 | _b = new double[_maxXSize]; 62 | std::swap(_b, _x); 63 | } else { 64 | _b = new double[_maxXSize]; 65 | #ifndef NDEBUG 66 | memset(_b, 0, _maxXSize * sizeof(double)); 67 | #endif 68 | } 69 | } 70 | } 71 | 72 | void Solver::setOptimizer(SparseOptimizer* optimizer) 73 | { 74 | _optimizer = optimizer; 75 | } 76 | 77 | void Solver::setLevenberg(bool levenberg) 78 | { 79 | _isLevenberg = levenberg; 80 | } 81 | 82 | void Solver::setAdditionalVectorSpace(size_t s) 83 | { 84 | _additionalVectorSpace = s; 85 | } 86 | 87 | } // end namespace 88 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/stuff/color_macros.h: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #ifndef G2O_COLOR_MACROS_H 28 | #define G2O_COLOR_MACROS_H 29 | 30 | // font attributes 31 | #define FT_BOLD "\033[1m" 32 | #define FT_UNDERLINE "\033[4m" 33 | 34 | //background color 35 | #define BG_BLACK "\033[40m" 36 | #define BG_RED "\033[41m" 37 | #define BG_GREEN "\033[42m" 38 | #define BG_YELLOW "\033[43m" 39 | #define BG_LIGHTBLUE "\033[44m" 40 | #define BG_MAGENTA "\033[45m" 41 | #define BG_BLUE "\033[46m" 42 | #define BG_WHITE "\033[47m" 43 | 44 | // font color 45 | #define CL_BLACK(s) "\033[30m" << s << "\033[0m" 46 | #define CL_RED(s) "\033[31m" << s << "\033[0m" 47 | #define CL_GREEN(s) "\033[32m" << s << "\033[0m" 48 | #define CL_YELLOW(s) "\033[33m" << s << "\033[0m" 49 | #define CL_LIGHTBLUE(s) "\033[34m" << s << "\033[0m" 50 | #define CL_MAGENTA(s) "\033[35m" << s << "\033[0m" 51 | #define CL_BLUE(s) "\033[36m" << s << "\033[0m" 52 | #define CL_WHITE(s) "\033[37m" << s << "\033[0m" 53 | 54 | #define FG_BLACK "\033[30m" 55 | #define FG_RED "\033[31m" 56 | #define FG_GREEN "\033[32m" 57 | #define FG_YELLOW "\033[33m" 58 | #define FG_LIGHTBLUE "\033[34m" 59 | #define FG_MAGENTA "\033[35m" 60 | #define FG_BLUE "\033[36m" 61 | #define FG_WHITE "\033[37m" 62 | 63 | #define FG_NORM "\033[0m" 64 | 65 | #endif 66 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/stuff/os_specific.c: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #include "os_specific.h" 28 | 29 | #ifdef WINDOWS 30 | 31 | int vasprintf(char** strp, const char* fmt, va_list ap) 32 | { 33 | int n; 34 | int size = 100; 35 | char* p; 36 | char* np; 37 | 38 | if ((p = (char*)malloc(size * sizeof(char))) == NULL) 39 | return -1; 40 | 41 | while (1) { 42 | #ifdef _MSC_VER 43 | n = vsnprintf_s(p, size, size - 1, fmt, ap); 44 | #else 45 | n = vsnprintf(p, size, fmt, ap); 46 | #endif 47 | if (n > -1 && n < size) { 48 | *strp = p; 49 | return n; 50 | } 51 | if (n > -1) 52 | size = n+1; 53 | else 54 | size *= 2; 55 | if ((np = (char*)realloc (p, size * sizeof(char))) == NULL) { 56 | free(p); 57 | return -1; 58 | } else 59 | p = np; 60 | } 61 | } 62 | 63 | 64 | #endif 65 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/stuff/os_specific.h: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #ifndef G2O_OS_SPECIFIC_HH_ 28 | #define G2O_OS_SPECIFIC_HH_ 29 | 30 | #ifdef WINDOWS 31 | #include 32 | #include 33 | #include 34 | #ifndef _WINDOWS 35 | #include 36 | #endif 37 | #define drand48() ((double) rand()/(double)RAND_MAX) 38 | 39 | #ifdef __cplusplus 40 | extern "C" { 41 | #endif 42 | 43 | int vasprintf(char** strp, const char* fmt, va_list ap); 44 | 45 | #ifdef __cplusplus 46 | } 47 | #endif 48 | 49 | #endif 50 | 51 | #ifdef UNIX 52 | #include 53 | // nothing to do on real operating systems 54 | #endif 55 | 56 | #endif 57 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/types/se3_ops.h: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 H. Strasdat 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #ifndef G2O_MATH_STUFF 28 | #define G2O_MATH_STUFF 29 | 30 | #include 31 | #include 32 | 33 | namespace g2o { 34 | using namespace Eigen; 35 | 36 | inline Matrix3d skew(const Vector3d&v); 37 | inline Vector3d deltaR(const Matrix3d& R); 38 | inline Vector2d project(const Vector3d&); 39 | inline Vector3d project(const Vector4d&); 40 | inline Vector3d unproject(const Vector2d&); 41 | inline Vector4d unproject(const Vector3d&); 42 | 43 | #include "se3_ops.hpp" 44 | 45 | } 46 | 47 | #endif //MATH_STUFF 48 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/types/se3_ops.hpp: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 H. Strasdat 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | Matrix3d skew(const Vector3d&v) 28 | { 29 | Matrix3d m; 30 | m.fill(0.); 31 | m(0,1) = -v(2); 32 | m(0,2) = v(1); 33 | m(1,2) = -v(0); 34 | m(1,0) = v(2); 35 | m(2,0) = -v(1); 36 | m(2,1) = v(0); 37 | return m; 38 | } 39 | 40 | Vector3d deltaR(const Matrix3d& R) 41 | { 42 | Vector3d v; 43 | v(0)=R(2,1)-R(1,2); 44 | v(1)=R(0,2)-R(2,0); 45 | v(2)=R(1,0)-R(0,1); 46 | return v; 47 | } 48 | 49 | Vector2d project(const Vector3d& v) 50 | { 51 | Vector2d res; 52 | res(0) = v(0)/v(2); 53 | res(1) = v(1)/v(2); 54 | return res; 55 | } 56 | 57 | Vector3d project(const Vector4d& v) 58 | { 59 | Vector3d res; 60 | res(0) = v(0)/v(3); 61 | res(1) = v(1)/v(3); 62 | res(2) = v(2)/v(3); 63 | return res; 64 | } 65 | 66 | Vector3d unproject(const Vector2d& v) 67 | { 68 | Vector3d res; 69 | res(0) = v(0); 70 | res(1) = v(1); 71 | res(2) = 1; 72 | return res; 73 | } 74 | 75 | Vector4d unproject(const Vector3d& v) 76 | { 77 | Vector4d res; 78 | res(0) = v(0); 79 | res(1) = v(1); 80 | res(2) = v(2); 81 | res(3) = 1; 82 | return res; 83 | } 84 | 85 | 86 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/types/types_sba.cpp: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 Kurt Konolige 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #include "types_sba.h" 28 | #include 29 | 30 | namespace g2o { 31 | 32 | using namespace std; 33 | 34 | 35 | VertexSBAPointXYZ::VertexSBAPointXYZ() : BaseVertex<3, Vector3d>() 36 | { 37 | } 38 | 39 | bool VertexSBAPointXYZ::read(std::istream& is) 40 | { 41 | Vector3d lv; 42 | for (int i=0; i<3; i++) 43 | is >> _estimate[i]; 44 | return true; 45 | } 46 | 47 | bool VertexSBAPointXYZ::write(std::ostream& os) const 48 | { 49 | Vector3d lv=estimate(); 50 | for (int i=0; i<3; i++){ 51 | os << lv[i] << " "; 52 | } 53 | return os.good(); 54 | } 55 | 56 | } // end namespace 57 | -------------------------------------------------------------------------------- /Thirdparty/g2o/g2o/types/types_sba.h: -------------------------------------------------------------------------------- 1 | // g2o - General Graph Optimization 2 | // Copyright (C) 2011 Kurt Konolige 3 | // All rights reserved. 4 | // 5 | // Redistribution and use in source and binary forms, with or without 6 | // modification, are permitted provided that the following conditions are 7 | // met: 8 | // 9 | // * Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // * Redistributions in binary form must reproduce the above copyright 12 | // notice, this list of conditions and the following disclaimer in the 13 | // documentation and/or other materials provided with the distribution. 14 | // 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 16 | // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 17 | // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 18 | // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 21 | // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 22 | // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 23 | // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 24 | // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 25 | // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 | 27 | #ifndef G2O_SBA_TYPES 28 | #define G2O_SBA_TYPES 29 | 30 | #include "../core/base_vertex.h" 31 | 32 | #include 33 | #include 34 | 35 | namespace g2o { 36 | 37 | /** 38 | * \brief Point vertex, XYZ 39 | */ 40 | class VertexSBAPointXYZ : public BaseVertex<3, Vector3d> 41 | { 42 | public: 43 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 44 | VertexSBAPointXYZ(); 45 | virtual bool read(std::istream& is); 46 | virtual bool write(std::ostream& os) const; 47 | 48 | virtual void setToOriginImpl() { 49 | _estimate.fill(0.); 50 | } 51 | 52 | virtual void oplusImpl(const double* update) 53 | { 54 | Eigen::Map v(update); 55 | _estimate += v; 56 | } 57 | }; 58 | 59 | } // end namespace 60 | 61 | #endif // SBA_TYPES 62 | -------------------------------------------------------------------------------- /Thirdparty/g2o/lib/libg2o.so: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Thirdparty/g2o/lib/libg2o.so -------------------------------------------------------------------------------- /Thirdparty/g2o/license-bsd.txt: -------------------------------------------------------------------------------- 1 | g2o - General Graph Optimization 2 | Copyright (C) 2011 Rainer Kuemmerle, Giorgio Grisetti, Hauke Strasdat, 3 | Kurt Konolige, and Wolfram Burgard 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions are 8 | met: 9 | 10 | * Redistributions of source code must retain the above copyright notice, 11 | this list of conditions and the following disclaimer. 12 | * Redistributions in binary form must reproduce the above copyright 13 | notice, this list of conditions and the following disclaimer in the 14 | documentation and/or other materials provided with the distribution. 15 | 16 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 17 | IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 18 | TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A 19 | PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 20 | HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 21 | SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED 22 | TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR 23 | PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 24 | LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 25 | NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 26 | SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 27 | 28 | -------------------------------------------------------------------------------- /Vocabulary/ORBvoc.txt.tar.gz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yanyan-li/PlanarSLAM/08b5719e609b7ff72e1032b759721a3ae87b01c8/Vocabulary/ORBvoc.txt.tar.gz -------------------------------------------------------------------------------- /build.sh: -------------------------------------------------------------------------------- 1 | echo "Configuring and building Thirdparty/DBoW2 ..." 2 | 3 | cd Thirdparty/DBoW2 4 | mkdir build 5 | cd build 6 | cmake .. -DCMAKE_BUILD_TYPE=Release 7 | make -j 8 | 9 | cd ../../g2o 10 | 11 | echo "Configuring and building Thirdparty/g2o ..." 12 | 13 | mkdir build 14 | cd build 15 | cmake .. -DCMAKE_BUILD_TYPE=Release 16 | make -j 17 | 18 | cd ../../../ 19 | 20 | echo "Uncompress vocabulary ..." 21 | 22 | cd Vocabulary 23 | tar -xf ORBvoc.txt.tar.gz 24 | cd .. 25 | 26 | echo "Configuring and building ORB_SLAM2 ..." 27 | 28 | mkdir build 29 | cd build 30 | cmake .. -DCMAKE_BUILD_TYPE=Release 31 | make -j 32 | -------------------------------------------------------------------------------- /cmake_modules/FindEigen3.cmake: -------------------------------------------------------------------------------- 1 | # - Try to find Eigen3 lib 2 | # 3 | # This module supports requiring a minimum version, e.g. you can do 4 | # find_package(Eigen3 3.1.2) 5 | # to require version 3.1.2 or newer of Eigen3. 6 | # 7 | # Once done this will define 8 | # 9 | # EIGEN3_FOUND - system has eigen lib with correct version 10 | # EIGEN3_INCLUDE_DIR - the eigen include directory 11 | # EIGEN3_VERSION - eigen version 12 | 13 | # Copyright (c) 2006, 2007 Montel Laurent, 14 | # Copyright (c) 2008, 2009 Gael Guennebaud, 15 | # Copyright (c) 2009 Benoit Jacob 16 | # Redistribution and use is allowed according to the terms of the 2-clause BSD license. 17 | 18 | if(NOT Eigen3_FIND_VERSION) 19 | if(NOT Eigen3_FIND_VERSION_MAJOR) 20 | set(Eigen3_FIND_VERSION_MAJOR 2) 21 | endif(NOT Eigen3_FIND_VERSION_MAJOR) 22 | if(NOT Eigen3_FIND_VERSION_MINOR) 23 | set(Eigen3_FIND_VERSION_MINOR 91) 24 | endif(NOT Eigen3_FIND_VERSION_MINOR) 25 | if(NOT Eigen3_FIND_VERSION_PATCH) 26 | set(Eigen3_FIND_VERSION_PATCH 0) 27 | endif(NOT Eigen3_FIND_VERSION_PATCH) 28 | 29 | set(Eigen3_FIND_VERSION "${Eigen3_FIND_VERSION_MAJOR}.${Eigen3_FIND_VERSION_MINOR}.${Eigen3_FIND_VERSION_PATCH}") 30 | endif(NOT Eigen3_FIND_VERSION) 31 | 32 | macro(_eigen3_check_version) 33 | file(READ "${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _eigen3_version_header) 34 | 35 | string(REGEX MATCH "define[ \t]+EIGEN_WORLD_VERSION[ \t]+([0-9]+)" _eigen3_world_version_match "${_eigen3_version_header}") 36 | set(EIGEN3_WORLD_VERSION "${CMAKE_MATCH_1}") 37 | string(REGEX MATCH "define[ \t]+EIGEN_MAJOR_VERSION[ \t]+([0-9]+)" _eigen3_major_version_match "${_eigen3_version_header}") 38 | set(EIGEN3_MAJOR_VERSION "${CMAKE_MATCH_1}") 39 | string(REGEX MATCH "define[ \t]+EIGEN_MINOR_VERSION[ \t]+([0-9]+)" _eigen3_minor_version_match "${_eigen3_version_header}") 40 | set(EIGEN3_MINOR_VERSION "${CMAKE_MATCH_1}") 41 | 42 | set(EIGEN3_VERSION ${EIGEN3_WORLD_VERSION}.${EIGEN3_MAJOR_VERSION}.${EIGEN3_MINOR_VERSION}) 43 | if(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) 44 | set(EIGEN3_VERSION_OK FALSE) 45 | else(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) 46 | set(EIGEN3_VERSION_OK TRUE) 47 | endif(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) 48 | 49 | if(NOT EIGEN3_VERSION_OK) 50 | 51 | message(STATUS "Eigen3 version ${EIGEN3_VERSION} found in ${EIGEN3_INCLUDE_DIR}, " 52 | "but at least version ${Eigen3_FIND_VERSION} is required") 53 | endif(NOT EIGEN3_VERSION_OK) 54 | endmacro(_eigen3_check_version) 55 | 56 | if (EIGEN3_INCLUDE_DIR) 57 | 58 | # in cache already 59 | _eigen3_check_version() 60 | set(EIGEN3_FOUND ${EIGEN3_VERSION_OK}) 61 | 62 | else (EIGEN3_INCLUDE_DIR) 63 | 64 | # specific additional paths for some OS 65 | if (WIN32) 66 | set(EIGEN_ADDITIONAL_SEARCH_PATHS ${EIGEN_ADDITIONAL_SEARCH_PATHS} "C:/Program Files/Eigen/include" "C:/Program Files (x86)/Eigen/include") 67 | endif(WIN32) 68 | 69 | find_path(EIGEN3_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library 70 | PATHS 71 | ${CMAKE_INSTALL_PREFIX}/include 72 | ${EIGEN_ADDITIONAL_SEARCH_PATHS} 73 | ${KDE4_INCLUDE_DIR} 74 | PATH_SUFFIXES eigen3 eigen 75 | ) 76 | 77 | if(EIGEN3_INCLUDE_DIR) 78 | _eigen3_check_version() 79 | endif(EIGEN3_INCLUDE_DIR) 80 | 81 | include(FindPackageHandleStandardArgs) 82 | find_package_handle_standard_args(Eigen3 DEFAULT_MSG EIGEN3_INCLUDE_DIR EIGEN3_VERSION_OK) 83 | 84 | mark_as_advanced(EIGEN3_INCLUDE_DIR) 85 | 86 | endif(EIGEN3_INCLUDE_DIR) 87 | 88 | -------------------------------------------------------------------------------- /g2oAddition/VertexPlane.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by fishmarch on 19-5-28. 3 | // 4 | 5 | #ifndef ORB_SLAM2_VERTEXPLANE_H 6 | #define ORB_SLAM2_VERTEXPLANE_H 7 | 8 | #include "Thirdparty/g2o/g2o/core/base_vertex.h" 9 | #include "Thirdparty/g2o/g2o/core/hyper_graph_action.h" 10 | #include "Thirdparty/g2o/g2o/core/eigen_types.h" 11 | #include "Thirdparty/g2o/g2o/stuff/misc.h" 12 | #include "g2oAddition/Plane3D.h" 13 | 14 | 15 | namespace g2o { 16 | class VertexPlane : public BaseVertex<3, Plane3D> { 17 | public: 18 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW; 19 | 20 | VertexPlane() {} 21 | 22 | virtual void setToOriginImpl() { _estimate = Plane3D(); } 23 | 24 | virtual void oplusImpl(const double *update_) { 25 | Eigen::Map update(update_); 26 | _estimate.oplus(update); 27 | } 28 | 29 | virtual bool setEstimateDataImpl(const double *est) { 30 | Eigen::Map _est(est); 31 | _estimate.fromVector(_est); 32 | return true; 33 | } 34 | 35 | virtual bool getEstimateData(double *est) const { 36 | Eigen::Map _est(est); 37 | _est = _estimate.toVector(); 38 | return true; 39 | } 40 | 41 | virtual int estimateDimension() const { 42 | return 4; 43 | } 44 | 45 | virtual bool read(std::istream &is) { 46 | Vector4D lv; 47 | for (int i = 0; i < 4; i++) 48 | is >> lv[i]; 49 | setEstimate(Plane3D(lv)); 50 | return true; 51 | } 52 | 53 | virtual bool write(std::ostream &os) const { 54 | Vector4D lv = _estimate.toVector(); 55 | for (int i = 0; i < 4; i++) { 56 | os << lv[i] << " "; 57 | } 58 | return os.good(); 59 | } 60 | 61 | }; 62 | } 63 | 64 | 65 | #endif //ORB_SLAM2_VERTEXPLANE_H 66 | -------------------------------------------------------------------------------- /include/Config.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by fishmarch on 19-5-24. 3 | // 4 | 5 | #ifndef ORB_SLAM2_CONFIG_H 6 | #define ORB_SLAM2_CONFIG_H 7 | #include 8 | #include 9 | #include 10 | 11 | using namespace std; 12 | namespace Planar_SLAM { 13 | class Config{ 14 | public: 15 | static void SetParameterFile( const string& filename ); 16 | 17 | template 18 | static T Get(const string& key){ 19 | return T(Config::mConfig->mFile[key]); 20 | } 21 | ~Config(); 22 | private: 23 | Config(){} 24 | static std::shared_ptr mConfig; 25 | cv::FileStorage mFile; 26 | }; 27 | } 28 | #endif //ORB_SLAM2_CONFIG_H 29 | -------------------------------------------------------------------------------- /include/Converter.h: -------------------------------------------------------------------------------- 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 | #ifndef CONVERTER_H 22 | #define CONVERTER_H 23 | 24 | #include 25 | 26 | #include 27 | #include"Thirdparty/g2o/g2o/types/types_six_dof_expmap.h" 28 | #include"Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h" 29 | #include "g2oAddition/Plane3D.h" 30 | 31 | namespace Planar_SLAM 32 | { 33 | 34 | class Converter 35 | { 36 | public: 37 | static std::vector toDescriptorVector(const cv::Mat &Descriptors); 38 | 39 | static g2o::SE3Quat toSE3Quat(const cv::Mat &cvT); 40 | static g2o::SE3Quat toSE3Quat(const g2o::Sim3 &gSim3); 41 | 42 | static cv::Mat toCvMat(const g2o::SE3Quat &SE3); 43 | static cv::Mat toCvMat(const g2o::Sim3 &Sim3); 44 | static cv::Mat toCvMat(const Eigen::Matrix &m); 45 | static cv::Mat toCvMat(const Eigen::Matrix3d &m); 46 | static cv::Mat toCvMat(const Eigen::Matrix &m); 47 | static cv::Mat toCvVec(const Eigen::Matrix &m); 48 | static cv::Mat toCvSE3(const Eigen::Matrix &R, const Eigen::Matrix &t); 49 | 50 | static Eigen::Matrix toVector3d(const cv::Mat &cvVector); 51 | static Eigen::Matrix toVector3d(const cv::Point3f &cvPoint); 52 | static Eigen::Matrix toMatrix3d(const cv::Mat &cvMat3); 53 | static Eigen::Matrix toMatrix4d(const cv::Mat &cvMat4); 54 | 55 | static std::vector toQuaternion(const cv::Mat &M); 56 | 57 | static g2o::Plane3D toPlane3D(const cv::Mat &coe); 58 | static cv::Mat toCvMat(const g2o::Plane3D &plane); 59 | }; 60 | 61 | }// namespace ORB_SLAM 62 | 63 | #endif // CONVERTER_H 64 | -------------------------------------------------------------------------------- /include/FrameDrawer.h: -------------------------------------------------------------------------------- 1 | #ifndef FRAMEDRAWER_H 2 | #define FRAMEDRAWER_H 3 | 4 | #include "Tracking.h" 5 | #include "MapPoint.h" 6 | #include "Map.h" 7 | 8 | #include 9 | #include 10 | 11 | #include 12 | 13 | 14 | namespace Planar_SLAM 15 | { 16 | 17 | class Tracking; 18 | class Viewer; 19 | 20 | class FrameDrawer 21 | { 22 | public: 23 | FrameDrawer(Map* pMap); 24 | 25 | // Update info from the last processed frame. 26 | void Update(Tracking *pTracker); 27 | 28 | // Draw last processed frame. 29 | cv::Mat DrawFrame(); 30 | 31 | protected: 32 | 33 | void DrawTextInfo(cv::Mat &im, int nState, cv::Mat &imText); 34 | 35 | // Info of the frame to be drawn 36 | cv::Mat mIm; 37 | int N; 38 | std::vector mvCurrentKeys; 39 | std::vector mvbMap, mvbVO; 40 | bool mbOnlyTracking; 41 | int mnTracked, mnTrackedVO; 42 | std::vector mvIniKeys; 43 | std::vector mvIniMatches; 44 | int mState; 45 | 46 | int NL; 47 | std::vector mvCurrentKeyLines; 48 | std::vector mvbLineMap, mvbLineVO; 49 | std::vector mvIniKeyLines; 50 | 51 | int NSNx;int NSNz;int NSNy; 52 | 53 | std::vectormvSurfaceNormalx;std::vectormvSurfaceNormaly;std::vectormvSurfaceNormalz; 54 | 55 | int NSLx;int NSLz;int NSLy; 56 | 57 | std::vector>mvStructLinex;std::vector>mvStructLiney;std::vector>mvStructLinez; 58 | vector vCurrentKeyLines; 59 | 60 | Map* mpMap; 61 | 62 | std::mutex mMutex; 63 | }; 64 | 65 | } //namespace Planar_SLAM 66 | 67 | #endif // FRAMEDRAWER_H -------------------------------------------------------------------------------- /include/Initializer.h: -------------------------------------------------------------------------------- 1 | 2 | #ifndef INITIALIZER_H 3 | #define INITIALIZER_H 4 | 5 | #include 6 | #include "Frame.h" 7 | 8 | 9 | namespace Planar_SLAM 10 | { 11 | 12 | // THIS IS THE INITIALIZER FOR MONOCULAR SLAM. NOT USED IN THE STEREO OR RGBD CASE. 13 | class Initializer 14 | { 15 | typedef pair Match; 16 | 17 | public: 18 | 19 | // Fix the reference frame 20 | Initializer(const Frame &ReferenceFrame, float sigma = 1.0, int iterations = 200); 21 | 22 | // Computes in parallel a fundamental matrix and a homography 23 | // Selects a model and tries to recover the motion and the structure from motion 24 | bool Initialize(const Frame &CurrentFrame, const vector &vMatches12, 25 | cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated); 26 | 27 | 28 | private: 29 | 30 | void FindHomography(vector &vbMatchesInliers, float &score, cv::Mat &H21); 31 | void FindFundamental(vector &vbInliers, float &score, cv::Mat &F21); 32 | 33 | cv::Mat ComputeH21(const vector &vP1, const vector &vP2); 34 | cv::Mat ComputeF21(const vector &vP1, const vector &vP2); 35 | 36 | float CheckHomography(const cv::Mat &H21, const cv::Mat &H12, vector &vbMatchesInliers, float sigma); 37 | 38 | float CheckFundamental(const cv::Mat &F21, vector &vbMatchesInliers, float sigma); 39 | 40 | bool ReconstructF(vector &vbMatchesInliers, cv::Mat &F21, cv::Mat &K, 41 | cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated, float minParallax, int minTriangulated); 42 | 43 | bool ReconstructH(vector &vbMatchesInliers, cv::Mat &H21, cv::Mat &K, 44 | cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated, float minParallax, int minTriangulated); 45 | 46 | void Triangulate(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &P1, const cv::Mat &P2, cv::Mat &x3D); 47 | 48 | void Normalize(const vector &vKeys, vector &vNormalizedPoints, cv::Mat &T); 49 | 50 | int CheckRT(const cv::Mat &R, const cv::Mat &t, const vector &vKeys1, const vector &vKeys2, 51 | const vector &vMatches12, vector &vbInliers, 52 | const cv::Mat &K, vector &vP3D, float th2, vector &vbGood, float ¶llax); 53 | 54 | void DecomposeE(const cv::Mat &E, cv::Mat &R1, cv::Mat &R2, cv::Mat &t); 55 | 56 | 57 | // Keypoints from Reference Frame (Frame 1) 58 | vector mvKeys1; 59 | 60 | // Keypoints from Current Frame (Frame 2) 61 | vector mvKeys2; 62 | 63 | // Current Matches from Reference to Current 64 | vector mvMatches12; 65 | vector mvbMatched1; 66 | 67 | // Calibration 68 | cv::Mat mK; 69 | 70 | // Standard Deviation and Variance 71 | float mSigma, mSigma2; 72 | 73 | // Ransac max iterations 74 | int mMaxIterations; 75 | 76 | // Ransac sets 77 | vector > mvSets; 78 | 79 | }; 80 | 81 | } //namespace ORB_SLAM 82 | 83 | #endif // INITIALIZER_H 84 | -------------------------------------------------------------------------------- /include/KeyFrameDatabase.h: -------------------------------------------------------------------------------- 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 | #ifndef KEYFRAMEDATABASE_H 22 | #define KEYFRAMEDATABASE_H 23 | 24 | #include 25 | #include 26 | #include 27 | 28 | #include "KeyFrame.h" 29 | #include "Frame.h" 30 | #include "ORBVocabulary.h" 31 | 32 | #include 33 | 34 | 35 | namespace Planar_SLAM 36 | { 37 | 38 | class KeyFrame; 39 | class Frame; 40 | 41 | 42 | class KeyFrameDatabase 43 | { 44 | public: 45 | 46 | KeyFrameDatabase(const ORBVocabulary &voc); 47 | 48 | void add(KeyFrame* pKF); 49 | 50 | void erase(KeyFrame* pKF); 51 | 52 | void clear(); 53 | 54 | // Loop Detection 55 | std::vector DetectLoopCandidates(KeyFrame* pKF, float minScore); 56 | 57 | // Relocalization 58 | std::vector DetectRelocalizationCandidates(Frame* F); 59 | 60 | protected: 61 | 62 | // Associated vocabulary 63 | const ORBVocabulary* mpVoc; 64 | 65 | // Inverted file 66 | std::vector > mvInvertedFile; 67 | 68 | // Mutex 69 | std::mutex mMutex; 70 | }; 71 | 72 | } //namespace Planar_SLAM 73 | 74 | #endif 75 | -------------------------------------------------------------------------------- /include/LSDmatcher.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by lan on 17-12-26. 3 | // 4 | 5 | #ifndef ORB_SLAM2_LSDMATCHER_H 6 | #define ORB_SLAM2_LSDMATCHER_H 7 | 8 | #include "MapLine.h" 9 | #include "KeyFrame.h" 10 | #include "Frame.h" 11 | 12 | namespace Planar_SLAM 13 | { 14 | class LSDmatcher 15 | { 16 | public: 17 | static const int TH_HIGH, TH_LOW; 18 | 19 | LSDmatcher(float nnratio=0.6, bool checkOri=true); 20 | 21 | int SearchByDescriptor(KeyFrame* pKF, Frame ¤tF, std::vector &vpMapLineMatches); 22 | int SearchByDescriptor(KeyFrame* pKF, KeyFrame *pKF2, std::vector &vpMapLineMatches); 23 | int SearchByProjection(Frame &CurrentFrame, const Frame &LastFrame, const float th, const bool bMono); 24 | int SearchByProjection(Frame &F, const std::vector &vpMapLines, const float th=3); 25 | int SearchByProjection(KeyFrame* pKF, cv::Mat Scw, const std::vector &vpLines, std::vector &vpMatched, int th); 26 | int SearchBySim3(KeyFrame* pKF1, KeyFrame* pKF2, std::vector &vpMatches12, const float &s12, const cv::Mat &R12, const cv::Mat &t12, const float th); 27 | int SerachForInitialize(Frame &InitialFrame, Frame &CurrentFrame, std::vector> &LineMatches); 28 | int SearchForTriangulation(KeyFrame *pKF1, KeyFrame *pKF2, std::vector> &vMatchedPairs); 29 | 30 | // Project MapLines into KeyFrame and search for duplicated MapLines 31 | int Fuse(KeyFrame* pKF, const vector &vpMapLines, const float th=3.0); 32 | // int Fuse(KeyFrame* pKF, const vector &vpMapLines); 33 | 34 | int Fuse(KeyFrame* pKF, cv::Mat Scw, const std::vector &vpLines, float th, vector &vpReplaceLine); 35 | 36 | static int DescriptorDistance(const cv::Mat &a, const cv::Mat &b); 37 | 38 | protected: 39 | float RadiusByViewingCos(const float &viewCos); 40 | float mfNNratio; 41 | bool mbCheckOrientation; 42 | }; 43 | } 44 | 45 | 46 | #endif //ORB_SLAM2_LSDMATCHER_H 47 | -------------------------------------------------------------------------------- /include/LocalMapping.h: -------------------------------------------------------------------------------- 1 | #ifndef LOCALMAPPING_H 2 | #define LOCALMAPPING_H 3 | 4 | #include "KeyFrame.h" 5 | #include "Map.h" 6 | #include "LoopClosing.h" 7 | #include "Tracking.h" 8 | #include "KeyFrameDatabase.h" 9 | 10 | #include 11 | 12 | 13 | namespace Planar_SLAM 14 | { 15 | 16 | class Tracking; 17 | class LoopClosing; 18 | class Map; 19 | 20 | class LocalMapping 21 | { 22 | public: 23 | 24 | LocalMapping(Map* pMap, const float bMonocular); 25 | 26 | void SetLoopCloser(LoopClosing* pLoopCloser); 27 | 28 | void SetTracker(Tracking* pTracker); 29 | 30 | // Main function 31 | void Run(); 32 | 33 | void InsertKeyFrame(KeyFrame* pKF); 34 | 35 | // Thread Synch 36 | void RequestStop(); 37 | void RequestReset(); 38 | bool Stop(); 39 | void Release(); 40 | bool isStopped(); 41 | bool stopRequested(); 42 | bool AcceptKeyFrames(); 43 | void SetAcceptKeyFrames(bool flag); 44 | bool SetNotStop(bool flag); 45 | 46 | void InterruptBA(); 47 | 48 | void RequestFinish(); 49 | bool isFinished(); 50 | 51 | int KeyframesInQueue(){ 52 | unique_lock lock(mMutexNewKFs); 53 | return mlNewKeyFrames.size(); 54 | } 55 | 56 | protected: 57 | 58 | bool CheckNewKeyFrames(); 59 | void ProcessNewKeyFrame(); 60 | void CreateNewMapPoints(); 61 | void CreateNewMapLines1(); 62 | void CreateNewMapLines2(); 63 | 64 | void MapPointCulling(); 65 | void SearchInNeighbors(); 66 | 67 | void MapLineCulling(); 68 | void MapPlaneCulling(); 69 | 70 | void KeyFrameCulling(); 71 | 72 | cv::Mat ComputeF12(KeyFrame* &pKF1, KeyFrame* &pKF2); 73 | 74 | cv::Mat SkewSymmetricMatrix(const cv::Mat &v); 75 | 76 | bool mbMonocular; 77 | 78 | void ResetIfRequested(); 79 | bool mbResetRequested; 80 | std::mutex mMutexReset; 81 | 82 | bool CheckFinish(); 83 | void SetFinish(); 84 | bool mbFinishRequested; 85 | bool mbFinished; 86 | std::mutex mMutexFinish; 87 | 88 | Map* mpMap; 89 | 90 | LoopClosing* mpLoopCloser; 91 | Tracking* mpTracker; 92 | 93 | std::list mlNewKeyFrames; 94 | 95 | KeyFrame* mpCurrentKeyFrame; 96 | 97 | std::list mlpRecentAddedMapPoints; 98 | 99 | std::list mlpRecentAddedMapLines; 100 | 101 | std::list mlpRecentAddedMapPlanes; 102 | 103 | std::mutex mMutexNewKFs; 104 | 105 | bool mbAbortBA; 106 | 107 | bool mbStopped; 108 | bool mbStopRequested; 109 | bool mbNotStop; 110 | std::mutex mMutexStop; 111 | 112 | bool mbAcceptKeyFrames; 113 | std::mutex mMutexAccept; 114 | }; 115 | 116 | } //namespace Planar_SLAM 117 | 118 | #endif // LOCALMAPPING_H 119 | -------------------------------------------------------------------------------- /include/Map.h: -------------------------------------------------------------------------------- 1 | #ifndef MAP_H 2 | #define MAP_H 3 | 4 | #include "MapPoint.h" 5 | #include "KeyFrame.h" 6 | #include 7 | #include 8 | #include 9 | 10 | #include 11 | 12 | 13 | #include "MapLine.h" 14 | 15 | #include "MapPlane.h" 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | #include 22 | 23 | namespace Planar_SLAM 24 | { 25 | 26 | class MapPoint; 27 | class KeyFrame; 28 | class MapLine; 29 | class MapPlane; 30 | class Frame; 31 | 32 | class Map 33 | { 34 | public: 35 | typedef pcl::PointXYZRGB PointT; 36 | typedef pcl::PointCloud PointCloud; 37 | 38 | Map(); 39 | 40 | void AddKeyFrame(KeyFrame* pKF); 41 | void AddMapPoint(MapPoint* pMP); 42 | void EraseMapPoint(MapPoint* pMP); 43 | void EraseKeyFrame(KeyFrame* pKF); 44 | void SetReferenceMapPoints(const std::vector &vpMPs); 45 | 46 | void InformNewBigChange(); 47 | int GetLastBigChangeIdx(); 48 | void AddMapLine(MapLine* pML); 49 | void EraseMapLine(MapLine* pML); 50 | void SetReferenceMapLines(const std::vector &vpMLs); 51 | 52 | std::vector GetAllKeyFrames(); 53 | std::vector GetAllMapPoints(); 54 | std::vector GetReferenceMapPoints(); 55 | 56 | std::vector GetAllMapLines(); 57 | std::vector GetReferenceMapLines(); 58 | long unsigned int MapLinesInMap(); 59 | 60 | long unsigned int MapPointsInMap(); 61 | long unsigned KeyFramesInMap(); 62 | 63 | long unsigned int GetMaxKFid(); 64 | 65 | void clear(); 66 | 67 | vector mvpKeyFrameOrigins; 68 | 69 | std::mutex mMutexMapUpdate; 70 | 71 | // This avoid that two points are created simultaneously in separate threads (id conflict) 72 | std::mutex mMutexPointCreation; 73 | std::mutex mMutexLineCreation; 74 | 75 | void AddMapPlane(MapPlane* pMP); 76 | void EraseMapPlane(MapPlane *pMP); 77 | std::vector GetAllMapPlanes(); 78 | long unsigned int MapPlanesInMap(); 79 | 80 | cv::Mat FindManhattan(Frame &pF, const float &verTh, bool out = false); 81 | 82 | void FlagMatchedPlanePoints(Planar_SLAM::Frame &pF, const float &dTh); 83 | 84 | double PointDistanceFromPlane(const cv::Mat& plane, PointCloud::Ptr boundry, bool out = false); 85 | 86 | protected: 87 | std::set mspMapPoints; 88 | 89 | std::set mspMapLines; 90 | 91 | std::set mspMapPlanes; 92 | 93 | std::set mspKeyFrames; 94 | 95 | std::vector mvpReferenceMapPoints; 96 | std::vector mvpReferenceMapLines; 97 | long unsigned int mnMaxKFid; 98 | 99 | // Index related to a big change in the map (loop closure, global BA) 100 | int mnBigChangeIdx; 101 | std::mutex mMutexMap; 102 | }; 103 | 104 | } //namespace Planar_SLAM 105 | 106 | #endif // MAP_H 107 | -------------------------------------------------------------------------------- /include/MapDrawer.h: -------------------------------------------------------------------------------- 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 | #ifndef MAPDRAWER_H 22 | #define MAPDRAWER_H 23 | 24 | #include"Map.h" 25 | #include"MapPoint.h" 26 | #include"KeyFrame.h" 27 | #include 28 | 29 | #include 30 | 31 | namespace Planar_SLAM 32 | { 33 | 34 | class MapDrawer 35 | { 36 | public: 37 | MapDrawer(Map* pMap, const string &strSettingPath); 38 | 39 | Map* mpMap; 40 | 41 | void DrawMapPoints(); 42 | void DrawMapLines(); 43 | void DrawMapPlanes(); 44 | void DrawKeyFrames(const bool bDrawKF, const bool bDrawGraph); 45 | void DrawCurrentCamera(pangolin::OpenGlMatrix &Twc); 46 | void SetCurrentCameraPose(const cv::Mat &Tcw); 47 | void SetReferenceKeyFrame(KeyFrame *pKF); 48 | void GetCurrentOpenGLCameraMatrix(pangolin::OpenGlMatrix &M); 49 | 50 | private: 51 | float mLineWidth; //线特征的尺寸 52 | float mKeyFrameSize; 53 | float mKeyFrameLineWidth; 54 | float mGraphLineWidth; 55 | float mPointSize; 56 | float mCameraSize; 57 | float mCameraLineWidth; 58 | 59 | cv::Mat mCameraPose; 60 | 61 | std::mutex mMutexCamera; 62 | }; 63 | 64 | } //namespace ORB_SLAM 65 | 66 | #endif // MAPDRAWER_H 67 | -------------------------------------------------------------------------------- /include/MeshViewer.h: -------------------------------------------------------------------------------- 1 | #ifndef POINTCLOUDMAPPING_H 2 | #define POINTCLOUDMAPPING_H 3 | 4 | #include "System.h" 5 | #include "KeyFrame.h" 6 | #include "Map.h" 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | 19 | 20 | namespace Planar_SLAM { 21 | class KeyFrame; 22 | class Map; 23 | class MeshViewer { 24 | public: 25 | typedef pcl::PointXYZRGBA PointT; 26 | typedef pcl::PointCloud PointCloud; 27 | 28 | MeshViewer(Map* map); 29 | 30 | // 插入一个keyframe,会更新一次地图 31 | void insertKeyFrame(KeyFrame *kf, cv::Mat &color, cv::Mat &depth); 32 | 33 | void shutdown(); 34 | 35 | void viewer(); 36 | 37 | void print(); 38 | void SaveMeshModel(const string &filename); 39 | 40 | protected: 41 | Map* mMap; 42 | 43 | void AddKFPointCloud(KeyFrame *pKF); 44 | 45 | PointCloud::Ptr mAllCloudPoints; 46 | 47 | shared_ptr viewerThread; 48 | 49 | bool shutDownFlag = false; 50 | mutex shutDownMutex; 51 | 52 | bool printFlag = false; 53 | mutex printMutex; 54 | 55 | condition_variable keyFrameUpdated; 56 | mutex keyFrameUpdateMutex; 57 | 58 | // data to generate point clouds 59 | vector mvKeyframes; 60 | 61 | mutex keyframeMutex; 62 | uint16_t lastKeyframeSize = 0; 63 | 64 | }; 65 | } 66 | #endif // POINTCLOUDMAPPING_H 67 | -------------------------------------------------------------------------------- /include/ORBVocabulary.h: -------------------------------------------------------------------------------- 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 | #ifndef ORBVOCABULARY_H 23 | #define ORBVOCABULARY_H 24 | 25 | #include"Thirdparty/DBoW2/DBoW2/FORB.h" 26 | #include"Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h" 27 | 28 | namespace Planar_SLAM 29 | { 30 | 31 | typedef DBoW2::TemplatedVocabulary 32 | ORBVocabulary; 33 | 34 | } //namespace ORB_SLAM 35 | 36 | #endif // ORBVOCABULARY_H 37 | -------------------------------------------------------------------------------- /include/Optimizer.h: -------------------------------------------------------------------------------- 1 | #ifndef OPTIMIZER_H 2 | #define OPTIMIZER_H 3 | 4 | #include "Map.h" 5 | #include "MapPoint.h" 6 | #include "KeyFrame.h" 7 | #include "LoopClosing.h" 8 | #include "Frame.h" 9 | 10 | #include "Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h" 11 | #include "EdgeLine.h" 12 | namespace Planar_SLAM 13 | { 14 | 15 | class LoopClosing; 16 | 17 | class Optimizer 18 | { 19 | typedef pcl::PointXYZRGB PointT; 20 | typedef pcl::PointCloud PointCloud; 21 | public: 22 | void static BundleAdjustment(const vector &vpKFs, const vector &vpMP, const vector &vpML, 23 | const vector &vpMPL, int nIterations = 5, bool* pbStopFlag=NULL, const unsigned long nLoopKF=0, 24 | const bool bRobust = true); 25 | 26 | void static GlobalBundleAdjustemnt(Map* pMap, int nIterations=5, bool *pbStopFlag=NULL, 27 | const unsigned long nLoopKF=0, const bool bRobust = true); 28 | void static LocalBundleAdjustment(KeyFrame* pKF, bool *pbStopFlag, Map *pMap); 29 | 30 | int static PoseOptimizationPointsOnly(Frame* pFrame); 31 | int static PoseOptimization(Frame *pFrame); 32 | 33 | // if bFixScale is true, 6DoF optimization (stereo,rgbd), 7DoF otherwise (mono) 34 | void static OptimizeEssentialGraph(Map* pMap, KeyFrame* pLoopKF, KeyFrame* pCurKF, 35 | const LoopClosing::KeyFrameAndPose &NonCorrectedSim3, 36 | const LoopClosing::KeyFrameAndPose &CorrectedSim3, 37 | const map > &LoopConnections, 38 | const bool &bFixScale); 39 | 40 | // if bFixScale is true, optimize SE3 (stereo,rgbd), Sim3 otherwise (mono) 41 | 42 | static int OptimizeSim3(KeyFrame *pKF1, KeyFrame *pKF2, vector &vpMatches1, g2o::Sim3 &g2oS12, const float th2, const bool bFixScale); 43 | 44 | int static TranslationOptimization(Frame* pFrame); 45 | }; 46 | 47 | } //namespace Planar_SLAM 48 | 49 | #endif // OPTIMIZER_H 50 | -------------------------------------------------------------------------------- /include/PlaneExtractor.h: -------------------------------------------------------------------------------- 1 | #ifndef PLANEDETECTION_H 2 | #define PLANEDETECTION_H 3 | 4 | #include 5 | #include "opencv2/opencv.hpp" 6 | #include 7 | #include 8 | #include 9 | #include "include/peac/AHCPlaneFitter.hpp" 10 | #include 11 | 12 | typedef Eigen::Vector3d VertexType; 13 | 14 | #ifdef __linux__ 15 | #define _isnan(x) isnan(x) 16 | #endif 17 | 18 | struct ImagePointCloud 19 | { 20 | std::vector vertices; // 3D vertices 21 | int w, h; 22 | 23 | inline int width() const { return w; } 24 | inline int height() const { return h; } 25 | inline bool get(const int row, const int col, double &x, double &y, double &z) const { 26 | const int pixIdx = row * w + col; 27 | z = vertices[pixIdx][2]; 28 | // Remove points with 0 or invalid depth in case they are detected as a plane 29 | if (z == 0 || std::_isnan(z)) return false; 30 | x = vertices[pixIdx][0]; 31 | y = vertices[pixIdx][1]; 32 | return true; 33 | } 34 | }; 35 | 36 | class PlaneDetection 37 | { 38 | public: 39 | ImagePointCloud cloud; 40 | ahc::PlaneFitter< ImagePointCloud > plane_filter; 41 | std::vector> plane_vertices_; // vertex indices each plane contains 42 | cv::Mat seg_img_; // segmentation image 43 | cv::Mat color_img_; // input color image 44 | int plane_num_; 45 | 46 | public: 47 | PlaneDetection(); 48 | ~PlaneDetection(); 49 | 50 | bool readColorImage(cv::Mat RGBImg); 51 | 52 | bool readDepthImage(cv::Mat depthImg, cv::Mat &K, float kScaleFactor); 53 | 54 | void runPlaneDetection(int kDepthHeight, int kDepthWidth); 55 | 56 | }; 57 | 58 | 59 | #endif -------------------------------------------------------------------------------- /include/PlaneMatcher.h: -------------------------------------------------------------------------------- 1 | #ifndef ORB_SLAM2_PLANEMATCHER_H 2 | #define ORB_SLAM2_PLANEMATCHER_H 3 | 4 | #include "MapPlane.h" 5 | #include "KeyFrame.h" 6 | #include "Frame.h" 7 | #include 8 | #include 9 | 10 | namespace Planar_SLAM { 11 | class PlaneMatcher { 12 | public: 13 | typedef pcl::PointXYZRGB PointT; 14 | typedef pcl::PointCloud PointCloud; 15 | 16 | PlaneMatcher(float dTh = 0.1, float aTh = 0.86, float verTh = 0.08716, float parTh = 0.9962); 17 | 18 | int SearchMapByCoefficients(Frame &pF, const std::vector &vpMapPlanes); 19 | 20 | int Fuse(KeyFrame *pKF, const std::vector &vpMapPlanes); 21 | 22 | int Fuse(KeyFrame* pKF, cv::Mat Scw, const std::vector &vpPlanes, const std::vector &vpVerticalPlanes, 23 | const std::vector &vpParallelPlanes, vector &vpReplacePlane, 24 | vector &vpReplaceVerticalPlane, vector &vpReplaceParallelPlane); 25 | 26 | protected: 27 | float dTh, aTh, verTh, parTh; 28 | 29 | double PointDistanceFromPlane(const cv::Mat &plane, PointCloud::Ptr pointCloud); 30 | }; 31 | } 32 | 33 | 34 | #endif //Planar_SLAM -------------------------------------------------------------------------------- /include/Viewer.h: -------------------------------------------------------------------------------- 1 | #ifndef VIEWER_H 2 | #define VIEWER_H 3 | 4 | #include "FrameDrawer.h" 5 | #include "MapDrawer.h" 6 | #include "Tracking.h" 7 | #include "System.h" 8 | 9 | #include 10 | 11 | namespace Planar_SLAM 12 | { 13 | 14 | class Tracking; 15 | class FrameDrawer; 16 | class MapDrawer; 17 | class System; 18 | 19 | class Viewer 20 | { 21 | public: 22 | Viewer(System* pSystem, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Tracking *pTracking, const string &strSettingPath); 23 | 24 | // Main thread function. Draw points, lines, planes, keyframes, the current camera pose and the last processed 25 | // frame. Drawing is refreshed according to the camera fps. We use Pangolin. 26 | void RunWithPLP(); 27 | void RequestFinish(); 28 | 29 | void RequestStop(); 30 | 31 | bool isFinished(); 32 | 33 | bool isStopped(); 34 | 35 | void Release(); 36 | 37 | private: 38 | 39 | bool Stop(); 40 | 41 | System* mpSystem; 42 | FrameDrawer* mpFrameDrawer; 43 | MapDrawer* mpMapDrawer; 44 | Tracking* mpTracker; 45 | 46 | // 1/fps in ms 47 | double mT; 48 | float mImageWidth, mImageHeight; 49 | 50 | float mViewpointX, mViewpointY, mViewpointZ, mViewpointF; 51 | 52 | bool CheckFinish(); 53 | void SetFinish(); 54 | bool mbFinishRequested; 55 | bool mbFinished; 56 | std::mutex mMutexFinish; 57 | 58 | bool mbStopped; 59 | bool mbStopRequested; 60 | std::mutex mMutexStop; 61 | 62 | }; 63 | 64 | } 65 | 66 | 67 | #endif // VIEWER_H 68 | 69 | 70 | -------------------------------------------------------------------------------- /include/auxiliar.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by lan on 17-12-18. 3 | // 4 | 5 | #pragma once 6 | 7 | #include 8 | 9 | #include 10 | #include 11 | #include 12 | 13 | #include 14 | 15 | #include 16 | #include 17 | #include 18 | 19 | typedef Eigen::Matrix Vector6d; 20 | typedef Eigen::Matrix Matrix6d; 21 | 22 | struct compare_descriptor_by_NN_dist 23 | { 24 | inline bool operator()(const std::vector& a, const std::vector& b){ 25 | return ( a[0].distance < b[0].distance); 26 | } 27 | }; 28 | 29 | struct conpare_descriptor_by_NN12_dist 30 | { 31 | inline bool operator()(const std::vector& a, const std::vector& b){ 32 | return ((a[1].distance - a[0].distance) > (b[1].distance - b[0].distance)); 33 | } 34 | }; 35 | 36 | struct sort_descriptor_by_queryIdx 37 | { 38 | inline bool operator()(const std::vector& a, const std::vector& b){ 39 | return ( a[0].queryIdx < b[0].queryIdx ); 40 | } 41 | }; 42 | 43 | struct sort_lines_by_response 44 | { 45 | inline bool operator()(const cv::line_descriptor::KeyLine& a, const cv::line_descriptor::KeyLine& b){ 46 | return ( a.response > b.response ); 47 | } 48 | }; 49 | 50 | inline cv::Mat SkewSymmetricMatrix(const cv::Mat &v) 51 | { 52 | return (cv::Mat_(3,3) << 0, -v.at(2), v.at(1), 53 | v.at(2), 0,-v.at(0), 54 | -v.at(1), v.at(0), 0); 55 | } 56 | 57 | inline double vector_mad(std::vector residues) 58 | { 59 | if(residues.size()!=0) 60 | { 61 | // Return the standard deviation of vector with MAD estimation 62 | int n_samples = residues.size(); 63 | sort(residues.begin(), residues.end()); 64 | double median = residues[n_samples/2]; 65 | for(int i=0; i 31 | #else 32 | #include 33 | #endif 34 | 35 | namespace ahc { 36 | #ifndef USE_BOOST_SHARED_PTR 37 | using std::shared_ptr; 38 | #else 39 | using boost::shared_ptr; 40 | #endif 41 | } -------------------------------------------------------------------------------- /include/peac/AHCUtils.hpp: -------------------------------------------------------------------------------- 1 | // 2 | // Copyright 2014 Mitsubishi Electric Research Laboratories All 3 | // Rights Reserved. 4 | // 5 | // Permission to use, copy and modify this software and its 6 | // documentation without fee for educational, research and non-profit 7 | // purposes, is hereby granted, provided that the above copyright 8 | // notice, this paragraph, and the following three paragraphs appear 9 | // in all copies. 10 | // 11 | // To request permission to incorporate this software into commercial 12 | // products contact: Director; Mitsubishi Electric Research 13 | // Laboratories (MERL); 201 Broadway; Cambridge, MA 02139. 14 | // 15 | // IN NO EVENT SHALL MERL BE LIABLE TO ANY PARTY FOR DIRECT, 16 | // INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING 17 | // LOST PROFITS, ARISING OUT OF THE USE OF THIS SOFTWARE AND ITS 18 | // DOCUMENTATION, EVEN IF MERL HAS BEEN ADVISED OF THE POSSIBILITY OF 19 | // SUCH DAMAGES. 20 | // 21 | // MERL SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT 22 | // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 23 | // FOR A PARTICULAR PURPOSE. THE SOFTWARE PROVIDED HEREUNDER IS ON AN 24 | // "AS IS" BASIS, AND MERL HAS NO OBLIGATIONS TO PROVIDE MAINTENANCE, 25 | // SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS. 26 | // 27 | #pragma once 28 | 29 | #include 30 | #include "opencv2/opencv.hpp" 31 | 32 | namespace ahc { 33 | namespace utils { 34 | 35 | /** 36 | * \brief Generate pseudo-colors 37 | * 38 | * \param [in] ncolors number of colors to be generated (will be reset to 10 if ncolors<=0) 39 | * \return a vector of cv::Vec3b 40 | */ 41 | inline std::vector pseudocolor(int ncolors) { 42 | srand((unsigned int)time(0)); 43 | if(ncolors<=0) ncolors=10; 44 | std::vector ret(ncolors); 45 | for(int i=0; iscale = scale; 69 | startTick=0; 70 | } 71 | 72 | /** 73 | start record time, similar to matlab function "tic"; 74 | 75 | @return the start tick 76 | */ 77 | inline double tic() { 78 | return startTick = (double)cv::getTickCount(); 79 | } 80 | 81 | /** 82 | return duration from last tic, in (second * scale), similar to matlab function "toc" 83 | 84 | @return duration from last tic, in (second * scale) 85 | */ 86 | inline double toc() { 87 | return ((double)cv::getTickCount()-startTick)/cv::getTickFrequency() * scale; 88 | } 89 | inline double toc(std::string tag) { 90 | double time=toc(); 91 | std::cout< 30 | 31 | class DisjointSet 32 | { 33 | private: 34 | std::vector parent_; 35 | std::vector size_; 36 | 37 | public: 38 | DisjointSet(const int n) 39 | { 40 | parent_.reserve(n); 41 | size_.reserve(n); 42 | 43 | for (int i=0; i 38 | #include 39 | #endif 40 | 41 | #include 42 | #include 43 | 44 | namespace LA { 45 | //s[0]<=s[1]<=s[2], V[:][i] correspond to s[i] 46 | inline static bool eig33sym(double K[3][3], double s[3], double V[3][3]) 47 | { 48 | #ifdef USE_DSYEVH3 49 | double tmpV[3][3]; 50 | if(dsyevh3(K, tmpV, s)!=0) return false; 51 | 52 | int order[]={0,1,2}; 53 | for(int i=0; i<3; ++i) { 54 | for(int j=i+1; j<3; ++j) { 55 | if(s[i]>s[j]) { 56 | double tmp=s[i]; 57 | s[i]=s[j]; 58 | s[j]=tmp; 59 | int tmpor=order[i]; 60 | order[i]=order[j]; 61 | order[j]=tmpor; 62 | } 63 | } 64 | } 65 | V[0][0]=tmpV[0][order[0]]; V[0][1]=tmpV[0][order[1]]; V[0][2]=tmpV[0][order[2]]; 66 | V[1][0]=tmpV[1][order[0]]; V[1][1]=tmpV[1][order[1]]; V[1][2]=tmpV[1][order[2]]; 67 | V[2][0]=tmpV[2][order[0]]; V[2][1]=tmpV[2][order[1]]; V[2][2]=tmpV[2][order[2]]; 68 | #else 69 | //below we did not specify row major since it does not matter, K==K' 70 | Eigen::SelfAdjointEigenSolver es( 71 | Eigen::Map(K[0], 3, 3) ); 72 | Eigen::Map(s,3,1)=es.eigenvalues(); 73 | //below we need to specify row major since V!=V' 74 | Eigen::Map>(V[0],3,3)=es.eigenvectors(); 75 | #endif 76 | return true; 77 | } 78 | }//end of namespace LA -------------------------------------------------------------------------------- /src/Config.cc: -------------------------------------------------------------------------------- 1 | // 2 | // Created by fishmarch on 19-5-24. 3 | // 4 | 5 | #include "Config.h" 6 | 7 | namespace Planar_SLAM{ 8 | void Config::SetParameterFile( const std::string& filename ) 9 | { 10 | if ( mConfig == nullptr ) 11 | mConfig = shared_ptr(new Config); 12 | mConfig->mFile = cv::FileStorage( filename.c_str(), cv::FileStorage::READ ); 13 | if ( !mConfig->mFile.isOpened()) 14 | { 15 | std::cerr<<"parameter file "<< filename <<" does not exist."<mFile.release(); 17 | return; 18 | } 19 | } 20 | 21 | Config::~Config() 22 | { 23 | if ( mFile.isOpened() ) 24 | mFile.release(); 25 | } 26 | 27 | shared_ptr Config::mConfig = nullptr; 28 | } -------------------------------------------------------------------------------- /src/LSDextractor.cpp: -------------------------------------------------------------------------------- 1 | #include "LSDextractor.h" 2 | #include 3 | 4 | using namespace std; 5 | using namespace cv; 6 | using namespace cv::line_descriptor; 7 | using namespace Eigen; 8 | 9 | namespace Planar_SLAM { 10 | LineSegment::LineSegment() {} 11 | 12 | void LineSegment::ExtractLineSegment(const Mat &img, vector &keylines, Mat &ldesc, 13 | vector &keylineFunctions, float scale, int numOctaves) { 14 | Ptr lbd = BinaryDescriptor::createBinaryDescriptor(); 15 | Ptr lsd = line_descriptor::LSDDetector::createLSDDetector(); 16 | lsd->detect(img, keylines, scale, numOctaves); 17 | 18 | unsigned int lsdNFeatures = 40; 19 | 20 | // filter lines 21 | if (keylines.size() > lsdNFeatures) { 22 | sort(keylines.begin(), keylines.end(), sort_lines_by_response()); 23 | keylines.resize(lsdNFeatures); 24 | for (unsigned int i = 0; i < lsdNFeatures; i++) 25 | keylines[i].class_id = i; 26 | } 27 | 28 | lbd->compute(img, keylines, ldesc); 29 | 30 | for (vector::iterator it = keylines.begin(); it != keylines.end(); ++it) { 31 | Vector3d sp_l; 32 | sp_l << it->startPointX, it->startPointY, 1.0; 33 | Vector3d ep_l; 34 | ep_l << it->endPointX, it->endPointY, 1.0; 35 | Vector3d lineF; 36 | lineF << sp_l.cross(ep_l); 37 | lineF = lineF / sqrt(lineF(0) * lineF(0) + lineF(1) * lineF(1) + lineF(2) * lineF(2)); 38 | keylineFunctions.push_back(lineF); 39 | } 40 | } 41 | } -------------------------------------------------------------------------------- /src/PlaneExtractor.cpp: -------------------------------------------------------------------------------- 1 | #include "PlaneExtractor.h" 2 | using namespace std; 3 | using namespace cv; 4 | using namespace Eigen; 5 | 6 | PlaneDetection::PlaneDetection() { } 7 | 8 | PlaneDetection::~PlaneDetection() 9 | { 10 | cloud.vertices.clear(); 11 | seg_img_.release(); 12 | color_img_.release(); 13 | } 14 | 15 | bool PlaneDetection::readColorImage(cv::Mat RGBImg) 16 | { 17 | color_img_ = RGBImg; 18 | if (color_img_.empty() || color_img_.depth() != CV_8U) 19 | { 20 | cout << "ERROR: cannot read color image. No such a file, or the image format is not 8UC3" << endl; 21 | return false; 22 | } 23 | return true; 24 | } 25 | 26 | bool PlaneDetection::readDepthImage(cv::Mat depthImg, cv::Mat &K, float kScaleFactor) 27 | { 28 | auto width = depthImg.cols; 29 | auto height = depthImg.rows; 30 | cloud.vertices.resize(height * width); 31 | cloud.w = width; 32 | cloud.h = height; 33 | cv::Mat depth_img = depthImg; 34 | if (depth_img.empty() || depth_img.depth() != CV_16U) 35 | { 36 | cout << "WARNING: cannot read depth image. No such a file, or the image format is not 16UC1" << endl; 37 | return false; 38 | } 39 | int rows = depth_img.rows, cols = depth_img.cols; 40 | int vertex_idx = 0; 41 | for (int i = 0; i < rows; i+=1) 42 | { 43 | for (int j = 0; j < cols; j+=1) 44 | { 45 | double z = (double)(depth_img.at(i, j)) * kScaleFactor; 46 | if (_isnan(z)) 47 | { 48 | cloud.vertices[vertex_idx++] = VertexType(0, 0, z); 49 | continue; 50 | } 51 | double x = ((double)j - K.at(0, 2)) * z / K.at(0, 0); 52 | double y = ((double)i - K.at(1, 2)) * z / K.at(1, 1); 53 | cloud.vertices[vertex_idx++] = VertexType(x, y, z); 54 | } 55 | } 56 | return true; 57 | } 58 | 59 | void PlaneDetection::runPlaneDetection(int kDepthHeight, int kDepthWidth) 60 | { 61 | seg_img_ = cv::Mat(kDepthHeight, kDepthWidth, CV_8UC3); 62 | plane_filter.run(&cloud, &plane_vertices_, &seg_img_); 63 | 64 | plane_num_ = (int)plane_vertices_.size(); 65 | } 66 | -------------------------------------------------------------------------------- /src/PlaneMatcher.cpp: -------------------------------------------------------------------------------- 1 | #include "PlaneMatcher.h" 2 | 3 | using namespace std; 4 | using namespace cv; 5 | using namespace Eigen; 6 | 7 | namespace Planar_SLAM 8 | { 9 | PlaneMatcher::PlaneMatcher(float dTh, float aTh, float verTh, float parTh):dTh(dTh), aTh(aTh), verTh(verTh), parTh(parTh) {} 10 | int PlaneMatcher::SearchMapByCoefficients(Frame &pF, const std::vector &vpMapPlanes) { 11 | pF.mbNewPlane = false; 12 | 13 | int nmatches = 0; 14 | 15 | for (int i = 0; i < pF.mnPlaneNum; ++i) { 16 | 17 | cv::Mat pM = pF.ComputePlaneWorldCoeff(i); 18 | 19 | float ldTh = dTh; 20 | float lverTh = verTh; 21 | float lparTh = parTh; 22 | 23 | bool found = false; 24 | for (auto vpMapPlane : vpMapPlanes) { 25 | if (vpMapPlane->isBad()) 26 | continue; 27 | 28 | cv::Mat pW = vpMapPlane->GetWorldPos(); 29 | 30 | float angle = pM.at(0, 0) * pW.at(0, 0) + 31 | pM.at(1, 0) * pW.at(1, 0) + 32 | pM.at(2, 0) * pW.at(2, 0); 33 | 34 | // associate plane 35 | if ((angle > aTh || angle < -aTh)) 36 | { 37 | double dis = PointDistanceFromPlane(pM, vpMapPlane->mvPlanePoints); 38 | if(dis < ldTh) { 39 | ldTh = dis; 40 | pF.mvpMapPlanes[i] = static_cast(nullptr); 41 | pF.mvpMapPlanes[i] = vpMapPlane; 42 | found = true; 43 | continue; 44 | } 45 | } 46 | 47 | // vertical planes 48 | if (angle < lverTh && angle > -lverTh) { 49 | lverTh = abs(angle); 50 | pF.mvpVerticalPlanes[i] = static_cast(nullptr); 51 | pF.mvpVerticalPlanes[i] = vpMapPlane; 52 | continue; 53 | } 54 | 55 | //parallel planes 56 | if (angle > lparTh || angle < -lparTh) { 57 | lparTh = abs(angle); 58 | pF.mvpParallelPlanes[i] = static_cast(nullptr); 59 | pF.mvpParallelPlanes[i] = vpMapPlane; 60 | } 61 | } 62 | 63 | if (found) { 64 | nmatches++; 65 | } 66 | } 67 | 68 | return nmatches; 69 | } 70 | double PlaneMatcher::PointDistanceFromPlane(const cv::Mat &plane, PointCloud::Ptr pointCloud) { 71 | double res = 100; 72 | for(auto p : pointCloud->points){ 73 | double dis = abs(plane.at(0, 0) * p.x + 74 | plane.at(1, 0) * p.y + 75 | plane.at(2, 0) * p.z + 76 | plane.at(3, 0)); 77 | if(dis < res) 78 | res = dis; 79 | } 80 | return res; 81 | } 82 | } 83 | --------------------------------------------------------------------------------