Skip to content

Commit

Permalink
Modernize package.xml
Browse files Browse the repository at this point in the history
and add missing std_msgs in CATKIN_DEPENDS
  • Loading branch information
rhaschke committed Apr 3, 2020
1 parent ff6268d commit 58bdcbd
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 17 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ find_package(catkin REQUIRED
catkin_package(
INCLUDE_DIRS include
LIBRARIES interactive_markers
CATKIN_DEPENDS roscpp rosconsole rospy tf visualization_msgs
CATKIN_DEPENDS roscpp rosconsole rospy tf std_msgs visualization_msgs
)
catkin_python_setup()

Expand Down
24 changes: 8 additions & 16 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<package>
<package format="2">
<name>interactive_markers</name>
<description>
3D interactive marker communication library for RViz and similar tools.
Expand All @@ -13,19 +13,11 @@

<buildtool_depend>catkin</buildtool_depend>

<build_depend>rosconsole</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>rostest</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>tf</build_depend>
<build_depend>visualization_msgs</build_depend>

<run_depend>rosconsole</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>rospy</run_depend>
<run_depend>rostest</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>tf</run_depend>
<run_depend>visualization_msgs</run_depend>
<depend>rosconsole</depend>
<depend>roscpp</depend>
<depend>rospy</depend>
<depend>rostest</depend>
<depend>std_msgs</depend>
<depend>tf</depend>
<depend>visualization_msgs</depend>
</package>

0 comments on commit 58bdcbd

Please sign in to comment.