From dc2e5c4fbcac73f0d7bc74a8150abc8d801e2cde Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Tue, 13 Aug 2019 11:55:13 -0700 Subject: [PATCH 1/2] use condition attributes to specify Python 2 and 3 dependencies --- clients/rospy/package.xml | 32 ++++++++++++++------- test/test_rosbag/package.xml | 23 +++++++++------ test/test_roslaunch/package.xml | 13 +++++++-- test/test_rosparam/package.xml | 13 +++++++-- test/test_rospy/package.xml | 16 ++++++++--- tools/rosbag/package.xml | 51 ++++++++++++++++++--------------- tools/rosgraph/package.xml | 24 +++++++++++----- tools/roslaunch/package.xml | 33 +++++++++++++-------- tools/rosmaster/package.xml | 15 +++++++--- tools/rosmsg/package.xml | 23 +++++++++------ tools/rosparam/package.xml | 15 +++++++--- utilities/roswtf/package.xml | 28 +++++++++++------- 12 files changed, 189 insertions(+), 97 deletions(-) diff --git a/clients/rospy/package.xml b/clients/rospy/package.xml index 7a862a42e7..078723a6f6 100644 --- a/clients/rospy/package.xml +++ b/clients/rospy/package.xml @@ -1,4 +1,8 @@ - + + + rospy 1.14.3 @@ -22,20 +26,26 @@ Dirk Thomas BSD - http://ros.org/wiki/rospy + http://wiki.ros.org/rospy + https://github.com/ros/ros_comm/issues + https://github.com/ros/ros_comm + Ken Conley catkin - genpy - python-numpy - python-rospkg - python-yaml - roscpp - rosgraph - rosgraph_msgs - roslib - std_msgs + genpy + python-numpy + python3-numpy + python-rospkg + python3-rospkg + python-yaml + python3-yaml + roscpp + rosgraph + rosgraph_msgs + roslib + std_msgs diff --git a/test/test_rosbag/package.xml b/test/test_rosbag/package.xml index 8de09e2fd0..739f0b8428 100644 --- a/test/test_rosbag/package.xml +++ b/test/test_rosbag/package.xml @@ -1,4 +1,8 @@ - + + + test_rosbag 1.14.3 @@ -7,24 +11,28 @@ Dirk Thomas BSD - http://ros.org/wiki/rosbag + http://wiki.ros.org/rosbag + https://github.com/ros/ros_comm/issues + https://github.com/ros/ros_comm Tim Field Jeremy Leibs James Bowman + rosbag + rostest + catkin boost bzip2 cpp_common message_generation - python-imaging - rosbag + python-imaging + python3-imaging rosconsole roscpp roscpp_serialization rosgraph_msgs - rostest rosunit topic_tools xmlrpcpp @@ -32,11 +40,10 @@ genmsg genpy message_runtime - python-rospkg - rosbag + python-rospkg + python3-rospkg roslib rospy - rostest rostopic diff --git a/test/test_roslaunch/package.xml b/test/test_roslaunch/package.xml index f39d23fac1..3a1ce182d8 100644 --- a/test/test_roslaunch/package.xml +++ b/test/test_roslaunch/package.xml @@ -1,4 +1,8 @@ - + + + test_roslaunch 1.14.3 @@ -7,14 +11,17 @@ Dirk Thomas BSD - http://ros.org/wiki/roslaunch + http://wiki.ros.org/roslaunch + https://github.com/ros/ros_comm/issues + https://github.com/ros/ros_comm Ken Conley catkin rostest - python-rospkg + python-rospkg + python3-rospkg rosgraph roslaunch diff --git a/test/test_rosparam/package.xml b/test/test_rosparam/package.xml index 78ace8693c..3e52a61fde 100644 --- a/test/test_rosparam/package.xml +++ b/test/test_rosparam/package.xml @@ -1,4 +1,8 @@ - + + + test_rosparam 1.14.3 @@ -7,14 +11,17 @@ Dirk Thomas BSD - http://ros.org/wiki/rosparam + http://wiki.ros.org/rosparam + https://github.com/ros/ros_comm/issues + https://github.com/ros/ros_comm Ken Conley catkin rostest - python-yaml + python-yaml + python3-yaml rosgraph rosparam diff --git a/test/test_rospy/package.xml b/test/test_rospy/package.xml index 951e92b618..22e7b69933 100644 --- a/test/test_rospy/package.xml +++ b/test/test_rospy/package.xml @@ -1,4 +1,8 @@ - + + + test_rospy 1.14.3 @@ -7,7 +11,9 @@ Dirk Thomas BSD - http://ros.org/wiki/rospy + http://wiki.ros.org/rospy + https://github.com/ros/ros_comm/issues + https://github.com/ros/ros_comm Ken Conley catkin @@ -17,8 +23,10 @@ std_msgs test_rosmaster - python-numpy - python-psutil + python-numpy + python3-numpy + python-psutil + python3-psutil rosbuild rosgraph rospy diff --git a/tools/rosbag/package.xml b/tools/rosbag/package.xml index f4e8607816..459f6170bb 100644 --- a/tools/rosbag/package.xml +++ b/tools/rosbag/package.xml @@ -1,4 +1,8 @@ - + + + rosbag 1.14.3 @@ -9,38 +13,39 @@ Dirk Thomas BSD - http://ros.org/wiki/rosbag + http://wiki.ros.org/rosbag + https://github.com/ros/ros_comm/issues + https://github.com/ros/ros_comm Tim Field Jeremy Leibs James Bowman + boost + rosbag_storage + rosconsole + roscpp + std_srvs + xmlrpcpp + catkin - boost cpp_common - python-imaging - rosbag_storage - rosconsole - roscpp + python-imaging + python3-imaging roscpp_serialization - std_srvs topic_tools - xmlrpcpp - boost - genmsg - genpy - python-pycryptodome - python-gnupg - python-rospkg - rosbag_storage - rosconsole - roscpp - roslib - rospy - std_srvs - topic_tools - xmlrpcpp + genmsg + genpy + python-pycryptodome + python3-pycryptodome + python-gnupg + python3-gnupg + python-rospkg + python3-rospkg + roslib + rospy + topic_tools diff --git a/tools/rosgraph/package.xml b/tools/rosgraph/package.xml index 7bd821df75..6ad7399981 100644 --- a/tools/rosgraph/package.xml +++ b/tools/rosgraph/package.xml @@ -1,5 +1,9 @@ - - rosgraph + + + + rosgraph 1.14.3 rosgraph contains the rosgraph command-line tool, which prints @@ -9,16 +13,22 @@ Dirk Thomas BSD - http://ros.org/wiki/rosgraph + http://wiki.ros.org/rosgraph + https://github.com/ros/ros_comm/issues + https://github.com/ros/ros_comm Ken Conley catkin - python-netifaces - python-rospkg - python-yaml + python-netifaces + python3-netifaces + python-rospkg + python3-rospkg + python-yaml + python3-yaml - python-mock + python-mock + python3-mock diff --git a/tools/roslaunch/package.xml b/tools/roslaunch/package.xml index 0c13f41603..9341885791 100644 --- a/tools/roslaunch/package.xml +++ b/tools/roslaunch/package.xml @@ -1,4 +1,8 @@ - + + + roslaunch 1.14.3 @@ -15,21 +19,26 @@ Dirk Thomas BSD - http://ros.org/wiki/roslaunch + http://wiki.ros.org/roslaunch + https://github.com/ros/ros_comm/issues + https://github.com/ros/ros_comm Ken Conley catkin - python-paramiko - python-rospkg - python-yaml - rosclean - rosgraph_msgs - roslib - rosmaster - rosout - rosparam - rosunit + python-paramiko + python3-paramiko + python-rospkg + python3-rospkg + python-yaml + python3-yaml + rosclean + rosgraph_msgs + roslib + rosmaster + rosout + rosparam + rosunit rosbuild diff --git a/tools/rosmaster/package.xml b/tools/rosmaster/package.xml index a7d24de48c..17db3457b0 100644 --- a/tools/rosmaster/package.xml +++ b/tools/rosmaster/package.xml @@ -1,4 +1,8 @@ - + + + rosmaster 1.14.3 @@ -7,13 +11,16 @@ Dirk Thomas BSD - http://ros.org/wiki/rosmaster + http://wiki.ros.org/rosmaster + https://github.com/ros/ros_comm/issues + https://github.com/ros/ros_comm Ken Conley catkin - rosgraph - python-defusedxml + rosgraph + python-defusedxml + python3-defusedxml diff --git a/tools/rosmsg/package.xml b/tools/rosmsg/package.xml index 66831e1cd8..8611b296a1 100644 --- a/tools/rosmsg/package.xml +++ b/tools/rosmsg/package.xml @@ -1,4 +1,8 @@ - + + + rosmsg 1.14.3 @@ -13,18 +17,21 @@ Dirk Thomas BSD - http://ros.org/wiki/rosmsg + http://wiki.ros.org/rosmsg + https://github.com/ros/ros_comm/issues + https://github.com/ros/ros_comm Ken Conley Tully Foote catkin - catkin - genmsg - genpy - python-rospkg - rosbag - roslib + catkin + genmsg + genpy + python-rospkg + python3-rospkg + rosbag + roslib std_msgs diff --git a/tools/rosparam/package.xml b/tools/rosparam/package.xml index a25fb3d1bd..a95e7545c9 100644 --- a/tools/rosparam/package.xml +++ b/tools/rosparam/package.xml @@ -1,4 +1,8 @@ - + + + rosparam 1.14.3 @@ -14,13 +18,16 @@ Dirk Thomas BSD - http://ros.org/wiki/rosparam + http://wiki.ros.org/rosparam + https://github.com/ros/ros_comm/issues + https://github.com/ros/ros_comm Ken Conley catkin - python-yaml - rosgraph + python-yaml + python3-yaml + rosgraph diff --git a/utilities/roswtf/package.xml b/utilities/roswtf/package.xml index 64346301fe..3717a52205 100644 --- a/utilities/roswtf/package.xml +++ b/utilities/roswtf/package.xml @@ -1,4 +1,8 @@ - + + + roswtf 1.14.3 @@ -7,21 +11,25 @@ Dirk Thomas BSD - http://ros.org/wiki/roswtf + http://wiki.ros.org/roswtf + https://github.com/ros/ros_comm/issues + https://github.com/ros/ros_comm Ken Conley catkin rostest - python-paramiko - python-rospkg - rosbuild - rosgraph - roslaunch - roslib - rosnode - rosservice + python-paramiko + python3-paramiko + python-rospkg + python3-rospkg + rosbuild + rosgraph + roslaunch + roslib + rosnode + rosservice cmake_modules rosbag From bd2dcba045652610ba7afa8923a0a8daff8fe644 Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Wed, 14 Aug 2019 08:53:52 -0700 Subject: [PATCH 2/2] use python3-pil --- test/test_rosbag/package.xml | 2 +- tools/rosbag/package.xml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/test/test_rosbag/package.xml b/test/test_rosbag/package.xml index 739f0b8428..4265a1867c 100644 --- a/test/test_rosbag/package.xml +++ b/test/test_rosbag/package.xml @@ -28,7 +28,7 @@ cpp_common message_generation python-imaging - python3-imaging + python3-pil rosconsole roscpp roscpp_serialization diff --git a/tools/rosbag/package.xml b/tools/rosbag/package.xml index 459f6170bb..836eba113c 100644 --- a/tools/rosbag/package.xml +++ b/tools/rosbag/package.xml @@ -31,7 +31,7 @@ cpp_common python-imaging - python3-imaging + python3-pil roscpp_serialization topic_tools