Skip to content

Commit

Permalink
Ported to Kinetic on Uubntu 16.04
Browse files Browse the repository at this point in the history
  • Loading branch information
Seanmatthews committed Feb 13, 2017
1 parent ce19965 commit 5906aff
Show file tree
Hide file tree
Showing 4 changed files with 46 additions and 23 deletions.
21 changes: 18 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,15 +16,29 @@ set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)

LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)

find_package(catkin REQUIRED COMPONENTS
roscpp
image_transport
sensor_msgs
cv_bridge
tf
)

find_package(OpenCV REQUIRED)
find_package(Eigen3 REQUIRED)

catkin_package(
INCLUDE_DIRS include
CATKIN_DEPENDS roscpp image_transport sensor_msgs cv_bridge tf
)

include_directories(
${PROJECT_SOURCE_DIR}
${EIGEN3_INCLUDE_DIR}
${catkin_INCLUDE_DIRS}
)

rosbuild_add_executable(${PROJECT_NAME}
add_executable(${PROJECT_NAME}
src/main.cc
src/Tracking.cc
src/LocalMapping.cc
Expand All @@ -44,12 +58,13 @@ src/KeyFrameDatabase.cc
src/Sim3Solver.cc
src/Initializer.cc
)
rosbuild_add_boost_directories()
rosbuild_link_boost(${PROJECT_NAME} thread)
#rosbuild_add_boost_directories()
#rosbuild_link_boost(${PROJECT_NAME} thread)

target_link_libraries(${PROJECT_NAME}
${OpenCV_LIBS}
${EIGEN3_LIBS}
${catkin_LIBRARIES}
${PROJECT_SOURCE_DIR}/Thirdparty/DBoW2/lib/libDBoW2.so
${PROJECT_SOURCE_DIR}/Thirdparty/g2o/lib/libg2o.so
)
Expand Down
5 changes: 4 additions & 1 deletion Thirdparty/g2o/g2o/solvers/linear_solver_eigen.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,10 @@ class LinearSolverEigen: public LinearSolver<MatrixType>
public:
typedef Eigen::SparseMatrix<double, Eigen::ColMajor> SparseMatrix;
typedef Eigen::Triplet<double> Triplet;
typedef Eigen::PermutationMatrix<Eigen::Dynamic, Eigen::Dynamic, SparseMatrix::Index> PermutationMatrix;

// https://github.com/arntanguy/ORB_SLAM2/commit/691d6af2a018e6261995ecd382d676b45cb63c6a
typedef Eigen::PermutationMatrix<Eigen::Dynamic, Eigen::Dynamic, int> PermutationMatrix;

/**
* \brief Sub-classing Eigen's SimplicialLDLT to perform ordering with a given ordering
*/
Expand Down
19 changes: 0 additions & 19 deletions manifest.xml

This file was deleted.

24 changes: 24 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
<package>
<name>ORB_SLAM</name>
<version>0.0.0</version>
<description>ORB_SLAM</description>
<author>Raul Mur-Artal</author>
<maintainer email="[email protected]">dev</maintainer>
<license>GPLv3</license>

<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>tf</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>image_transport</build_depend>
<build_depend>cv_bridge</build_depend>

<run_depend>roscpp</run_depend>
<run_depend>tf</run_depend>
<run_depend>sensor_msgs</run_depend>
<run_depend>image_transport</run_depend>
<run_depend>cv_bridge</run_depend>

</package>


0 comments on commit 5906aff

Please sign in to comment.