Skip to content

Commit

Permalink
Fix gmapping boost libs
Browse files Browse the repository at this point in the history
  • Loading branch information
Tobias-Fischer committed Mar 11, 2021
1 parent d1e5df8 commit d1b3c11
Showing 1 changed file with 13 additions and 0 deletions.
13 changes: 13 additions & 0 deletions patch/ros-noetic-gmapping.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 04f3c8d..c4ea9c2 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -3,7 +3,7 @@ project(gmapping)

find_package(catkin REQUIRED nav_msgs nodelet openslam_gmapping roscpp tf rosbag_storage)

-find_package(Boost REQUIRED)
+find_package(Boost COMPONENTS thread system program_options REQUIRED)

include_directories(${Boost_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS})

0 comments on commit d1b3c11

Please sign in to comment.