From 58bdcbdc2381f992a3337091572bc691437eb828 Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Fri, 3 Apr 2020 19:53:02 +0200 Subject: [PATCH] Modernize package.xml and add missing std_msgs in CATKIN_DEPENDS --- CMakeLists.txt | 2 +- package.xml | 24 ++++++++---------------- 2 files changed, 9 insertions(+), 17 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 48537f25..946b2997 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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() diff --git a/package.xml b/package.xml index fbda419b..d95e429d 100644 --- a/package.xml +++ b/package.xml @@ -1,4 +1,4 @@ - + interactive_markers 3D interactive marker communication library for RViz and similar tools. @@ -13,19 +13,11 @@ catkin - rosconsole - roscpp - rospy - rostest - std_msgs - tf - visualization_msgs - - rosconsole - roscpp - rospy - rostest - std_msgs - tf - visualization_msgs + rosconsole + roscpp + rospy + rostest + std_msgs + tf + visualization_msgs