Skip to content

Commit

Permalink
adds missed control_toolbox dependency
Browse files Browse the repository at this point in the history
  • Loading branch information
efernandez committed Nov 15, 2014
1 parent 0693947 commit 7054744
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 1 deletion.
4 changes: 3 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,8 @@ find_package(catkin REQUIRED
std_srvs
tf
pal_multirobot_msgs
roscpp)
roscpp
control_toolbox)

# Depend on system install of Gazebo and SDFormat
find_package(gazebo REQUIRED)
Expand All @@ -30,6 +31,7 @@ catkin_package(
tf
pal_multirobot_msgs
roscpp
control_toolbox
DEPENDS gazebo)

link_directories(${GAZEBO_LIBRARY_DIRS})
Expand Down
2 changes: 2 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,12 +23,14 @@
<build_depend>std_srvs</build_depend>
<build_depend>pal_multirobot_msgs</build_depend>
<build_depend>tf</build_depend>
<build_depend>control_toolbox</build_depend>

<run_depend>gazebo</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>std_srvs</run_depend>
<run_depend>pal_multirobot_msgs</run_depend>
<run_depend>tf</run_depend>
<run_depend>control_toolbox</run_depend>

</package>

0 comments on commit 7054744

Please sign in to comment.