├── .DS_Store
├── README.md
├── orbslamios.xcodeproj
├── project.pbxproj
├── project.xcworkspace
│ ├── contents.xcworkspacedata
│ └── xcuserdata
│ │ └── Yinggx.xcuserdatad
│ │ └── UserInterfaceState.xcuserstate
└── xcuserdata
│ └── Yinggx.xcuserdatad
│ ├── xcdebugger
│ └── Breakpoints_v2.xcbkptlist
│ └── xcschemes
│ ├── orbslamios.xcscheme
│ └── xcschememanagement.plist
├── orbslamios
├── .DS_Store
├── AppDelegate.h
├── AppDelegate.m
├── Assets.xcassets
│ └── AppIcon.appiconset
│ │ └── Contents.json
├── Base.lproj
│ ├── LaunchScreen.storyboard
│ └── Main.storyboard
├── Info.plist
├── ORB_SLAM
│ ├── .DS_Store
│ ├── Thirdparty
│ │ ├── .DS_Store
│ │ ├── DBoW2
│ │ │ ├── .DS_Store
│ │ │ ├── CMakeLists.txt
│ │ │ ├── DBoW2
│ │ │ │ ├── BowVector.cpp
│ │ │ │ ├── BowVector.h
│ │ │ │ ├── FClass.h
│ │ │ │ ├── FORB.cpp
│ │ │ │ ├── FORB.h
│ │ │ │ ├── FeatureVector.cpp
│ │ │ │ ├── FeatureVector.h
│ │ │ │ ├── LICENSE.txt
│ │ │ │ ├── ScoringObject.cpp
│ │ │ │ ├── ScoringObject.h
│ │ │ │ └── TemplatedVocabulary.h
│ │ │ ├── DUtils
│ │ │ │ ├── LICENSE.txt
│ │ │ │ ├── Random.cpp
│ │ │ │ ├── Random.h
│ │ │ │ ├── Timestamp.cpp
│ │ │ │ └── Timestamp.h
│ │ │ └── LICENSE.txt
│ │ └── g2o
│ │ │ ├── .DS_Store
│ │ │ ├── config.h
│ │ │ └── g2o
│ │ │ ├── .DS_Store
│ │ │ ├── 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
│ ├── include
│ │ ├── Converter.h
│ │ ├── Frame.h
│ │ ├── FrameDrawer.h
│ │ ├── Initializer.h
│ │ ├── KeyFrame.h
│ │ ├── KeyFrameDatabase.h
│ │ ├── LocalMapping.h
│ │ ├── LoopClosing.h
│ │ ├── Map.h
│ │ ├── MapDrawer.h
│ │ ├── MapPoint.h
│ │ ├── ORBVocabulary.h
│ │ ├── ORBextractor.h
│ │ ├── ORBmatcher.h
│ │ ├── Optimizer.h
│ │ ├── PnPsolver.h
│ │ ├── Sim3Solver.h
│ │ ├── System.h
│ │ ├── Tracking.h
│ │ └── Viewer.h
│ └── src
│ │ ├── Converter.cc
│ │ ├── Frame.cc
│ │ ├── FrameDrawer.cc
│ │ ├── Initializer.cc
│ │ ├── KeyFrame.cc
│ │ ├── KeyFrameDatabase.cc
│ │ ├── LocalMapping.cc
│ │ ├── LoopClosing.cc
│ │ ├── Map.cc
│ │ ├── MapDrawer.cc
│ │ ├── MapPoint.cc
│ │ ├── ORBextractor.cc
│ │ ├── ORBmatcher.cc
│ │ ├── Optimizer.cc
│ │ ├── PnPsolver.cc
│ │ ├── Sim3Solver.cc
│ │ ├── System.cc
│ │ ├── Tracking.cc
│ │ └── Viewer.cc
├── ViewController.h
├── ViewController.mm
├── eigen
│ ├── .DS_Store
│ └── Eigen
│ │ ├── .DS_Store
│ │ ├── Array
│ │ ├── CMakeLists.txt
│ │ ├── Cholesky
│ │ ├── CholmodSupport
│ │ ├── Core
│ │ ├── Dense
│ │ ├── Eigen
│ │ ├── Eigen2Support
│ │ ├── Eigenvalues
│ │ ├── Geometry
│ │ ├── Householder
│ │ ├── IterativeLinearSolvers
│ │ ├── Jacobi
│ │ ├── LU
│ │ ├── LeastSquares
│ │ ├── MetisSupport
│ │ ├── OrderingMethods
│ │ ├── PaStiXSupport
│ │ ├── PardisoSupport
│ │ ├── QR
│ │ ├── QtAlignedMalloc
│ │ ├── SPQRSupport
│ │ ├── SVD
│ │ ├── Sparse
│ │ ├── SparseCholesky
│ │ ├── SparseCore
│ │ ├── SparseLU
│ │ ├── SparseQR
│ │ ├── StdDeque
│ │ ├── StdList
│ │ ├── StdVector
│ │ ├── SuperLUSupport
│ │ ├── UmfPackSupport
│ │ └── src
│ │ ├── .DS_Store
│ │ ├── CMakeLists.txt
│ │ ├── Cholesky
│ │ ├── CMakeLists.txt
│ │ ├── LDLT.h
│ │ ├── LLT.h
│ │ └── LLT_MKL.h
│ │ ├── CholmodSupport
│ │ ├── CMakeLists.txt
│ │ └── CholmodSupport.h
│ │ ├── Core
│ │ ├── Array.h
│ │ ├── ArrayBase.h
│ │ ├── ArrayWrapper.h
│ │ ├── Assign.h
│ │ ├── Assign_MKL.h
│ │ ├── BandMatrix.h
│ │ ├── Block.h
│ │ ├── BooleanRedux.h
│ │ ├── CMakeLists.txt
│ │ ├── CommaInitializer.h
│ │ ├── CoreIterators.h
│ │ ├── CwiseBinaryOp.h
│ │ ├── CwiseNullaryOp.h
│ │ ├── CwiseUnaryOp.h
│ │ ├── CwiseUnaryView.h
│ │ ├── DenseBase.h
│ │ ├── DenseCoeffsBase.h
│ │ ├── DenseStorage.h
│ │ ├── Diagonal.h
│ │ ├── DiagonalMatrix.h
│ │ ├── DiagonalProduct.h
│ │ ├── Dot.h
│ │ ├── EigenBase.h
│ │ ├── Flagged.h
│ │ ├── ForceAlignedAccess.h
│ │ ├── Functors.h
│ │ ├── Fuzzy.h
│ │ ├── GeneralProduct.h
│ │ ├── GenericPacketMath.h
│ │ ├── GlobalFunctions.h
│ │ ├── IO.h
│ │ ├── Map.h
│ │ ├── MapBase.h
│ │ ├── MathFunctions.h
│ │ ├── Matrix.h
│ │ ├── MatrixBase.h
│ │ ├── NestByValue.h
│ │ ├── NoAlias.h
│ │ ├── NumTraits.h
│ │ ├── PermutationMatrix.h
│ │ ├── PlainObjectBase.h
│ │ ├── ProductBase.h
│ │ ├── Random.h
│ │ ├── Redux.h
│ │ ├── Ref.h
│ │ ├── Replicate.h
│ │ ├── ReturnByValue.h
│ │ ├── Reverse.h
│ │ ├── Select.h
│ │ ├── SelfAdjointView.h
│ │ ├── SelfCwiseBinaryOp.h
│ │ ├── SolveTriangular.h
│ │ ├── StableNorm.h
│ │ ├── Stride.h
│ │ ├── Swap.h
│ │ ├── Transpose.h
│ │ ├── Transpositions.h
│ │ ├── TriangularMatrix.h
│ │ ├── VectorBlock.h
│ │ ├── VectorwiseOp.h
│ │ ├── Visitor.h
│ │ ├── arch
│ │ │ ├── AltiVec
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── Complex.h
│ │ │ │ └── PacketMath.h
│ │ │ ├── CMakeLists.txt
│ │ │ ├── Default
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ └── Settings.h
│ │ │ ├── NEON
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── Complex.h
│ │ │ │ └── PacketMath.h
│ │ │ └── SSE
│ │ │ │ ├── CMakeLists.txt
│ │ │ │ ├── Complex.h
│ │ │ │ ├── MathFunctions.h
│ │ │ │ └── PacketMath.h
│ │ ├── products
│ │ │ ├── CMakeLists.txt
│ │ │ ├── CoeffBasedProduct.h
│ │ │ ├── GeneralBlockPanelKernel.h
│ │ │ ├── GeneralMatrixMatrix.h
│ │ │ ├── GeneralMatrixMatrixTriangular.h
│ │ │ ├── GeneralMatrixMatrixTriangular_MKL.h
│ │ │ ├── GeneralMatrixMatrix_MKL.h
│ │ │ ├── GeneralMatrixVector.h
│ │ │ ├── GeneralMatrixVector_MKL.h
│ │ │ ├── Parallelizer.h
│ │ │ ├── SelfadjointMatrixMatrix.h
│ │ │ ├── SelfadjointMatrixMatrix_MKL.h
│ │ │ ├── SelfadjointMatrixVector.h
│ │ │ ├── SelfadjointMatrixVector_MKL.h
│ │ │ ├── SelfadjointProduct.h
│ │ │ ├── SelfadjointRank2Update.h
│ │ │ ├── TriangularMatrixMatrix.h
│ │ │ ├── TriangularMatrixMatrix_MKL.h
│ │ │ ├── TriangularMatrixVector.h
│ │ │ ├── TriangularMatrixVector_MKL.h
│ │ │ ├── TriangularSolverMatrix.h
│ │ │ ├── TriangularSolverMatrix_MKL.h
│ │ │ └── TriangularSolverVector.h
│ │ └── util
│ │ │ ├── BlasUtil.h
│ │ │ ├── CMakeLists.txt
│ │ │ ├── Constants.h
│ │ │ ├── DisableStupidWarnings.h
│ │ │ ├── ForwardDeclarations.h
│ │ │ ├── MKL_support.h
│ │ │ ├── Macros.h
│ │ │ ├── Memory.h
│ │ │ ├── Meta.h
│ │ │ ├── NonMPL2.h
│ │ │ ├── ReenableStupidWarnings.h
│ │ │ ├── StaticAssert.h
│ │ │ └── XprHelper.h
│ │ ├── Eigen2Support
│ │ ├── Block.h
│ │ ├── CMakeLists.txt
│ │ ├── Cwise.h
│ │ ├── CwiseOperators.h
│ │ ├── Geometry
│ │ │ ├── AlignedBox.h
│ │ │ ├── All.h
│ │ │ ├── AngleAxis.h
│ │ │ ├── CMakeLists.txt
│ │ │ ├── Hyperplane.h
│ │ │ ├── ParametrizedLine.h
│ │ │ ├── Quaternion.h
│ │ │ ├── Rotation2D.h
│ │ │ ├── RotationBase.h
│ │ │ ├── Scaling.h
│ │ │ ├── Transform.h
│ │ │ └── Translation.h
│ │ ├── LU.h
│ │ ├── Lazy.h
│ │ ├── LeastSquares.h
│ │ ├── Macros.h
│ │ ├── MathFunctions.h
│ │ ├── Memory.h
│ │ ├── Meta.h
│ │ ├── Minor.h
│ │ ├── QR.h
│ │ ├── SVD.h
│ │ ├── TriangularSolver.h
│ │ └── VectorBlock.h
│ │ ├── Eigenvalues
│ │ ├── CMakeLists.txt
│ │ ├── ComplexEigenSolver.h
│ │ ├── ComplexSchur.h
│ │ ├── ComplexSchur_MKL.h
│ │ ├── EigenSolver.h
│ │ ├── GeneralizedEigenSolver.h
│ │ ├── GeneralizedSelfAdjointEigenSolver.h
│ │ ├── HessenbergDecomposition.h
│ │ ├── MatrixBaseEigenvalues.h
│ │ ├── RealQZ.h
│ │ ├── RealSchur.h
│ │ ├── RealSchur_MKL.h
│ │ ├── SelfAdjointEigenSolver.h
│ │ ├── SelfAdjointEigenSolver_MKL.h
│ │ └── Tridiagonalization.h
│ │ ├── Geometry
│ │ ├── AlignedBox.h
│ │ ├── AngleAxis.h
│ │ ├── CMakeLists.txt
│ │ ├── EulerAngles.h
│ │ ├── Homogeneous.h
│ │ ├── Hyperplane.h
│ │ ├── OrthoMethods.h
│ │ ├── ParametrizedLine.h
│ │ ├── Quaternion.h
│ │ ├── Rotation2D.h
│ │ ├── RotationBase.h
│ │ ├── Scaling.h
│ │ ├── Transform.h
│ │ ├── Translation.h
│ │ ├── Umeyama.h
│ │ └── arch
│ │ │ ├── CMakeLists.txt
│ │ │ └── Geometry_SSE.h
│ │ ├── Householder
│ │ ├── BlockHouseholder.h
│ │ ├── CMakeLists.txt
│ │ ├── Householder.h
│ │ └── HouseholderSequence.h
│ │ ├── IterativeLinearSolvers
│ │ ├── BasicPreconditioners.h
│ │ ├── BiCGSTAB.h
│ │ ├── CMakeLists.txt
│ │ ├── ConjugateGradient.h
│ │ ├── IncompleteLUT.h
│ │ └── IterativeSolverBase.h
│ │ ├── Jacobi
│ │ ├── CMakeLists.txt
│ │ └── Jacobi.h
│ │ ├── LU
│ │ ├── CMakeLists.txt
│ │ ├── Determinant.h
│ │ ├── FullPivLU.h
│ │ ├── Inverse.h
│ │ ├── PartialPivLU.h
│ │ ├── PartialPivLU_MKL.h
│ │ └── arch
│ │ │ ├── CMakeLists.txt
│ │ │ └── Inverse_SSE.h
│ │ ├── MetisSupport
│ │ ├── CMakeLists.txt
│ │ └── MetisSupport.h
│ │ ├── OrderingMethods
│ │ ├── Amd.h
│ │ ├── CMakeLists.txt
│ │ ├── Eigen_Colamd.h
│ │ └── Ordering.h
│ │ ├── PaStiXSupport
│ │ ├── CMakeLists.txt
│ │ └── PaStiXSupport.h
│ │ ├── PardisoSupport
│ │ ├── CMakeLists.txt
│ │ └── PardisoSupport.h
│ │ ├── QR
│ │ ├── CMakeLists.txt
│ │ ├── ColPivHouseholderQR.h
│ │ ├── ColPivHouseholderQR_MKL.h
│ │ ├── FullPivHouseholderQR.h
│ │ ├── HouseholderQR.h
│ │ └── HouseholderQR_MKL.h
│ │ ├── SPQRSupport
│ │ ├── CMakeLists.txt
│ │ └── SuiteSparseQRSupport.h
│ │ ├── SVD
│ │ ├── CMakeLists.txt
│ │ ├── JacobiSVD.h
│ │ ├── JacobiSVD_MKL.h
│ │ └── UpperBidiagonalization.h
│ │ ├── SparseCholesky
│ │ ├── CMakeLists.txt
│ │ ├── SimplicialCholesky.h
│ │ └── SimplicialCholesky_impl.h
│ │ ├── SparseCore
│ │ ├── AmbiVector.h
│ │ ├── CMakeLists.txt
│ │ ├── CompressedStorage.h
│ │ ├── ConservativeSparseSparseProduct.h
│ │ ├── MappedSparseMatrix.h
│ │ ├── SparseBlock.h
│ │ ├── SparseColEtree.h
│ │ ├── SparseCwiseBinaryOp.h
│ │ ├── SparseCwiseUnaryOp.h
│ │ ├── SparseDenseProduct.h
│ │ ├── SparseDiagonalProduct.h
│ │ ├── SparseDot.h
│ │ ├── SparseFuzzy.h
│ │ ├── SparseMatrix.h
│ │ ├── SparseMatrixBase.h
│ │ ├── SparsePermutation.h
│ │ ├── SparseProduct.h
│ │ ├── SparseRedux.h
│ │ ├── SparseSelfAdjointView.h
│ │ ├── SparseSparseProductWithPruning.h
│ │ ├── SparseTranspose.h
│ │ ├── SparseTriangularView.h
│ │ ├── SparseUtil.h
│ │ ├── SparseVector.h
│ │ ├── SparseView.h
│ │ └── TriangularSolver.h
│ │ ├── SparseLU
│ │ ├── CMakeLists.txt
│ │ ├── SparseLU.h
│ │ ├── SparseLUImpl.h
│ │ ├── SparseLU_Memory.h
│ │ ├── SparseLU_Structs.h
│ │ ├── SparseLU_SupernodalMatrix.h
│ │ ├── SparseLU_Utils.h
│ │ ├── SparseLU_column_bmod.h
│ │ ├── SparseLU_column_dfs.h
│ │ ├── SparseLU_copy_to_ucol.h
│ │ ├── SparseLU_gemm_kernel.h
│ │ ├── SparseLU_heap_relax_snode.h
│ │ ├── SparseLU_kernel_bmod.h
│ │ ├── SparseLU_panel_bmod.h
│ │ ├── SparseLU_panel_dfs.h
│ │ ├── SparseLU_pivotL.h
│ │ ├── SparseLU_pruneL.h
│ │ └── SparseLU_relax_snode.h
│ │ ├── SparseQR
│ │ ├── CMakeLists.txt
│ │ └── SparseQR.h
│ │ ├── StlSupport
│ │ ├── CMakeLists.txt
│ │ ├── StdDeque.h
│ │ ├── StdList.h
│ │ ├── StdVector.h
│ │ └── details.h
│ │ ├── SuperLUSupport
│ │ ├── CMakeLists.txt
│ │ └── SuperLUSupport.h
│ │ ├── UmfPackSupport
│ │ ├── CMakeLists.txt
│ │ └── UmfPackSupport.h
│ │ ├── misc
│ │ ├── CMakeLists.txt
│ │ ├── Image.h
│ │ ├── Kernel.h
│ │ ├── Solve.h
│ │ ├── SparseSolve.h
│ │ └── blas.h
│ │ └── plugins
│ │ ├── ArrayCwiseBinaryOps.h
│ │ ├── ArrayCwiseUnaryOps.h
│ │ ├── BlockMethods.h
│ │ ├── CMakeLists.txt
│ │ ├── CommonCwiseBinaryOps.h
│ │ ├── CommonCwiseUnaryOps.h
│ │ ├── MatrixCwiseBinaryOps.h
│ │ └── MatrixCwiseUnaryOps.h
├── icon.jpg
└── main.m
├── orbslamiosTests
├── Info.plist
└── orbslamiosTests.m
├── orbslamiosUITests
├── Info.plist
└── orbslamiosUITests.m
└── ygxslam
├── .DS_Store
├── ORBvoc.bin
└── Settings.yaml
/.DS_Store:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ygx2011/ORB_SLAM2-IOS/31b6ef6e13424e3a0df984b17ea379c4249ef41a/.DS_Store
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # ORB_SLAM2-IOS
2 | This is iOS port of [ORB-SLAM2](https://github.com/raulmur/ORB_SLAM2) with modified dependency for iOS.
3 |
4 | And this link is iOS port of [ORB-SLAM1](https://github.com/ygx2011/ORB_SLAM-IOS).
5 |
6 | You need to download some dependency and opencv2.framework from
7 | https://pan.baidu.com/s/1i5fsyot
8 |
9 | Unzip orbslam2ios.zip and put the dependency folder and opencv2.framework in the orbslamios folder.
10 |
11 | You can do some AR projects. If you are interested in SLAM-AR, you can see my another project [Stereo-SLAM-AR](https://github.com/ygx2011/Stereo_SLAM_AR).
12 |
13 |
16 |
--------------------------------------------------------------------------------
/orbslamios.xcodeproj/project.xcworkspace/contents.xcworkspacedata:
--------------------------------------------------------------------------------
1 |
2 |
4 |
6 |
7 |
8 |
--------------------------------------------------------------------------------
/orbslamios.xcodeproj/project.xcworkspace/xcuserdata/Yinggx.xcuserdatad/UserInterfaceState.xcuserstate:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ygx2011/ORB_SLAM2-IOS/31b6ef6e13424e3a0df984b17ea379c4249ef41a/orbslamios.xcodeproj/project.xcworkspace/xcuserdata/Yinggx.xcuserdatad/UserInterfaceState.xcuserstate
--------------------------------------------------------------------------------
/orbslamios.xcodeproj/xcuserdata/Yinggx.xcuserdatad/xcdebugger/Breakpoints_v2.xcbkptlist:
--------------------------------------------------------------------------------
1 |
2 |
5 |
6 |
--------------------------------------------------------------------------------
/orbslamios.xcodeproj/xcuserdata/Yinggx.xcuserdatad/xcschemes/xcschememanagement.plist:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 | SchemeUserState
6 |
7 | orbslamios.xcscheme
8 |
9 | orderHint
10 | 0
11 |
12 |
13 | SuppressBuildableAutocreation
14 |
15 | 60FF20331DC883E7003B783E
16 |
17 | primary
18 |
19 |
20 | 60FF204C1DC883E7003B783E
21 |
22 | primary
23 |
24 |
25 | 60FF20571DC883E7003B783E
26 |
27 | primary
28 |
29 |
30 |
31 |
32 |
33 |
--------------------------------------------------------------------------------
/orbslamios/.DS_Store:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ygx2011/ORB_SLAM2-IOS/31b6ef6e13424e3a0df984b17ea379c4249ef41a/orbslamios/.DS_Store
--------------------------------------------------------------------------------
/orbslamios/AppDelegate.h:
--------------------------------------------------------------------------------
1 | //
2 | // AppDelegate.h
3 | // orbslamios
4 | //
5 | // Created by Ying Gaoxuan on 16/11/1.
6 | // Copyright © 2016年 Ying Gaoxuan. All rights reserved.
7 | //
8 |
9 | #import
10 |
11 | @interface AppDelegate : UIResponder
12 |
13 | @property (strong, nonatomic) UIWindow *window;
14 |
15 |
16 | @end
17 |
18 |
--------------------------------------------------------------------------------
/orbslamios/AppDelegate.m:
--------------------------------------------------------------------------------
1 | //
2 | // AppDelegate.m
3 | // orbslamios
4 | //
5 | // Created by Ying Gaoxuan on 16/11/1.
6 | // Copyright © 2016年 Ying Gaoxuan. All rights reserved.
7 | //
8 |
9 | #import "AppDelegate.h"
10 |
11 | @interface AppDelegate ()
12 |
13 | @end
14 |
15 | @implementation AppDelegate
16 |
17 |
18 | - (BOOL)application:(UIApplication *)application didFinishLaunchingWithOptions:(NSDictionary *)launchOptions {
19 | // Override point for customization after application launch.
20 | return YES;
21 | }
22 |
23 |
24 | - (void)applicationWillResignActive:(UIApplication *)application {
25 | // Sent when the application is about to move from active to inactive state. This can occur for certain types of temporary interruptions (such as an incoming phone call or SMS message) or when the user quits the application and it begins the transition to the background state.
26 | // Use this method to pause ongoing tasks, disable timers, and invalidate graphics rendering callbacks. Games should use this method to pause the game.
27 | }
28 |
29 |
30 | - (void)applicationDidEnterBackground:(UIApplication *)application {
31 | // Use this method to release shared resources, save user data, invalidate timers, and store enough application state information to restore your application to its current state in case it is terminated later.
32 | // If your application supports background execution, this method is called instead of applicationWillTerminate: when the user quits.
33 | }
34 |
35 |
36 | - (void)applicationWillEnterForeground:(UIApplication *)application {
37 | // Called as part of the transition from the background to the active state; here you can undo many of the changes made on entering the background.
38 | }
39 |
40 |
41 | - (void)applicationDidBecomeActive:(UIApplication *)application {
42 | // Restart any tasks that were paused (or not yet started) while the application was inactive. If the application was previously in the background, optionally refresh the user interface.
43 | }
44 |
45 |
46 | - (void)applicationWillTerminate:(UIApplication *)application {
47 | // Called when the application is about to terminate. Save data if appropriate. See also applicationDidEnterBackground:.
48 | }
49 |
50 |
51 | @end
52 |
--------------------------------------------------------------------------------
/orbslamios/Assets.xcassets/AppIcon.appiconset/Contents.json:
--------------------------------------------------------------------------------
1 | {
2 | "images" : [
3 | {
4 | "idiom" : "iphone",
5 | "size" : "20x20",
6 | "scale" : "2x"
7 | },
8 | {
9 | "idiom" : "iphone",
10 | "size" : "20x20",
11 | "scale" : "3x"
12 | },
13 | {
14 | "idiom" : "iphone",
15 | "size" : "29x29",
16 | "scale" : "2x"
17 | },
18 | {
19 | "idiom" : "iphone",
20 | "size" : "29x29",
21 | "scale" : "3x"
22 | },
23 | {
24 | "idiom" : "iphone",
25 | "size" : "40x40",
26 | "scale" : "2x"
27 | },
28 | {
29 | "idiom" : "iphone",
30 | "size" : "40x40",
31 | "scale" : "3x"
32 | },
33 | {
34 | "idiom" : "iphone",
35 | "size" : "60x60",
36 | "scale" : "2x"
37 | },
38 | {
39 | "idiom" : "iphone",
40 | "size" : "60x60",
41 | "scale" : "3x"
42 | },
43 | {
44 | "idiom" : "ipad",
45 | "size" : "20x20",
46 | "scale" : "1x"
47 | },
48 | {
49 | "idiom" : "ipad",
50 | "size" : "20x20",
51 | "scale" : "2x"
52 | },
53 | {
54 | "idiom" : "ipad",
55 | "size" : "29x29",
56 | "scale" : "1x"
57 | },
58 | {
59 | "idiom" : "ipad",
60 | "size" : "29x29",
61 | "scale" : "2x"
62 | },
63 | {
64 | "idiom" : "ipad",
65 | "size" : "40x40",
66 | "scale" : "1x"
67 | },
68 | {
69 | "idiom" : "ipad",
70 | "size" : "40x40",
71 | "scale" : "2x"
72 | },
73 | {
74 | "idiom" : "ipad",
75 | "size" : "76x76",
76 | "scale" : "1x"
77 | },
78 | {
79 | "idiom" : "ipad",
80 | "size" : "76x76",
81 | "scale" : "2x"
82 | },
83 | {
84 | "idiom" : "ipad",
85 | "size" : "83.5x83.5",
86 | "scale" : "2x"
87 | }
88 | ],
89 | "info" : {
90 | "version" : 1,
91 | "author" : "xcode"
92 | }
93 | }
--------------------------------------------------------------------------------
/orbslamios/Base.lproj/LaunchScreen.storyboard:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
--------------------------------------------------------------------------------
/orbslamios/Info.plist:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 | CFBundleDevelopmentRegion
6 | en
7 | CFBundleExecutable
8 | $(EXECUTABLE_NAME)
9 | CFBundleIconFiles
10 |
11 | icon.jpg
12 |
13 | CFBundleIdentifier
14 | $(PRODUCT_BUNDLE_IDENTIFIER)
15 | CFBundleInfoDictionaryVersion
16 | 6.0
17 | CFBundleName
18 | $(PRODUCT_NAME)
19 | CFBundlePackageType
20 | APPL
21 | CFBundleShortVersionString
22 | 1.0
23 | CFBundleVersion
24 | 1
25 | LSRequiresIPhoneOS
26 |
27 | NSCameraUsageDescription
28 | 让我用下相机呗
29 | UILaunchStoryboardName
30 | LaunchScreen
31 | UIMainStoryboardFile
32 | Main
33 | UIRequiredDeviceCapabilities
34 |
35 | armv7
36 |
37 | UISupportedInterfaceOrientations
38 |
39 | UIInterfaceOrientationLandscapeRight
40 |
41 | UISupportedInterfaceOrientations~ipad
42 |
43 | UIInterfaceOrientationPortrait
44 | UIInterfaceOrientationPortraitUpsideDown
45 | UIInterfaceOrientationLandscapeLeft
46 | UIInterfaceOrientationLandscapeRight
47 |
48 |
49 |
50 |
--------------------------------------------------------------------------------
/orbslamios/ORB_SLAM/.DS_Store:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ygx2011/ORB_SLAM2-IOS/31b6ef6e13424e3a0df984b17ea379c4249ef41a/orbslamios/ORB_SLAM/.DS_Store
--------------------------------------------------------------------------------
/orbslamios/ORB_SLAM/Thirdparty/.DS_Store:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ygx2011/ORB_SLAM2-IOS/31b6ef6e13424e3a0df984b17ea379c4249ef41a/orbslamios/ORB_SLAM/Thirdparty/.DS_Store
--------------------------------------------------------------------------------
/orbslamios/ORB_SLAM/Thirdparty/DBoW2/.DS_Store:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ygx2011/ORB_SLAM2-IOS/31b6ef6e13424e3a0df984b17ea379c4249ef41a/orbslamios/ORB_SLAM/Thirdparty/DBoW2/.DS_Store
--------------------------------------------------------------------------------
/orbslamios/ORB_SLAM/Thirdparty/DBoW2/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | version https://git-lfs.github.com/spec/v1
2 | oid sha256:74db2d8bdcc8a22afb73fff5854cf3871a1758673d823c4cc9d5d84b5a785524
3 | size 800
4 |
--------------------------------------------------------------------------------
/orbslamios/ORB_SLAM/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