diff --git a/README.md b/README.md index 13b1bd7b..a8ddeb99 100644 --- a/README.md +++ b/README.md @@ -22,7 +22,7 @@ Please ask support questions on [ROS Answers](http://answers.ros.org/questions/) On ROS Indigo or Jade, the `indigo-devel` branch is recommended. -On ROS Kinetic, the `master` branch is recommended. +On ROS Kinetic, Melodic and Noetic, the `master` branch is recommended. # Development, Branch and Release Policy @@ -32,6 +32,6 @@ The `sound_play`, `groovy-devel` and `hydro-devel` branches are from previous RO The `indigo-devel` branch is the stable branch; only bug fixes are accepted on this branch. Periodic releases are done from `indigo-devel` into ROS Indigo and ROS Jade, with version numbers in the 0.2.x range. -The `master` branch is currently considered the development branch, and is released into ROS Kinetic with version numbers in the 0.3.x range. `master` is accepting new, non-breaking features and bug fixes. +The `master` branch is currently considered the development branch, and is released into ROS Kinetic, Melodic and Noetic with version numbers in the 0.3.x range. `master` is accepting new, non-breaking features and bug fixes. Large, breaking changes such as changes to dependencies or the package API will be considered, but they will probably be staged into a development branch for release into the next major release of ROS (ROS L) diff --git a/sound_play/CMakeLists.txt b/sound_play/CMakeLists.txt index 92bd8e01..552a04ea 100644 --- a/sound_play/CMakeLists.txt +++ b/sound_play/CMakeLists.txt @@ -16,29 +16,28 @@ generate_messages(DEPENDENCIES actionlib_msgs) catkin_package(CATKIN_DEPENDS message_runtime actionlib_msgs INCLUDE_DIRS include) -# if(CATKIN_ENABLE_TESTING) -# catkin_add_nosetests(scripts/test) -# -# add_subdirectory(test) -# endif() - -install(PROGRAMS - scripts/playbuiltin.py - scripts/play.py - scripts/say.py - scripts/shutup.py - scripts/soundplay_node.py - scripts/test.py - scripts/test_actionlib_client.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) +catkin_install_python(PROGRAMS + scripts/playbuiltin.py + scripts/play.py + scripts/say.py + scripts/shutup.py + scripts/soundplay_node.py + scripts/test.py + scripts/test_actionlib_client.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(FILES - soundplay_node.launch - test.launch - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + soundplay_node.launch + test.launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) install(DIRECTORY sounds DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + +# if(CATKIN_ENABLE_TESTING) +# catkin_add_nosetests(scripts/test) +# add_subdirectory(test) +# endif() diff --git a/sound_play/package.xml b/sound_play/package.xml index cf89c78f..92a9a8ca 100644 --- a/sound_play/package.xml +++ b/sound_play/package.xml @@ -1,4 +1,8 @@ - + + + sound_play 0.3.4 @@ -12,6 +16,8 @@ https://github.com/ros-drivers/audio_common/issues catkin + python-setuptools + python3-setuptools roscpp roslib @@ -21,21 +27,22 @@ diagnostic_msgs message_generation - roscpp - roslib - actionlib_msgs - audio_common_msgs - diagnostic_msgs + roscpp + roslib + actionlib_msgs + audio_common_msgs + diagnostic_msgs - python-gi - gstreamer1.0 - gstreamer1.0-plugins-base - gstreamer1.0-plugins-ugly - gstreamer1.0-plugins-good + python-gi + python3-gi + gstreamer1.0 + gstreamer1.0-plugins-base + gstreamer1.0-plugins-ugly + gstreamer1.0-plugins-good - rospy - festival - message_runtime + rospy + festival + message_runtime diff --git a/sound_play/setup.py b/sound_play/setup.py index e335d64a..29c05038 100644 --- a/sound_play/setup.py +++ b/sound_play/setup.py @@ -1,6 +1,4 @@ -#!/usr/bin/env python - -from distutils.core import setup +from setuptools import setup from catkin_pkg.python_setup import generate_distutils_setup d = generate_distutils_setup( diff --git a/sound_play/src/sound_play/__init__.py b/sound_play/src/sound_play/__init__.py index fa64a038..8a611cb3 100644 --- a/sound_play/src/sound_play/__init__.py +++ b/sound_play/src/sound_play/__init__.py @@ -30,4 +30,4 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -import libsoundplay as libsoundplay +import sound_play.libsoundplay as libsoundplay diff --git a/sound_play/src/sound_play/libsoundplay.py b/sound_play/src/sound_play/libsoundplay.py index 6254fb88..b1622a62 100644 --- a/sound_play/src/sound_play/libsoundplay.py +++ b/sound_play/src/sound_play/libsoundplay.py @@ -1,5 +1,3 @@ -#!/usr/bin/env python - #*********************************************************** #* Software License Agreement (BSD License) #*