Skip to content

Commit

Permalink
update amcl to have proper depends
Browse files Browse the repository at this point in the history
* add geometry_msgs
* add tf2_msgs
* fix alphabetical order
  • Loading branch information
mikeferguson committed Jul 30, 2018
1 parent 6b8f276 commit b2e7102
Show file tree
Hide file tree
Showing 2 changed files with 29 additions and 20 deletions.
44 changes: 25 additions & 19 deletions amcl/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,19 +2,20 @@ cmake_minimum_required(VERSION 2.8.3)
project(amcl)

find_package(catkin REQUIRED
COMPONENTS
message_filters
rosbag
roscpp
std_srvs
tf2
tf2_geometry_msgs
tf2_ros
dynamic_reconfigure
nav_msgs
sensor_msgs
std_srvs
)
COMPONENTS
dynamic_reconfigure
geometry_msgs
message_filters
nav_msgs
rosbag
roscpp
sensor_msgs
std_srvs
tf2
tf2_geometry_msgs
tf2_msgs
tf2_ros
)

find_package(Boost REQUIRED)

Expand All @@ -24,12 +25,17 @@ generate_dynamic_reconfigure_options(
)

catkin_package(
CATKIN_DEPENDS
rosbag
roscpp
dynamic_reconfigure
tf2_ros
CATKIN_DEPENDS nav_msgs std_srvs
CATKIN_DEPENDS
dynamic_reconfigure
geometry_msgs
nav_msgs
rosbag
roscpp
sensor_msgs
std_srvs
tf2
tf2_msgs
tf2_ros
INCLUDE_DIRS include
LIBRARIES amcl_sensors amcl_map amcl_pf
)
Expand Down
5 changes: 4 additions & 1 deletion amcl/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -29,11 +29,14 @@
<build_depend>tf2_geometry_msgs</build_depend>

<depend>dynamic_reconfigure</depend>
<depend>geometry_msgs</depend>
<depend>nav_msgs</depend>
<depend>rosbag</depend>
<depend>roscpp</depend>
<depend>std_srvs</depend>
<depend>sensor_msgs</depend>
<depend>std_srvs</depend>
<depend>tf2</depend>
<depend>tf2_msgs</depend>
<depend>tf2_ros</depend>

<test_depend>map_server</test_depend>
Expand Down

0 comments on commit b2e7102

Please sign in to comment.