diff --git a/.github/labeler.yml b/.github/labeler.yml deleted file mode 100644 index 941f46ff3..000000000 --- a/.github/labeler.yml +++ /dev/null @@ -1,14 +0,0 @@ -github-action: - - .github/**/* -audio_capture: - - audio_capture/**/* -audio_common: - - audio_common/**/* -audio_common_msgs: - - audio_common_msgs/**/* -audio_play: - - audio_play/**/* -sound_play: - - sound_play/**/* -readme: - - REAEME.md diff --git a/.github/workflows/labeler.yml b/.github/workflows/labeler.yml deleted file mode 100644 index 72e4b415f..000000000 --- a/.github/workflows/labeler.yml +++ /dev/null @@ -1,17 +0,0 @@ -name: "Pull Request Labeler" -on: -- pull_request_target - -permissions: - contents: read - -jobs: - triage: - permissions: - contents: read - pull-requests: write - runs-on: ubuntu-latest - steps: - - uses: actions/labeler@v3 - with: - repo-token: "${{ secrets.GITHUB_TOKEN }}" diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml deleted file mode 100644 index 784d44e64..000000000 --- a/.github/workflows/main.yml +++ /dev/null @@ -1,28 +0,0 @@ -name: ROS1 CI -on: - push: - pull_request: - schedule: - - cron: "0 0 * * *" -jobs: - industrial_ci: - strategy: - matrix: - env: - - ROS_DISTRO: melodic - ROS_REPO: testing - CMAKE_ARGS: '-DCMAKE_BUILD_TYPE=Debug' - - ROS_DISTRO: melodic - ROS_REPO: testing - CMAKE_ARGS: '-DCMAKE_BUILD_TYPE=Release' - - ROS_DISTRO: noetic - ROS_REPO: testing - CMAKE_ARGS: '-DCMAKE_BUILD_TYPE=Debug' - - ROS_DISTRO: noetic - ROS_REPO: testing - CMAKE_ARGS: '-DCMAKE_BUILD_TYPE=Release' - runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v1 - - uses: 'ros-industrial/industrial_ci@master' - env: ${{matrix.env}} diff --git a/audio_play/CHANGELOG.rst b/CHANGELOG.rst similarity index 100% rename from audio_play/CHANGELOG.rst rename to CHANGELOG.rst diff --git a/audio_play/CMakeLists.txt b/CMakeLists.txt similarity index 100% rename from audio_play/CMakeLists.txt rename to CMakeLists.txt diff --git a/LICENSE b/LICENSE deleted file mode 100644 index c319170e5..000000000 --- a/LICENSE +++ /dev/null @@ -1,29 +0,0 @@ -BSD 3-Clause License - -Copyright (c) 2009, Willow Garage, Inc. -All rights reserved. - -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this - list of conditions and the following disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - -3. Neither the name of the copyright holder nor the names of its - contributors may be used to endorse or promote products derived from - this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE -FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/README.md b/README.md deleted file mode 100644 index 29b0ea27b..000000000 --- a/README.md +++ /dev/null @@ -1,37 +0,0 @@ -# ROS audio\_common Package - -[![ROS1 CI](https://github.com/ros-drivers/audio_common/actions/workflows/main.yml/badge.svg)](https://github.com/ros-drivers/audio_common/actions/workflows/main.yml) -[![ROS2 CI](https://github.com/ros-drivers/audio_common/actions/workflows/ros2.yml/badge.svg)](https://github.com/ros-drivers/audio_common/actions/workflows/ros2.yml) - -This repository contains the ROS audio\_common package. - -For user documentation, please refer to the [ROS Wiki page for audio\_common](http://wiki.ros.org/audio_common) - -## Deb Build Status - -| Package | Melodic (Bionic) | Noetic (Focal) | Noetic (Buster) | -|:---------------------|:-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|:---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|:-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| -| audio_common (arm64) | [![Build Status](http://build.ros.org/job/Mbin_ubv8_uBv8__audio_common__ubuntu_bionic_arm64__binary/badge/icon)](http://build.ros.org/job/Mbin_ubv8_uBv8__audio_common__ubuntu_bionic_arm64__binary) | [![Build Status](http://build.ros.org/job/Nbin_ufv8_uFv8__audio_common__ubuntu_focal_arm64__binary/badge/icon)](http://build.ros.org/job/Nbin_ufv8_uFv8__audio_common__ubuntu_focal_arm64__binary) | [![Build Status](http://build.ros.org/job/Nbin_dbv8_dBv8__audio_common__debian_buster_arm64__binary/badge/icon)](http://build.ros.org/job/Nbin_dbv8_dBv8__audio_common__debian_buster_arm64__binary) | -| audio_common (armhf) | [![Build Status](http://build.ros.org/job/Mbin_ubhf_uBhf__audio_common__ubuntu_bionic_armhf__binary/badge/icon)](http://build.ros.org/job/Mbin_ubhf_uBhf__audio_common__ubuntu_bionic_armhf__binary) | [![Build Status](http://build.ros.org/job/Nbin_ufhf_uFhf__audio_common__ubuntu_focal_armhf__binary/badge/icon)](http://build.ros.org/job/Nbin_ufhf_uFhf__audio_common__ubuntu_focal_armhf__binary) | --- | -| audio_common (i386) | --- | --- | --- | -| audio_common (amd64) | [![Build Status](http://build.ros.org/job/Mbin_uB64__audio_common__ubuntu_bionic_amd64__binary/badge/icon)](http://build.ros.org/job/Mbin_uB64__audio_common__ubuntu_bionic_amd64__binary) | [![Build Status](http://build.ros.org/job/Nbin_uF64__audio_common__ubuntu_focal_amd64__binary/badge/icon)](http://build.ros.org/job/Nbin_uF64__audio_common__ubuntu_focal_amd64__binary) | [![Build Status](http://build.ros.org/job/Nbin_db_dB64__audio_common__debian_buster_amd64__binary/badge/icon)](http://build.ros.org/job/Nbin_db_dB64__audio_common__debian_buster_amd64__binary) | - -## ROS1 source build - -On ROS Kinetic, Melodic and Noetic, the [master](https://github.com/ros-drivers/audio_common/tree/master) branch is recommended. - -## ROS2 source build - -On ROS2, the [ros2](https://github.com/ros-drivers/audio_common/tree/ros2) branch is recommended - -## Development, Branch and Release Policy - -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) - -## Support - -Please ask support questions on [ROS Answers](http://answers.ros.org/questions/). diff --git a/audio_capture/CHANGELOG.rst b/audio_capture/CHANGELOG.rst deleted file mode 100644 index 799d52b16..000000000 --- a/audio_capture/CHANGELOG.rst +++ /dev/null @@ -1,220 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package audio_capture -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.3.18 (2024-08-13) -------------------- - -0.3.17 (2023-06-08) -------------------- -* Merge pull request `#220 `_ from v4hn/master -* on real systems publish system clock time in capture node -* The capture node is hard-coded to alsasrc -* Contributors: Shingo Kitagawa, v4hn - -0.3.16 (2022-12-23) -------------------- -* Merge pull request `#204 `_ from knorth55/audio-capture-stamped -* add todo comment -* publish audio stamped in audio_capture.cpp -* Merge pull request `#216 `_ from knorth55/launch-update -* update audio_capture launch -* Contributors: Shingo Kitagawa - -0.3.15 (2022-08-29) -------------------- - -0.3.14 (2022-08-18) -------------------- - -0.3.13 (2022-04-07) -------------------- - -0.3.12 (2021-09-01) -------------------- -* Merge branch 'master' into master -* Contributors: Shingo Kitagawa - -0.3.11 (2021-04-08) -------------------- - -0.3.10 (2021-01-07) -------------------- -* add bitrate in capture launch -* [audio_capture] Publish audio info once before publishing /audio -* Contributors: Naoya Yamaguchi, Shingo Kitagawa - -0.3.9 (2020-10-22) ------------------- -* Merge pull request `#160 `_ from knorth55/add-device-play -* use ROS_INFO instead of printf -* Contributors: Shingo Kitagawa - -0.3.8 (2020-09-13) ------------------- - -0.3.7 (2020-08-08) ------------------- -* Merge pull request `#150 `_ from sktometometo/fix_mp3_options - Fix property of lamemp3enc element in audio_capture so that the bitrate parameter work properly. -* fix property of lamemp3enc element so that it will use the specified bitrate -* Merge pull request `#146 `_ from knorth55/mp3-support -* use space instead of tab -* use same caps -* support channls for mp3 -* Merge pull request `#145 `_ from knorth55/mp3-channel-rate - [audio_capture] add sample_format in audio_capture -* Merge pull request `#147 `_ from knorth55/fix-filesink - [audio_capture] fix filesink for wave format -* add sample_format arg in capture_to_file.launch -* fix filesink for wave format -* add sample_format in audio_capture -* Contributors: Koki Shinjo, Shingo Kitagawa - -0.3.6 (2020-05-29) ------------------- -* Merge pull request `#141 `_ from knorth55/add-maintainer - add maintainer -* add maintainer -* Contributors: Shingo Kitagawa - -0.3.5 (2020-04-28) ------------------- - -0.3.4 (2020-04-02) ------------------- -* Merge branch 'master' of github.com:ros-drivers/audio_common -* Contributors: Gerard Canal - -0.3.3 (2018-05-22) ------------------- - -0.3.2 (2018-05-02) ------------------- -* [sound_play] add option to select audio device to play / record (`#87 `_) - * [sound_play] add option to select audio device to play - * [sound_play] reformat README to markdown; add usage to set device via rosparam - * audio_capture: add option for selecting device to use - * audio_play: add option to select device for playing audio - * add device argument to launch files - Conflicts: - audio_capture/launch/capture.launch - audio_capture/launch/capture_to_file.launch - audio_capture/src/audio_capture.cpp - audio_play/launch/play.launch - sound_play/scripts/soundplay_node.py -* Merge pull request `#102 `_ from EndPointCorp/fix_capture_leak - Fix audio_capture leak -* Fix audio_capture sample/buffer leak -* Merge pull request `#90 `_ from prarobo/master - Error checking code and improvements to launch files -* Bug fix -* fix(audio_capture): capturing wave using gst1.0 - 0.10-style raw audio caps were being created, according to GStreamer warning. Should be audio/x-raw,format=(string).. now. -* Merge pull request `#1 `_ from prarobo/fixes - Error checking code and improvements to launch files -* Removed default device -* Added error checking code -* Added parameters to launch files -* Contributors: Austin, Matt Vollrath, Prasanna Kannappan, Rokus, Yuki Furuta, prarobo - -0.3.1 (2016-08-28) ------------------- -* Update to new gstreamer rosdeps -* #70 can launch these in different namespaces with different microphones, and both are operating. -* #70 can switch between different microphones, but the first microphone doesn't like the hw:1, it only works with device:="" - so must be doing something wrong still. -* Add changelogs -* [audio_capture] add error handler -* [audio_capture] add option to publish captured audio data as wav format - Conflicts: - audio_capture/src/audio_capture.cpp -* Fixed memory leak (see #18). -* Removed trailing whitespace. -* Fixed problem that CMake uses gstreamer-0.1 instead of gstreamer-1.0 -* Added gstreamer 1.0 dependecies -* Ported to gstreamer 1.0 - package.xml dependencies still missing -* Update maintainer email -* Contributors: Benny, Felix Duvallet, Furushchev, Lucas Walter, trainman419 - -0.2.11 (2016-02-16) -------------------- -* Add changelogs -* Contributors: trainman419 - -0.2.10 (2016-01-21) -------------------- -* Add changelogs -* Contributors: trainman419 - -0.2.9 (2015-12-02) ------------------- -* Add changelogs -* [audio_capture] add error handler -* [audio_capture] add option to publish captured audio data as wav format -* Fixed memory leak (see `#18 `_). -* Removed trailing whitespace. -* Contributors: Felix Duvallet, Furushchev, trainman419 - -0.2.8 (2015-10-02) ------------------- -* Update maintainer email -* Contributors: trainman419 - -0.2.7 (2014-07-25) ------------------- -* audio_capture.cpp has to wait for generated AudioData headers -* Contributors: v4hn - -0.2.6 (2014-02-26) ------------------- -* audio_capture and play _require\_ gstreamer, it's not optional -* Contributors: v4hn - -0.2.5 (2014-01-23) ------------------- -* "0.2.5" -* Contributors: trainman419 - -0.2.4 (2013-09-10) ------------------- -* Update CMakeLists.txt -* audio_capture: install launchfiles -* Contributors: David Gossow - -0.2.3 (2013-07-15) ------------------- -* Fix install rule for audio_capture. -* Contributors: Austin Hendrix - -0.2.2 (2013-04-10) ------------------- - -0.2.1 (2013-04-08 13:59) ------------------------- - -0.2.0 (2013-04-08 13:49) ------------------------- -* Finish catkinizing audio_common. -* Catkinize audio_play. -* Catkinize audio_capture. -* Fix typo in package.xml -* Versions and more URLs. -* Convert manifests to package.xml -* Convert audio_capture manifest to package.xml -* Ditch old makefiles. -* Updates manifest -* Updated manifests for rodep2 -* oneiric build fixes, bump version to 0.1.6 -* Removed redundant thread::thread -* Added a rosdep.yaml file -* Fixed to use audio_common_msgs -* Added ability to use different festival voices -* Updated documentation -* Added ability to capture to file -* Fixed ignore files -* Added hgignore files -* Audio_capture and audio_play working -* Making separate audio_capture and audio_play packages -* Moved audio_transport to audio_capture -* Contributors: Austin Hendrix, Brian Gerkey, Nate Koenig, nkoenig diff --git a/audio_capture/CMakeLists.txt b/audio_capture/CMakeLists.txt deleted file mode 100644 index 0bc0b116c..000000000 --- a/audio_capture/CMakeLists.txt +++ /dev/null @@ -1,24 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) - -project(audio_capture) - -find_package(catkin REQUIRED COMPONENTS roscpp audio_common_msgs) - -find_package(PkgConfig) -pkg_check_modules(GST1.0 gstreamer-1.0 REQUIRED) - -find_package(Boost REQUIRED COMPONENTS thread) - -include_directories(${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} ${GST1.0_INCLUDE_DIRS}) - -catkin_package() - -add_executable(audio_capture src/audio_capture.cpp) -target_link_libraries(audio_capture ${catkin_LIBRARIES} ${GST1.0_LIBRARIES} ${Boost_LIBRARIES}) -add_dependencies(audio_capture ${catkin_EXPORTED_TARGETS}) - -install(TARGETS audio_capture - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) - -install(DIRECTORY launch - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/audio_capture/launch/capture.launch b/audio_capture/launch/capture.launch deleted file mode 100644 index 6495bb214..000000000 --- a/audio_capture/launch/capture.launch +++ /dev/null @@ -1,30 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/audio_capture/launch/capture_to_file.launch b/audio_capture/launch/capture_to_file.launch deleted file mode 100644 index d81ef6534..000000000 --- a/audio_capture/launch/capture_to_file.launch +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/audio_capture/launch/capture_wave.launch b/audio_capture/launch/capture_wave.launch deleted file mode 100644 index 5daf779c9..000000000 --- a/audio_capture/launch/capture_wave.launch +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/audio_capture/mainpage.dox b/audio_capture/mainpage.dox deleted file mode 100644 index 4733f766e..000000000 --- a/audio_capture/mainpage.dox +++ /dev/null @@ -1,21 +0,0 @@ -/** -\mainpage -\htmlinclude manifest.html - -\b audio_capture is a package that records audio from a microphone and makes it available to other ROS nodes. - -\section codeapi Code API - - - - -*/ diff --git a/audio_capture/package.xml b/audio_capture/package.xml deleted file mode 100644 index d517ef4b5..000000000 --- a/audio_capture/package.xml +++ /dev/null @@ -1,31 +0,0 @@ - - audio_capture - 0.3.18 - - Transports audio from a source to a destination. Audio sources can come - from a microphone or file. The destination can play the audio or save it - to an mp3 file. - - Austin Hendrix - Shingo Kitagawa - Nate Koenig - BSD - http://ros.org/wiki/audio_capture - https://github.com/ros-drivers/audio_common - https://github.com/ros-drivers/audio_common/issues - - catkin - - roscpp - audio_common_msgs - libgstreamer1.0-dev - libgstreamer-plugins-base1.0-dev - - roscpp - audio_common_msgs - gstreamer1.0 - gstreamer1.0-alsa - gstreamer1.0-plugins-base - gstreamer1.0-plugins-good - gstreamer1.0-plugins-ugly - diff --git a/audio_capture/src/audio_capture.cpp b/audio_capture/src/audio_capture.cpp deleted file mode 100644 index 0ef67a878..000000000 --- a/audio_capture/src/audio_capture.cpp +++ /dev/null @@ -1,263 +0,0 @@ -#include -#include -#include -#include - -#include - -#include "audio_common_msgs/AudioData.h" -#include "audio_common_msgs/AudioDataStamped.h" -#include "audio_common_msgs/AudioInfo.h" - -namespace audio_transport -{ - class RosGstCapture - { - public: - RosGstCapture() - { - _bitrate = 192; - - std::string dst_type; - - // Need to encoding or publish raw wave data - ros::param::param("~format", _format, "mp3"); - ros::param::param("~sample_format", _sample_format, "S16LE"); - - // The bitrate at which to encode the audio - ros::param::param("~bitrate", _bitrate, 192); - - // only available for raw data - ros::param::param("~channels", _channels, 1); - ros::param::param("~depth", _depth, 16); - ros::param::param("~sample_rate", _sample_rate, 16000); - - // The destination of the audio - ros::param::param("~dst", dst_type, "appsink"); - - // The source of the audio - //ros::param::param("~src", source_type, "alsasrc"); - std::string device; - ros::param::param("~device", device, ""); - - _pub = _nh.advertise("audio", 10, true); - _pub_stamped = _nh.advertise("audio_stamped", 10, true); - _pub_info = _nh.advertise("audio_info", 1, true); - - _loop = g_main_loop_new(NULL, false); - _pipeline = gst_pipeline_new("ros_pipeline"); - GstClock *clock = gst_system_clock_obtain(); - g_object_set(clock, "clock-type", GST_CLOCK_TYPE_REALTIME, NULL); - gst_pipeline_use_clock(GST_PIPELINE_CAST(_pipeline), clock); - gst_object_unref(clock); - - _bus = gst_pipeline_get_bus(GST_PIPELINE(_pipeline)); - gst_bus_add_signal_watch(_bus); - g_signal_connect(_bus, "message::error", - G_CALLBACK(onMessage), this); - g_object_unref(_bus); - - // We create the sink first, just for convenience - if (dst_type == "appsink") - { - _sink = gst_element_factory_make("appsink", "sink"); - g_object_set(G_OBJECT(_sink), "emit-signals", true, NULL); - g_object_set(G_OBJECT(_sink), "max-buffers", 100, NULL); - g_signal_connect( G_OBJECT(_sink), "new-sample", - G_CALLBACK(onNewBuffer), this); - } - else - { - ROS_INFO("file sink to %s", dst_type.c_str()); - _sink = gst_element_factory_make("filesink", "sink"); - g_object_set( G_OBJECT(_sink), "location", dst_type.c_str(), NULL); - } - - _source = gst_element_factory_make("alsasrc", "source"); - // if device isn't specified, it will use the default which is - // the alsa default source. - // A valid device will be of the foram hw:0,0 with other numbers - // than 0 and 0 as are available. - if (device != "") - { - // ghcar *gst_device = device.c_str(); - g_object_set(G_OBJECT(_source), "device", device.c_str(), NULL); - } - - GstCaps *caps; - caps = gst_caps_new_simple("audio/x-raw", - "format", G_TYPE_STRING, _sample_format.c_str(), - "channels", G_TYPE_INT, _channels, - "width", G_TYPE_INT, _depth, - "depth", G_TYPE_INT, _depth, - "rate", G_TYPE_INT, _sample_rate, - "signed", G_TYPE_BOOLEAN, TRUE, - NULL); - - gboolean link_ok; - if (_format == "mp3"){ - _filter = gst_element_factory_make("capsfilter", "filter"); - g_object_set( G_OBJECT(_filter), "caps", caps, NULL); - gst_caps_unref(caps); - - _convert = gst_element_factory_make("audioconvert", "convert"); - if (!_convert) { - ROS_ERROR_STREAM("Failed to create audioconvert element"); - exitOnMainThread(1); - } - - _encode = gst_element_factory_make("lamemp3enc", "encoder"); - if (!_encode) { - ROS_ERROR_STREAM("Failed to create encoder element"); - exitOnMainThread(1); - } - g_object_set( G_OBJECT(_encode), "target", 1, NULL); - g_object_set( G_OBJECT(_encode), "bitrate", _bitrate, NULL); - - gst_bin_add_many( GST_BIN(_pipeline), _source, _filter, _convert, _encode, _sink, NULL); - link_ok = gst_element_link_many(_source, _filter, _convert, _encode, _sink, NULL); - } else if (_format == "wave") { - if (dst_type == "appsink") { - g_object_set( G_OBJECT(_sink), "caps", caps, NULL); - gst_caps_unref(caps); - gst_bin_add_many( GST_BIN(_pipeline), _source, _sink, NULL); - link_ok = gst_element_link_many( _source, _sink, NULL); - } else { - _filter = gst_element_factory_make("wavenc", "filter"); - gst_bin_add_many( GST_BIN(_pipeline), _source, _filter, _sink, NULL); - link_ok = gst_element_link_many( _source, _filter, _sink, NULL); - } - } else { - ROS_ERROR_STREAM("format must be \"wave\" or \"mp3\""); - exitOnMainThread(1); - } - /*} - else - { - _sleep_time = 10000; - _source = gst_element_factory_make("filesrc", "source"); - g_object_set(G_OBJECT(_source), "location", source_type.c_str(), NULL); - - gst_bin_add_many( GST_BIN(_pipeline), _source, _sink, NULL); - gst_element_link_many(_source, _sink, NULL); - } - */ - - if (!link_ok) { - ROS_ERROR_STREAM("Unsupported media type."); - exitOnMainThread(1); - } - - gst_element_set_state(GST_ELEMENT(_pipeline), GST_STATE_PLAYING); - - _gst_thread = boost::thread( boost::bind(g_main_loop_run, _loop) ); - - audio_common_msgs::AudioInfo info_msg; - info_msg.channels = _channels; - info_msg.sample_rate = _sample_rate; - info_msg.sample_format = _sample_format; - info_msg.bitrate = _bitrate; - info_msg.coding_format = _format; - _pub_info.publish(info_msg); - } - - ~RosGstCapture() - { - g_main_loop_quit(_loop); - gst_element_set_state(_pipeline, GST_STATE_NULL); - gst_object_unref(_pipeline); - g_main_loop_unref(_loop); - } - - void exitOnMainThread(int code) - { - exit(code); - } - - void publish( const audio_common_msgs::AudioData &msg ) - { - _pub.publish(msg); - } - - void publishStamped( const audio_common_msgs::AudioDataStamped &msg ) - { - _pub_stamped.publish(msg); - } - - static GstFlowReturn onNewBuffer (GstAppSink *appsink, gpointer userData) - { - audio_common_msgs::AudioData msg; - audio_common_msgs::AudioDataStamped stamped_msg; - - RosGstCapture *server = reinterpret_cast(userData); - GstMapInfo map; - - GstSample *sample; - g_signal_emit_by_name(appsink, "pull-sample", &sample); - - GstBuffer *buffer = gst_sample_get_buffer(sample); - - if( ros::Time::isSimTime() ) - { - stamped_msg.header.stamp = ros::Time::now(); - } - else - { - GstClockTime buffer_time = gst_element_get_base_time(server->_source)+GST_BUFFER_PTS(buffer); - stamped_msg.header.stamp.fromNSec(buffer_time); - } - - gst_buffer_map(buffer, &map, GST_MAP_READ); - msg.data.resize( map.size ); - - memcpy( &msg.data[0], map.data, map.size ); - stamped_msg.audio = msg; - - gst_buffer_unmap(buffer, &map); - gst_sample_unref(sample); - - server->publish(msg); - server->publishStamped(stamped_msg); - - return GST_FLOW_OK; - } - - static gboolean onMessage (GstBus *bus, GstMessage *message, gpointer userData) - { - RosGstCapture *server = reinterpret_cast(userData); - GError *err; - gchar *debug; - - gst_message_parse_error(message, &err, &debug); - ROS_ERROR_STREAM("gstreamer: " << err->message); - g_error_free(err); - g_free(debug); - g_main_loop_quit(server->_loop); - server->exitOnMainThread(1); - return FALSE; - } - - private: - ros::NodeHandle _nh; - ros::Publisher _pub; - ros::Publisher _pub_stamped; - ros::Publisher _pub_info; - - boost::thread _gst_thread; - - GstElement *_pipeline, *_source, *_filter, *_sink, *_convert, *_encode; - GstBus *_bus; - int _bitrate, _channels, _depth, _sample_rate; - GMainLoop *_loop; - std::string _format, _sample_format; - }; -} - -int main (int argc, char **argv) -{ - ros::init(argc, argv, "audio_capture"); - gst_init(&argc, &argv); - - audio_transport::RosGstCapture server; - ros::spin(); -} diff --git a/audio_common/CHANGELOG.rst b/audio_common/CHANGELOG.rst deleted file mode 100644 index 638153081..000000000 --- a/audio_common/CHANGELOG.rst +++ /dev/null @@ -1,120 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package audio_common -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.3.18 (2024-08-13) -------------------- - -0.3.17 (2023-06-08) -------------------- - -0.3.16 (2022-12-23) -------------------- - -0.3.15 (2022-08-29) -------------------- - -0.3.14 (2022-08-18) -------------------- - -0.3.13 (2022-04-07) -------------------- - -0.3.12 (2021-09-01) -------------------- -* Merge branch 'master' into master -* Contributors: Shingo Kitagawa - -0.3.11 (2021-04-08) -------------------- - -0.3.10 (2021-01-07) -------------------- - -0.3.9 (2020-10-22) ------------------- - -0.3.8 (2020-09-13) ------------------- - -0.3.7 (2020-08-08) ------------------- - -0.3.6 (2020-05-29) ------------------- -* Merge pull request `#141 `_ from knorth55/add-maintainer - add maintainer -* add maintainer -* Contributors: Shingo Kitagawa - -0.3.5 (2020-04-28) ------------------- - -0.3.4 (2020-04-02) ------------------- -* Merge branch 'master' of github.com:ros-drivers/audio_common -* Contributors: Gerard Canal - -0.3.3 (2018-05-22) ------------------- - -0.3.2 (2018-05-02) ------------------- - -0.3.1 (2016-08-28) ------------------- -* Add changelogs -* Update maintainer email -* Contributors: trainman419 - -0.2.11 (2016-02-16) -------------------- -* Add changelogs -* Contributors: trainman419 - -0.2.10 (2016-01-21) -------------------- -* Add changelogs -* Contributors: trainman419 - -0.2.9 (2015-12-02) ------------------- -* Add changelogs -* Contributors: trainman419 - -0.2.8 (2015-10-02) ------------------- -* Update maintainer email -* Contributors: trainman419 - -0.2.7 (2014-07-25) ------------------- - -0.2.6 (2014-02-26) ------------------- - -0.2.5 (2014-01-23) ------------------- -* "0.2.5" -* Contributors: trainman419 - -0.2.4 (2013-09-10) ------------------- - -0.2.3 (2013-07-15) ------------------- - -0.2.2 (2013-04-10) ------------------- - -0.2.1 (2013-04-08 13:59) ------------------------- -* Fix metapackage for REP 127. -* Contributors: Austin Hendrix - -0.2.0 (2013-04-08 13:49) ------------------------- -* Versions and more URLs. -* Convert stack.xml to metapackage package.xml -* Start catkinizing. -* Contributors: Austin Hendrix diff --git a/audio_common/CMakeLists.txt b/audio_common/CMakeLists.txt deleted file mode 100644 index d0f5151e0..000000000 --- a/audio_common/CMakeLists.txt +++ /dev/null @@ -1,4 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(audio_common) -find_package(catkin REQUIRED) -catkin_metapackage() diff --git a/audio_common/package.xml b/audio_common/package.xml deleted file mode 100644 index f82716434..000000000 --- a/audio_common/package.xml +++ /dev/null @@ -1,25 +0,0 @@ - - audio_common - 0.3.18 - - Common code for working with audio in ROS - - Austin Hendrix - Shingo Kitagawa - Blaise Gassend - BSD - http://ros.org/wiki/audio_common - https://github.com/ros-drivers/audio_common - https://github.com/ros-drivers/audio_common/issues - - catkin - - audio_capture - audio_common_msgs - audio_play - sound_play - - - - - diff --git a/audio_common_msgs/CHANGELOG.rst b/audio_common_msgs/CHANGELOG.rst deleted file mode 100644 index 27f3a76bd..000000000 --- a/audio_common_msgs/CHANGELOG.rst +++ /dev/null @@ -1,127 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package audio_common_msgs -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.3.18 (2024-08-13) -------------------- - -0.3.17 (2023-06-08) -------------------- - -0.3.16 (2022-12-23) -------------------- -* Merge pull request `#202 `_ from knorth55/audio-stamped-msg -* add AudioDataStamped.msg -* Contributors: Shingo Kitagawa - -0.3.15 (2022-08-29) -------------------- - -0.3.14 (2022-08-18) -------------------- - -0.3.13 (2022-04-07) -------------------- - -0.3.12 (2021-09-01) -------------------- -* Merge branch 'master' into master -* Contributors: Shingo Kitagawa - -0.3.11 (2021-04-08) -------------------- - -0.3.10 (2021-01-07) -------------------- -* Change comment style in AudioInfo.msg -* [audio_common_msgs] AudioInfo.msg to add audio meta data -* Contributors: Naoya Yamaguchi - -0.3.9 (2020-10-22) ------------------- - -0.3.8 (2020-09-13) ------------------- - -0.3.7 (2020-08-08) ------------------- - -0.3.6 (2020-05-29) ------------------- -* Merge pull request `#141 `_ from knorth55/add-maintainer - add maintainer -* add maintainer -* Contributors: Shingo Kitagawa - -0.3.5 (2020-04-28) ------------------- - -0.3.4 (2020-04-02) ------------------- -* Merge branch 'master' of github.com:ros-drivers/audio_common -* Contributors: Gerard Canal - -0.3.3 (2018-05-22) ------------------- - -0.3.2 (2018-05-02) ------------------- - -0.3.1 (2016-08-28) ------------------- -* Add changelogs -* Update maintainer email -* Contributors: trainman419 - -0.2.11 (2016-02-16) -------------------- -* Add changelogs -* Contributors: trainman419 - -0.2.10 (2016-01-21) -------------------- -* Add changelogs -* Contributors: trainman419 - -0.2.9 (2015-12-02) ------------------- -* Add changelogs -* Contributors: trainman419 - -0.2.8 (2015-10-02) ------------------- -* Update maintainer email -* Contributors: trainman419 - -0.2.7 (2014-07-25) ------------------- - -0.2.6 (2014-02-26) ------------------- - -0.2.5 (2014-01-23) ------------------- -* "0.2.5" -* Contributors: trainman419 - -0.2.4 (2013-09-10) ------------------- - -0.2.3 (2013-07-15) ------------------- - -0.2.2 (2013-04-10) ------------------- - -0.2.1 (2013-04-08 13:59) ------------------------- - -0.2.0 (2013-04-08 13:49) ------------------------- -* Catkinize audio_common_msgs. -* Versions and more URLs. -* Convert manifests to package.xml -* Ditch old makefiles. -* Fixed audio_msgs names to audio_common_msgs -* Renamed audio_msgs to audio_common_msgs -* Contributors: Austin Hendrix, Nate Koenig diff --git a/audio_common_msgs/CMakeLists.txt b/audio_common_msgs/CMakeLists.txt deleted file mode 100644 index 3b06fdb6d..000000000 --- a/audio_common_msgs/CMakeLists.txt +++ /dev/null @@ -1,22 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) - -project(audio_common_msgs) - -find_package(catkin REQUIRED - COMPONENTS - message_generation - std_msgs -) - -add_message_files(DIRECTORY msg FILES - AudioData.msg - AudioDataStamped.msg - AudioInfo.msg - ) - -generate_messages( - DEPENDENCIES - std_msgs -) - -catkin_package(CATKIN_DEPENDS message_runtime) diff --git a/audio_common_msgs/mainpage.dox b/audio_common_msgs/mainpage.dox deleted file mode 100644 index 24249e466..000000000 --- a/audio_common_msgs/mainpage.dox +++ /dev/null @@ -1,11 +0,0 @@ -/** -\mainpage -\htmlinclude manifest.html - -\b audio_common_msgs contain messages for transimitting audio via ROS. - - -\section codeapi Code API - - -*/ diff --git a/audio_common_msgs/msg/AudioData.msg b/audio_common_msgs/msg/AudioData.msg deleted file mode 100644 index dd2331bbe..000000000 --- a/audio_common_msgs/msg/AudioData.msg +++ /dev/null @@ -1 +0,0 @@ -uint8[] data diff --git a/audio_common_msgs/msg/AudioDataStamped.msg b/audio_common_msgs/msg/AudioDataStamped.msg deleted file mode 100644 index 30e7e2b16..000000000 --- a/audio_common_msgs/msg/AudioDataStamped.msg +++ /dev/null @@ -1,2 +0,0 @@ -std_msgs/Header header -audio_common_msgs/AudioData audio diff --git a/audio_common_msgs/msg/AudioInfo.msg b/audio_common_msgs/msg/AudioInfo.msg deleted file mode 100644 index ca4b55e34..000000000 --- a/audio_common_msgs/msg/AudioInfo.msg +++ /dev/null @@ -1,12 +0,0 @@ -# This message contains the audio meta data - -# Number of channels -uint8 channels -# Sampling rate [Hz] -uint32 sample_rate -# Audio format (e.g. S16LE) -string sample_format -# Amount of audio data per second [bits/s] -uint32 bitrate -# Audio coding format (e.g. WAVE, MP3) -string coding_format diff --git a/audio_common_msgs/package.xml b/audio_common_msgs/package.xml deleted file mode 100644 index 75c129679..000000000 --- a/audio_common_msgs/package.xml +++ /dev/null @@ -1,22 +0,0 @@ - - audio_common_msgs - 0.3.18 - - Messages for transmitting audio via ROS - - Austin Hendrix - Shingo Kitagawa - Nate Koenig - BSD - http://ros.org/wiki/audio_common_msgs - https://github.com/ros-drivers/audio_common - https://github.com/ros-drivers/audio_common/issues - - catkin - - message_generation - std_msgs - - message_runtime - std_msgs - diff --git a/audio_play/launch/play.launch b/launch/play.launch similarity index 100% rename from audio_play/launch/play.launch rename to launch/play.launch diff --git a/audio_play/launch/record_to_file.launch b/launch/record_to_file.launch similarity index 100% rename from audio_play/launch/record_to_file.launch rename to launch/record_to_file.launch diff --git a/audio_play/mainpage.dox b/mainpage.dox similarity index 100% rename from audio_play/mainpage.dox rename to mainpage.dox diff --git a/audio_play/package.xml b/package.xml similarity index 100% rename from audio_play/package.xml rename to package.xml diff --git a/sound_play/CHANGELOG.rst b/sound_play/CHANGELOG.rst deleted file mode 100644 index 54d23f048..000000000 --- a/sound_play/CHANGELOG.rst +++ /dev/null @@ -1,418 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package sound_play -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.3.18 (2024-08-13) -------------------- -* Merge pull request `#249 `_ from peci1/patch-1 - festival_plugin: add support for different encodings -* festival_plugin: add support for different encodings -* Contributors: Martin Pecka, Shingo Kitagawa - -0.3.17 (2023-06-08) -------------------- -* Merge pull request `#231 `_ from knorth55/no-wait-mode -* dont wait when rospy.Duration(0) is set for timeout -* Merge pull request `#229 `_ from furushchev/flite-plugin-lazy-load - FlitePlugin: Lazy loading default voice path -* FlitePlugin: Lazy loading default voice path -* Contributors: Shingo Kitagawa, Yuki Furuta - -0.3.16 (2022-12-23) -------------------- -* Merge pull request `#203 `_ from nakane11/timeout -* refactor libsoundplay.py -* Add timeout to wait_for_server and wait_for_result -* Contributors: Aoi Nakane, Shingo Kitagawa - -0.3.15 (2022-08-29) -------------------- -* Merge pull request `#200 `_ from knorth55/yaml-missing -* show error and skip loading when plugin yaml is missing -* Merge pull request `#199 `_ from knorth55/install-plugin-yaml -* fix missing install in CMakeLists.txt -* Contributors: Shingo Kitagawa - -0.3.14 (2022-08-18) -------------------- -* Merge pull request `#193 `_ from knorth55/refactor-soundplay-node -* refactor soundplay_node.py -* Merge pull request `#192 `_ from knorth55/fix-file-open-issue -* fix typo causing file open issue -* Merge pull request `#191 `_ from knorth55/flite-default-voice-dir -* add default voice dir for flite_plugin -* Merge pull request `#190 `_ from ros-drivers/knorth55-patch-1 -* Update soundplay_node.py -* Merge pull request `#187 `_ from knorth55/fix-typo -* fix typo in soundplay_node.py -* Merge pull request `#185 `_ from knorth55/sound-play-flite-plugin - add flite plugin for sound_play -* Merge pull request `#183 `_ from knorth55/sound-play-plugin - add soundplay plugin feature -* add flite in sound_play dependency -* refactor FestivalPlugin -* add flite plugin -* change default_voice to None -* add plugin arg in soundplay_node.launch -* refactor codes -* add output screen in soundplay_node.launch -* add soundplay plugin attribute -* Merge pull request `#184 `_ from knorth55/default-voice -* add default_voice in soundplay_node.launch -* Merge pull request `#182 `_ from iory/is-speaking -* Improve is_speaking by checking goal status -* Merge pull request `#181 `_ from knorth55/refactor-is-speaking -* refactor is_speaking.py -* Contributors: JSK fetch user, Shingo Kitagawa, iory - -0.3.13 (2022-04-07) -------------------- -* Merge pull request `#176 `_ from iory/is-speeching -* Add is_speaking.py to catkin_install_python -* Fixed name speeching to speaking -* Add is_speeching node for checking robot is speaking -* Contributors: Shingo Kitagawa, iory - -0.3.12 (2021-09-01) -------------------- -* Merge pull request `#175 `_ from iory/rate - Modified loop rate for action execution -* Modified loop rate for action execution -* Merge pull request `#131 `_ from yann-bourrigault/master - Handle playing sound in loop -* import GObject in try section -* Merge pull request `#174 `_ from iory/cache - Add arg2 information for cache -* Add arg2 information for cache -* Merge pull request `#173 `_ from knorth55/replace-sound-client -* Merge pull request `#172 `_ from knorth55/start-action-after-init - [sound_play] start ActionServer after initialize in soundplay_node.py -* Merge pull request `#171 `_ from knorth55/set-aborted - [sound_play] add proper set_aborted in soundplay_node.py -* add replace in sendMsg -* start actionserver after initialize in soundplay_node.py -* add proper set_aborted in soundplay_node.py -* Merge branch 'master' into master -* Handle playing sound repeatedly -* Contributors: Shingo Kitagawa, Yann BOURRIGAULT, iory - -0.3.11 (2021-04-08) -------------------- -* Merge pull request `#167 `_ from k-okada/fix_155 -* Use rospy.myargv() instead of sys.argv to support remapping -* Contributors: Kei Okada, Shingo Kitagawa - -0.3.10 (2021-01-07) -------------------- - -0.3.9 (2020-10-22) ------------------- - -0.3.8 (2020-09-13) ------------------- -* Merge pull request `#155 `_ from garaemon/use-myargv - Use rospy.myargv() instead of sys.argv to support remapping -* Use rospy.myargv() instead of sys.argv to support remapping -* Merge pull request `#154 `_ from mikaelarguedas/fix_say_python3 -* update to support no iso-8859-15 language (`#1 `_) - * support non iso-8859-15 language - * encode only for python2 -* convert items to an iterator -* make cleanup compatible with Python 3 -* catch AttributeError to handle python3 strings -* Contributors: Mikael Arguedas, Ryohei Ueda, Shingo Kitagawa - -0.3.7 (2020-08-08) ------------------- -* Merge pull request `#149 `_ from garaemon/specify-topic-to-play-sound - Support use different topic and actionlib to play sound -* Support use different topic and actionlib to play sound - * Add two keywords to the constructor of SoundClient class in order to - specify actionlib namespace and topic name to play sound. - * See `#119 `_. -* Merge pull request `#144 `_ from ros-drivers/knorth55-patch-1 -* add gstreamer1.0-alsa exec_depend in sound_play -* Contributors: Ryohei Ueda, Shingo Kitagawa - -0.3.6 (2020-05-29) ------------------- -* Merge pull request `#140 `_ from knorth55/support-python3 - fix syntax for python3 -* Merge pull request `#141 `_ from knorth55/add-maintainer - add maintainer -* add maintainer -* fix syntax for python3 -* Contributors: Shingo Kitagawa - -0.3.5 (2020-04-28) ------------------- -* Merge pull request `#133 `_ from knorth55/noetic-build -* remove unnecessary shebang -* use setuptools instead of distutils.core -* use package format=3 for python3 -* refactor CMakeLists.txt -* use catkin_install_python for python shebang -* Merge pull request `#135 `_ from knorth55/add-travis -* disable sound_play test -* Contributors: Shingo Kitagawa - -0.3.4 (2020-04-02) ------------------- -* Merge pull request `#126 `_ from itohdak/fix-Gstreamer-memory-leak - [sound_play/scripts/soundplay_node.py] fix Gstreamer memory leak -* Merge pull request `#123 `_ from 708yamaguchi/fix-encode - Do not encode text when using langages which ISO-8859-15 does not support -* [sound_play/scripts/soundplay_node.py] fix Gstreamer memory leak -* do not encode text when using langages which ISO-8859-15 does not support -* Merge pull request `#118 `_ from v4hn/patch-1 - use default audio output by default -* use default audio output by default - Not specifying a sound device defaults to *the first* sound device starting from Ubuntu 16.04., not to the one configured as default. - The change is backward compatible and tested on ROS indigo and kinetic on a PR2 robot. -* Merge pull request `#110 `_ from gerardcanal/master - Encoded text to be said in ISO-8859-15 -* Merge branch 'master' of github.com:ros-drivers/audio_common -* Sound play: Encoded file to be said in ISO-8859-15 so that accents in languages such as Spanish, Catalan or French are correctly pronounced (based on http://festcat.talp.cat/en/usage.php which says festival expects ISO-8859-15 encoding) -* Contributors: Austin, Gerard Canal, Michael Görner, Naoya Yamaguchi, Shingo Kitagawa, itohdak - -0.3.3 (2018-05-22) ------------------- -* Fix gstreamer errors. Fixes `#108 `_ -* Contributors: trainman419 - -0.3.2 (2018-05-02) ------------------- -* [sound_play] add option to select audio device to play / record (`#87 `_) - * [sound_play] add option to select audio device to play - * [sound_play] reformat README to markdown; add usage to set device via rosparam - * audio_capture: add option for selecting device to use - * audio_play: add option to select device for playing audio - * add device argument to launch files - Conflicts: - audio_capture/launch/capture.launch - audio_capture/launch/capture_to_file.launch - audio_capture/src/audio_capture.cpp - audio_play/launch/play.launch - sound_play/scripts/soundplay_node.py -* Merge pull request `#95 `_ from yujinrobot/volume_check - [sound_play] volume check for cached sounds -* [sound_play] checks if sound's Gst instance's volume has changed and resets it -* Contributors: Austin, Naveed Usmani, Yuki Furuta - -0.3.1 (2016-08-28) ------------------- -* Update to new gstreamer rosdeps -* Update sound_play to gstreamer 1.0 -* remove chance of uninitialised variable being called in a subscriber callback. -* Add changelogs -* Issue: The error checks for missing publisher/action client in sendMsg were inverted. - The non-blocking brach tested the action client while the blocking branch - tested the publisher. - Fix: Inverted the blocking boolean for both branchs. -* sound_play: Fix build with -DCATKIN_ENABLE_TESTING=OFF. - https://bugs.gentoo.org/show_bug.cgi?id=567466 -* [soundplay_node] fix resources not being released on dict cleanup - This was resulting in the number of sink inputs reaching the maximum threshold, - (32 on ubuntu 14.04 with pulseaudio 4.0) after which no more sounds could be - played by the node. It would only happen if the rate of sounds being played was - slower than the dictionary cleanup. -* depend on actionlib. -* Introduce unit test to ensure soundclient is started correctly. -* Example of using the explicit blocking parameter to override the class setting. -* SoundClient can also explicitly specify whether or not to block while playing the sound. - Each play/repeat/say/... method can take an option blocking=True|False argument (using **kwargs), which over-rides the class-wide setting. -* Merge pull request #62 from felixduvallet/set_queue_size - Set queue_size in soundplay_node Publisher -* do both in same script. -* Added script showing the various blocking/non-blocking ways of using SoundClient. -* removed trailing whitespace only -* loginfo -> logdebug. -* Slightly more condensed version of thresholding. -* Enable blocking calls inside libsoundplay's SoundClient. - This makes use of the actionlib interface provided by soundplay_node, by ensuring SoundClient receives a response before returning. - Turn this on by: SoundClient(blocking=true). -* Use new-style python classes (inherits from object). -* removed trailing whitespace. -* Set the volume in each of the sound_play actionlib tests. - This makes the script actually play the sounds it requests. -* Specify queue size explicitly. - Removed warning message printed each time soundplay_node was started. -* remove trailing whitespace only. -* Change wiki urls -* Fix test target name collision. Fixes #49 -* sound_play: cpp header conforms to the style guide -* sound_play: update scripts to allow volume to be set -* sound_play: updated tests to include volume changes -* sound_play: add ability to specify volume at which to play sounds - Also changed error to warning as per todo -* sound_play: fix indentation and comment inconsistencies -* sound_play: remove some raw prints cluttering output -* sound_play: added queue_size to SoundClient init - Should prevent warning being displayed whenever the client is created. - Fixes issue #43 -* add simple-actionlib functionality to sound_play -* sound_play: Added functions to play files relative to a package path -* Update maintainer email -* Contributors: Alexis Ballier, Austin, Daniel Stonier, David V. Lu, Felix Duvallet, Matthias Nieuwenhuisen, Michal Staniaszek, Neowizard, aginika, trainman419 - -0.2.11 (2016-02-16) -------------------- -* Add changelogs -* Fix bug in say.py. Fixes `#72 `_ -* Contributors: trainman419 - -0.2.10 (2016-01-21) -------------------- -* Add changelogs -* Issue: The error checks for missing publisher/action client in sendMsg were inverted. - The non-blocking brach tested the action client while the blocking branch - tested the publisher. - Fix: Inverted the blocking boolean for both branchs. -* sound_play: Fix build with -DCATKIN_ENABLE_TESTING=OFF. - https://bugs.gentoo.org/show_bug.cgi?id=567466 -* Contributors: Alexis Ballier, Neowizard, trainman419 - -0.2.9 (2015-12-02) ------------------- -* Add changelogs -* [soundplay_node] fix resources not being released on dict cleanup - This was resulting in the number of sink inputs reaching the maximum threshold, - (32 on ubuntu 14.04 with pulseaudio 4.0) after which no more sounds could be - played by the node. It would only happen if the rate of sounds being played was - slower than the dictionary cleanup. -* depend on actionlib. -* Introduce unit test to ensure soundclient is started correctly. -* Example of using the explicit blocking parameter to override the class setting. -* SoundClient can also explicitly specify whether or not to block while playing the sound. - Each play/repeat/say/... method can take an option blocking=True|False argument (using **kwargs), which over-rides the class-wide setting. - Conflicts: - sound_play/src/sound_play/libsoundplay.py -* do both in same script. -* Added script showing the various blocking/non-blocking ways of using SoundClient. -* removed trailing whitespace only - Conflicts: - sound_play/scripts/say.py -* loginfo -> logdebug. -* Enable blocking calls inside libsoundplay's SoundClient. - This makes use of the actionlib interface provided by soundplay_node, by ensuring SoundClient receives a response before returning. - Turn this on by: SoundClient(blocking=true). - Conflicts: - sound_play/src/sound_play/libsoundplay.py -* Use new-style python classes (inherits from object). - Conflicts: - sound_play/src/sound_play/libsoundplay.py -* removed trailing whitespace. - Conflicts: - sound_play/src/sound_play/libsoundplay.py -* Revert "Set the volume in each of the sound_play actionlib tests." - This reverts commit 55ab08c882809fc6d21affb849a7dac9f1901867. - Indigo-devel does not have the volume API -* Set the volume in each of the sound_play actionlib tests. - This makes the script actually play the sounds it requests. -* Specify queue size explicitly. - Removed warning message printed each time soundplay_node was started. -* remove trailing whitespace only. -* Fix wiki links -* Contributors: David V. Lu, Felix Duvallet, Michal Staniaszek, trainman419 - -0.2.8 (2015-10-02) ------------------- -* Fix test target name collision. Fixes `#49 `_ -* sound_play: remove some raw prints cluttering output -* sound_play: added queue_size to SoundClient init - Should prevent warning being displayed whenever the client is created. - Fixes issue `#43 `_ -* add simple-actionlib functionality to sound_play -* sound_play: Added functions to play files relative to a package path -* Update maintainer email -* Contributors: Matthias Nieuwenhuisen, Michal Staniaszek, aginika, trainman419 - -0.2.7 (2014-07-25) ------------------- - -0.2.6 (2014-02-26) ------------------- -* Fix path resolution in python soundplay lib. -* now importing roslib. closes `#33 `_ -* Contributors: Piyush Khandelwal, trainman419 - -0.2.5 (2014-01-23) ------------------- -* "0.2.5" -* Install sounds. Fixes `#29 `_. -* install sound_play.h and export include folder -* Contributors: ahendrix, trainman419, v4hn - -0.2.4 (2013-09-10) ------------------- -* Fix cmake ordering. -* Contributors: Austin Hendrix - -0.2.3 (2013-07-15) ------------------- -* Fix python. -* Contributors: Austin Hendrix - -0.2.2 (2013-04-10) ------------------- -* Actually add proper dependency on message generation. -* Reorder CMakeLists.txt. -* Contributors: Austin Hendrix - -0.2.1 (2013-04-08 13:59) ------------------------- - -0.2.0 (2013-04-08 13:49) ------------------------- -* Finish catkinizing audio_common. -* Start catkinizing sound_play. -* Fix typo in package.xml -* Versions and more URLs. -* Convert manifests to package.xml -* Ditch old makefiles. -* Use festival default voice from libsoundplay. -* Set myself as the maintainer. -* Fix filehandle leak and add debug statements. -* Updates manifest -* Updated manifests for rodep2 -* Fixed sound_play -* Added test wave -* Cleaned up the test script -* Added default voice to say command -* Updated the gstreamer rosdeps -* Removed comment -* Added diagnostic_msgs to sound_play -* Added a rosdep.yaml file -* Added ability to use different festival voices -* Added exit(1) when import of pygame fails. This makes the error message easier to notice. -* Added Ubuntu platform tags to manifest -* Added a link to the troubleshooting wiki page in the diagnostic message as requested by `#4070 `_. -* Took out the deprecated API. -* Sound play now publishes header timestamp in message. `#3822 `_ -* Cleaned up temp file generation when doing text to speach. Now uses the tempfile module. -* Adding missing export of headers for sound_play C++ API -* Changing node name for sound play diagnostics, `#3599 `_ -* Added test.launch to run sound server and a test client. -* Remove use of deprecated rosbuild macros -* Replaced review tag with standardized message -* Updated review status -* Added a launch file to start soundplay_node.py -* Made the sound_play client libraries be more explicit about what to do when the node is not running. -* Updated manifest description -* Updated copyright year -* fixed XML typo -* updated package description -* Added a copyright message. -* Removed debugging message from sound_play node. -* Added tests for new sound_play python API and fixed a few bugs. -* Fixed missing self arguments in sound_play libsoundplay.py -* Upgraded the python sound_play API -* Converted non-camelCase methods to camelCase in sound_play C++ API -* Changed Lock to RLock to fix `#2801 `_ -* Made the deprecation of SoundHandle into a warning. -* Added debug messages -* Updated soundplay_node to publish diagnostics and increased the number of active channels. -* Added diagnostic_msgs dependency to sound_play -* sound_play: Renamed SoundHandle to SoundClient. Added Sound-centric C++ API. Changed byte to int8 in msg file. Updated documentation. -* migration part 1 -* Contributors: Austin Hendrix, Nate Koenig, blaise, blaisegassend, eitan, gerkey, kwc, nkoenig, watts, wheeler diff --git a/sound_play/CMakeLists.txt b/sound_play/CMakeLists.txt deleted file mode 100644 index 98f3fe18a..000000000 --- a/sound_play/CMakeLists.txt +++ /dev/null @@ -1,45 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) - -project(sound_play) - -find_package(catkin REQUIRED COMPONENTS message_generation roscpp actionlib_msgs) - -add_action_files(DIRECTORY action FILES SoundRequest.action) -add_message_files(DIRECTORY msg FILES SoundRequest.msg) - -include_directories(include ${catkin_INCLUDE_DIRS}) - -catkin_python_setup() - -generate_messages(DEPENDENCIES actionlib_msgs) - -catkin_package(CATKIN_DEPENDS message_runtime actionlib_msgs - INCLUDE_DIRS include) - -catkin_install_python(PROGRAMS - scripts/is_speaking.py - 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 - sound_play_plugin.yaml - 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/README.md b/sound_play/README.md deleted file mode 100644 index 44694e736..000000000 --- a/sound_play/README.md +++ /dev/null @@ -1,67 +0,0 @@ -sound_play -========= - -## Dependencies - -- python-pygame -- festival -- festvox-don -- alsa-base -- alsa-tools - -## Checking that the speaker/sound card is recognized by the kernel - -`cat /proc/asound/cards` - -Your card should be in the list. Make note of the number in front of the -card, it will be used to tell alsa where to play sound from. - -If your sound device does not show up, your kernel may not support it, or -the module may not be loaded. For usb speakers, you may want to try: - -`modprobe snd-usb-audio` - -(not sure if this list is exhaustive) - -## Telling alsa which sound card/speaker to use - -Run (replace 75 with the number of the sound device to use): - -`asoundconf set-default-card 75` - -This will create .asoundrc.asoundconf in your home directory. -To make alsa use these settings, add the following line to `~/.asoundrc` - -`include ".asoundrc.asoundconf"` - -To set this default to all users, copy this to the system-wide alsa -configuration file: - -`mv ~/.asoundrc.asoundconf /etc/asound.conf` - -## Getting started - -Start the sound play node, and have a look at the scripts in the scripts -directory that exercise the node's functionality. - -## Specify Device via ROS Param - -Besides setting default device as system wide settings, you can also specify audio device via `rosparam`: - -``` xml - - - - - -``` - -or simply run: `rosrun sound_play soundplay_node.py _device:="hw:1,0"` - -In the launch file above, `~device` parameter is set to `hw:1,0`, which tells `soundplay_node` to use audio device No. `0` connected to audio card No.`1`. -To find card/device number which you want to use, execute: - -``` bash -sudo aplay -l -``` - diff --git a/sound_play/action/SoundRequest.action b/sound_play/action/SoundRequest.action deleted file mode 100644 index 49ef24aa7..000000000 --- a/sound_play/action/SoundRequest.action +++ /dev/null @@ -1,7 +0,0 @@ -SoundRequest sound_request ---- -bool playing -time stamp ---- -bool playing -time stamp \ No newline at end of file diff --git a/sound_play/include/sound_play/sound_play.h b/sound_play/include/sound_play/sound_play.h deleted file mode 100644 index d5fe4614e..000000000 --- a/sound_play/include/sound_play/sound_play.h +++ /dev/null @@ -1,410 +0,0 @@ -/* - *********************************************************** - * Software License Agreement (BSD License) - * - * Copyright (c) 2009, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the Willow Garage nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************** - */ - -#ifndef __SOUND_PLAY__SOUND_PLAY__H__ -#define __SOUND_PLAY__SOUND_PLAY__H__ - -#include -#include -#include -#include -#include - -namespace sound_play -{ - -/** \brief Class that publishes messages to the sound_play node. - * - * This class is a helper class for communicating with the sound_play node - * via the \ref sound_play::SoundRequest message. It has two ways of being used: - * - * - It can create Sound classes that represent a particular sound which - * can be played, repeated or stopped. - * - * - It provides methods for each way in which the sound_play::SoundRequest - * message can be invoked. - */ - -class SoundClient -{ -public: - class Sound - { - friend class SoundClient; - private: - int snd_; - float vol_; - std::string arg_; - std::string arg2_; - SoundClient *client_; - - Sound(SoundClient *sc, int snd, const std::string &arg, const std::string arg2 = std::string(), const float vol = 1.0f) - { - client_ = sc; - snd_ = snd; - arg_ = arg; - arg2_ = arg2; - vol_ = vol; - } - - public: - /** \brief Play the Sound. - * - * This method causes the Sound to be played once. - */ - void play() - { - client_->sendMsg(snd_, SoundRequest::PLAY_ONCE, arg_, arg2_, vol_); - } - - /** \brief Play the Sound repeatedly. - * - * This method causes the Sound to be played repeatedly until stop() is - * called. - */ - void repeat() - { - client_->sendMsg(snd_, SoundRequest::PLAY_START, arg_, arg2_, vol_); - } - - /** \brief Stop Sound playback. - * - * This method causes the Sound to stop playing. - */ - void stop() - { - client_->sendMsg(snd_, SoundRequest::PLAY_STOP, arg_, arg2_, vol_); - } - }; - - /** \brief Create a SoundClient that publishes on the given topic - * - * Creates a SoundClient that publishes to the given topic relative to the - * given NodeHandle. - * - * \param nh Node handle to use when creating the topic. - * - * \param topic Topic to publish to. - */ - SoundClient(ros::NodeHandle &nh, const std::string &topic) - { - init(nh, topic); - } - - /** \brief Create a SoundClient with the default topic - * - * Creates a SoundClient that publishes to "robotsound". - */ - SoundClient() - { - init(ros::NodeHandle(), "robotsound"); - } - - /** \brief Create a voice Sound. - * - * Creates a Sound corresponding to saying the indicated text. - * - * \param s Text to say - * \param volume Volume at which to play the sound. 0 is mute, 1.0 is 100%. - */ - Sound voiceSound(const std::string &s, float volume = 1.0f) - { - return Sound(this, SoundRequest::SAY, s, "", volume); - } - - /** \brief Create a wave Sound. - * - * Creates a Sound corresponding to indicated file. - * - * \param s File to play. Should be an absolute path that exists on the - * machine running the sound_play node. - * \param volume Volume at which to play the sound. 0 is mute, 1.0 is 100%. - */ - Sound waveSound(const std::string &s, float volume = 1.0f) - { - return Sound(this, SoundRequest::PLAY_FILE, s, "", volume); - } - - /** \brief Create a wave Sound from a package. - * - * Creates a Sound corresponding to indicated file. - * - * \param p Package containing the sound file. - * \param s Filename of the WAV or OGG file. Must be an path relative to the package valid - * on the computer on which the sound_play node is running - * \param volume Volume at which to play the sound. 0 is mute, 1.0 is 100%. - */ - Sound waveSoundFromPkg(const std::string &p, const std::string &s, float volume = 1.0f) - { - return Sound(this, SoundRequest::PLAY_FILE, s, p, volume); - } - - /** \brief Create a builtin Sound. - * - * Creates a Sound corresponding to indicated builtin wave. - * - * \param id Identifier of the sound to play. - * \param volume Volume at which to play the sound. 0 is mute, 1.0 is 100%. - */ - Sound builtinSound(int id, float volume = 1.0f) - { - return Sound(this, id, "", "", volume); - } - - /** \brief Say a string - * - * Send a string to be said by the sound_node. The vocalization can be - * stopped using stopSaying or stopAll. - * - * \param s String to say - * \param volume Volume at which to play the sound. 0 is mute, 1.0 is 100%. - */ - void say(const std::string &s, const std::string &voice="voice_kal_diphone", float volume = 1.0f) - { - sendMsg(SoundRequest::SAY, SoundRequest::PLAY_ONCE, s, voice, volume); - } - - /** \brief Say a string repeatedly - * - * The string is said repeatedly until stopSaying or stopAll is used. - * - * \param s String to say repeatedly - * \param volume Volume at which to play the sound. 0 is mute, 1.0 is 100%. - */ - void repeat(const std::string &s, float volume = 1.0f) - { - sendMsg(SoundRequest::SAY, SoundRequest::PLAY_START, s, "", volume); - } - - /** \brief Stop saying a string - * - * Stops saying a string that was previously started by say or repeat. The - * argument indicates which string to stop saying. - * - * \param s Same string as in the say or repeat command - */ - void stopSaying(const std::string &s) - { - sendMsg(SoundRequest::SAY, SoundRequest::PLAY_STOP, s, ""); - } - - /** \brief Plays a WAV or OGG file - * - * Plays a WAV or OGG file once. The playback can be stopped by stopWave or - * stopAll. - * - * \param s Filename of the WAV or OGG file. Must be an absolute path valid - * on the computer on which the sound_play node is running - * \param volume Volume at which to play the sound. 0 is mute, 1.0 is 100%. - */ - void playWave(const std::string &s, float volume = 1.0f) - { - sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_ONCE, s, "", volume); - } - - /** \brief Plays a WAV or OGG file repeatedly - * - * Plays a WAV or OGG file repeatedly until stopWave or stopAll is used. - * - * \param s Filename of the WAV or OGG file. Must be an absolute path valid - * on the computer on which the sound_play node is running. - * \param volume Volume at which to play the sound. 0 is mute, 1.0 is 100%. - */ - void startWave(const std::string &s, float volume = 1.0f) - { - sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_START, s, "", volume); - } - - /** \brief Stop playing a WAV or OGG file - * - * Stops playing a file that was previously started by playWave or - * startWave. - * - * \param s Same string as in the playWave or startWave command - */ - void stopWave(const std::string &s) - { - sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_STOP, s); - } - - /** \brief Plays a WAV or OGG file from a package - * - * Plays a WAV or OGG file once. The playback can be stopped by stopWaveFromPkg or - * stopAll. - * - * \param p Package name containing the sound file. - * \param s Filename of the WAV or OGG file. Must be an path relative to the package valid - * on the computer on which the sound_play node is running - * \param volume Volume at which to play the sound. 0 is mute, 1.0 is 100%. - */ - void playWaveFromPkg(const std::string &p, const std::string &s, float volume = 1.0f) - { - sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_ONCE, s, p, volume); - } - - /** \brief Plays a WAV or OGG file repeatedly - * - * Plays a WAV or OGG file repeatedly until stopWaveFromPkg or stopAll is used. - * - * \param p Package name containing the sound file. - * \param s Filename of the WAV or OGG file. Must be an path relative to the package valid - * on the computer on which the sound_play node is running - * \param volume Volume at which to play the sound. 0 is mute, 1.0 is 100%. - */ - void startWaveFromPkg(const std::string &p, const std::string &s, float volume = 1.0f) - { - sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_START, s, p, volume); - } - - /** \brief Stop playing a WAV or OGG file - * - * Stops playing a file that was previously started by playWaveFromPkg or - * startWaveFromPkg. - * - * \param p Package name containing the sound file. - * \param s Filename of the WAV or OGG file. Must be an path relative to the package valid - * on the computer on which the sound_play node is running - */ - void stopWaveFromPkg(const std::string &p, const std::string &s) - { - sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_STOP, s, p); - } - - /** \brief Play a buildin sound - * - * Starts playing one of the built-in sounds. built-ing sounds are documented - * in \ref SoundRequest.msg. Playback can be stopped by stopAll. - * - * \param sound Identifier of the sound to play. - * \param volume Volume at which to play the sound. 0 is mute, 1.0 is 100%. - */ - void play(int sound, float volume = 1.0f) - { - sendMsg(sound, SoundRequest::PLAY_ONCE, "", "", volume); - } - - /** \brief Play a buildin sound repeatedly - * - * Starts playing one of the built-in sounds repeatedly until stop or stopAll - * is used. Built-in sounds are documented in \ref SoundRequest.msg. - * - * \param sound Identifier of the sound to play. - * \param volume Volume at which to play the sound. 0 is mute, 1.0 is 100%. - */ - void start(int sound, float volume = 1.0f) - { - sendMsg(sound, SoundRequest::PLAY_START, "", "", volume); - } - - /** \brief Stop playing a built-in sound - * - * Stops playing a built-in sound started with play or start. - * - * \param sound Same sound that was used to start playback. - */ - void stop(int sound) - { - sendMsg(sound, SoundRequest::PLAY_STOP); - } - - /** \brief Stop all currently playing sounds - * - * This method stops all speech, wave file, and built-in sound playback. - */ - void stopAll() - { - stop(SoundRequest::ALL); - } - - /** \brief Turns warning messages on or off. - * - * If a message is sent when no node is subscribed to the topic, a - * warning message is printed. This method can be used to enable or - * disable warnings. - * - * \param state True to turn off messages, false to turn them on. - */ - void setQuiet(bool state) - { - quiet_ = state; - } - -private: - void init(ros::NodeHandle nh, const std::string &topic) - { - nh_ = nh; - pub_ = nh.advertise(topic, 5); - quiet_ = false; - } - - void sendMsg(int snd, int cmd, const std::string &s = "", const std::string &arg2 = "", const float &vol = 1.0f) - { - boost::mutex::scoped_lock lock(mutex_); - - if (!nh_.ok()) - return; - - SoundRequest msg; - msg.sound = snd; - msg.command = cmd; - msg.arg = s; - msg.arg2 = arg2; - - // ensure volume is in the correct range - if (vol < 0) - msg.volume = 0; - else if (vol > 1.0) - msg.volume = 1.0f; - else - msg.volume = vol; - - pub_.publish(msg); - - if (pub_.getNumSubscribers() == 0 && !quiet_) - ROS_WARN("Sound command issued, but no node is subscribed to the topic. Perhaps you forgot to run soundplay_node.py"); - } - - bool quiet_; - ros::NodeHandle nh_; - ros::Publisher pub_; - boost::mutex mutex_; -}; - -typedef SoundClient::Sound Sound; - -}; - -#endif diff --git a/sound_play/mainpage.dox b/sound_play/mainpage.dox deleted file mode 100644 index 61ca855e9..000000000 --- a/sound_play/mainpage.dox +++ /dev/null @@ -1,23 +0,0 @@ -/** - -\mainpage -\htmlinclude manifest.html - -The \b sound_play package provides a way to say strings, -play WAV or OGG files and to play builtin sounds. Documentation for the -package can be found here at http://www.ros.org/wiki/sound_play - -Multiple sounds can be played concurrently (up to 4 currently because of -limitations in pygame). - -Python and C++ client classes are provide for ease of use: - -- sound_play::SoundClient and sound_play::SoundClient::Sound for C++ -- libsoundplay::SoundClient and libsoundplay::SoundClient::Sound for Python - -Example uses are in: - -- test.cpp -- test.py - -*/ diff --git a/sound_play/msg/SoundRequest.msg b/sound_play/msg/SoundRequest.msg deleted file mode 100644 index 241628c76..000000000 --- a/sound_play/msg/SoundRequest.msg +++ /dev/null @@ -1,30 +0,0 @@ -# IMPORTANT: You should never have to generate this message yourself. -# Use the sound_play::SoundClient C++ helper or the -# sound_play.libsoundplay.SoundClient Python helper. - -# Sounds -int8 BACKINGUP = 1 -int8 NEEDS_UNPLUGGING = 2 -int8 NEEDS_PLUGGING = 3 -int8 NEEDS_UNPLUGGING_BADLY = 4 -int8 NEEDS_PLUGGING_BADLY = 5 - -# Sound identifiers that have special meaning -int8 ALL = -1 # Only legal with PLAY_STOP -int8 PLAY_FILE = -2 -int8 SAY = -3 - -int8 sound # Selects which sound to play (see above) - -# Commands -int8 PLAY_STOP = 0 # Stop this sound from playing -int8 PLAY_ONCE = 1 # Play the sound once -int8 PLAY_START = 2 # Play the sound in a loop until a stop request occurs - -int8 command # Indicates what to do with the sound - -# Volume at which to play the sound, with 0 as mute and 1.0 as 100%. -float32 volume - -string arg # file name or text to say -string arg2 # other arguments diff --git a/sound_play/package.xml b/sound_play/package.xml deleted file mode 100644 index 130bf0e1a..000000000 --- a/sound_play/package.xml +++ /dev/null @@ -1,55 +0,0 @@ - - - - sound_play - 0.3.18 - - sound_play provides a ROS node that translates commands on a ROS topic (robotsound) into sounds. The node supports built-in sounds, playing OGG/WAV files, and doing speech synthesis via festival. C++ and Python bindings allow this node to be used without understanding the details of the message format, allowing faster development and resilience to message format changes. - - Austin Hendrix - Shingo Kitagawa - Blaise Gassend - BSD - http://ros.org/wiki/sound_play - https://github.com/ros-drivers/audio_common - https://github.com/ros-drivers/audio_common/issues - - catkin - python-setuptools - python3-setuptools - - roscpp - roslib - actionlib_msgs - actionlib - audio_common_msgs - diagnostic_msgs - message_generation - - roscpp - roslib - actionlib_msgs - audio_common_msgs - diagnostic_msgs - - python-gi - python3-gi - gstreamer1.0 - gstreamer1.0-alsa - gstreamer1.0-plugins-base - gstreamer1.0-plugins-ugly - gstreamer1.0-plugins-good - - rospy - festival - flite - message_runtime - resource_retriever - - - - - - diff --git a/sound_play/scripts/is_speaking.py b/sound_play/scripts/is_speaking.py deleted file mode 100755 index 0794d28ea..000000000 --- a/sound_play/scripts/is_speaking.py +++ /dev/null @@ -1,55 +0,0 @@ -#!/usr/bin/env python - -import rospy - -from actionlib_msgs.msg import GoalStatus -from actionlib_msgs.msg import GoalStatusArray -import std_msgs.msg - - -class IsSpeaking(object): - - def __init__(self): - super(IsSpeaking, self).__init__() - - self.sub = rospy.Subscriber( - '~robotsound', - GoalStatusArray, - callback=self.callback, - queue_size=1) - - self.is_speaking = False - self.pub_speech_flag = rospy.Publisher( - '~output/is_speaking', - std_msgs.msg.Bool, queue_size=1) - - self.timer = rospy.Timer(rospy.Duration(0.01), self.speech_timer_cb) - - def check_speak_status(self, status_msg): - """Returns True when speaking. - - """ - # If it is not included in the terminal state, - # it is determined as a speaking state. - if status_msg.status in [GoalStatus.ACTIVE, - GoalStatus.PREEMPTING, - GoalStatus.RECALLING]: - return True - return False - - def callback(self, msg): - for status in msg.status_list: - if self.check_speak_status(status): - self.is_speaking = True - return - self.is_speaking = False - - def speech_timer_cb(self, timer): - self.pub_speech_flag.publish( - std_msgs.msg.Bool(self.is_speaking)) - - -if __name__ == '__main__': - rospy.init_node('is_speaking') - app = IsSpeaking() - rospy.spin() diff --git a/sound_play/scripts/play.py b/sound_play/scripts/play.py deleted file mode 100755 index 237f2bba0..000000000 --- a/sound_play/scripts/play.py +++ /dev/null @@ -1,62 +0,0 @@ -#!/usr/bin/env python - -#*********************************************************** -#* Software License Agreement (BSD License) -#* -#* Copyright (c) 2009, Willow Garage, Inc. -#* All rights reserved. -#* -#* Redistribution and use in source and binary forms, with or without -#* modification, are permitted provided that the following conditions -#* are met: -#* -#* * Redistributions of source code must retain the above copyright -#* notice, this list of conditions and the following disclaimer. -#* * Redistributions in binary form must reproduce the above -#* copyright notice, this list of conditions and the following -#* disclaimer in the documentation and/or other materials provided -#* with the distribution. -#* * Neither the name of the Willow Garage nor the names of its -#* contributors may be used to endorse or promote products derived -#* from this software without specific prior written permission. -#* -#* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -#* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -#* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -#* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -#* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -#* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -#* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -#* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -#* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -#* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -#* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -#* POSSIBILITY OF SUCH DAMAGE. -#*********************************************************** - -# Author: Blaise Gassend - - -if __name__ == '__main__': - import rospy - rospy.init_node('play', anonymous=True) - argv = rospy.myargv() - if len(argv) < 2 or len(argv) > 3 or argv[1] == '--help': - print('Usage: %s sound_to_play.(ogg|wav) [volume]' % argv[0]) - print() - print('Plays an .OGG or .WAV file. The path to the file should be absolute, and be valid on the computer on which sound_play is running.\n The (optional) second parameter sets the volume for the sound as a value between 0 and 1.0, where 0 is mute.') - exit(1) - - # Import after printing usage for speed. - from sound_play.msg import SoundRequest - from sound_play.libsoundplay import SoundClient - - soundhandle = SoundClient() - - rospy.sleep(1) - rospy.loginfo('Playing "%s".' % argv[1]) - - volume = float(argv[2]) if len(argv) == 3 else 1.0 - - soundhandle.playWave(argv[1], volume) - rospy.sleep(1) diff --git a/sound_play/scripts/playbuiltin.py b/sound_play/scripts/playbuiltin.py deleted file mode 100755 index 2258fd4e8..000000000 --- a/sound_play/scripts/playbuiltin.py +++ /dev/null @@ -1,66 +0,0 @@ -#!/usr/bin/env python - -#*********************************************************** -#* Software License Agreement (BSD License) -#* -#* Copyright (c) 2009, Willow Garage, Inc. -#* All rights reserved. -#* -#* Redistribution and use in source and binary forms, with or without -#* modification, are permitted provided that the following conditions -#* are met: -#* -#* * Redistributions of source code must retain the above copyright -#* notice, this list of conditions and the following disclaimer. -#* * Redistributions in binary form must reproduce the above -#* copyright notice, this list of conditions and the following -#* disclaimer in the documentation and/or other materials provided -#* with the distribution. -#* * Neither the name of the Willow Garage nor the names of its -#* contributors may be used to endorse or promote products derived -#* from this software without specific prior written permission. -#* -#* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -#* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -#* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -#* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -#* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -#* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -#* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -#* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -#* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -#* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -#* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -#* POSSIBILITY OF SUCH DAMAGE. -#*********************************************************** - -# Author: Blaise Gassend - -import sys - -if __name__ == '__main__': - import rospy - argv = rospy.myargv() - if len(argv) < 2 or len(argv) > 3 or argv[1] == '--help': - print('Usage: %s [volume]' % argv[0]) - print() - print('Plays one of the built-in sounds based on its integer ID. Look at the sound_play/SoundRequest message definition for IDs.\n The (optional) volume parameter sets the volume for the sound as a value between 0 and 1.0, where 0 is mute.') - exit(1) - - # Import here so that usage is fast. - from sound_play.msg import SoundRequest - from sound_play.libsoundplay import SoundClient - - rospy.init_node('play', anonymous=True) - - soundhandle = SoundClient() - rospy.sleep(1) - - num = int(argv[1]) - volume = float(argv[2]) if len(argv) == 3 else 1.0 - - rospy.loginfo('Playing sound %i.' % num) - - soundhandle.play(num, volume) - - rospy.sleep(1) diff --git a/sound_play/scripts/playpackage.py b/sound_play/scripts/playpackage.py deleted file mode 100755 index d3fc5f9e3..000000000 --- a/sound_play/scripts/playpackage.py +++ /dev/null @@ -1,63 +0,0 @@ -#!/usr/bin/env python - -#*********************************************************** -#* Software License Agreement (BSD License) -#* -#* Copyright (c) 2009, Willow Garage, Inc. -#* All rights reserved. -#* -#* Redistribution and use in source and binary forms, with or without -#* modification, are permitted provided that the following conditions -#* are met: -#* -#* * Redistributions of source code must retain the above copyright -#* notice, this list of conditions and the following disclaimer. -#* * Redistributions in binary form must reproduce the above -#* copyright notice, this list of conditions and the following -#* disclaimer in the documentation and/or other materials provided -#* with the distribution. -#* * Neither the name of the Willow Garage nor the names of its -#* contributors may be used to endorse or promote products derived -#* from this software without specific prior written permission. -#* -#* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -#* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -#* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -#* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -#* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -#* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -#* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -#* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -#* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -#* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -#* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -#* POSSIBILITY OF SUCH DAMAGE. -#*********************************************************** - -# Author: Matthias Nieuwenhuisen, Blaise Gassend - - -import sys - -if __name__ == '__main__': - import rospy - argv = rospy.myargv() - if len(argv) < 3 or len(argv) > 4 or argv[1] == '--help': - print('Usage: %s package sound_to_play.(ogg|wav) [volume]' % argv[0]) - print() - print('Plays an .OGG or .WAV file. The path to the file should be relative to the package, and be valid on the computer on which sound_play is running. \n The (optional) volume parameter sets the volume for the sound as a value between 0 and 1.0, where 0 is mute.') - exit(1) - - # Import after printing usage for speed. - from sound_play.msg import SoundRequest - from sound_play.libsoundplay import SoundClient - - rospy.init_node('play', anonymous=True) - soundhandle = SoundClient() - - volume = float(argv[3]) if len(argv) == 4 else 1.0 - - rospy.sleep(1) - rospy.loginfo('Playing "%s" from pkg "%s".' % (argv[2], argv[1])) - soundhandle.playWaveFromPkg(argv[1], argv[2], volume) - rospy.sleep(1) diff --git a/sound_play/scripts/say.py b/sound_play/scripts/say.py deleted file mode 100755 index de0efb6c9..000000000 --- a/sound_play/scripts/say.py +++ /dev/null @@ -1,84 +0,0 @@ -#!/usr/bin/env python - -#*********************************************************** -#* Software License Agreement (BSD License) -#* -#* Copyright (c) 2009, Willow Garage, Inc. -#* All rights reserved. -#* -#* Redistribution and use in source and binary forms, with or without -#* modification, are permitted provided that the following conditions -#* are met: -#* -#* * Redistributions of source code must retain the above copyright -#* notice, this list of conditions and the following disclaimer. -#* * Redistributions in binary form must reproduce the above -#* copyright notice, this list of conditions and the following -#* disclaimer in the documentation and/or other materials provided -#* with the distribution. -#* * Neither the name of the Willow Garage nor the names of its -#* contributors may be used to endorse or promote products derived -#* from this software without specific prior written permission. -#* -#* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -#* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -#* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -#* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -#* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -#* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -#* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -#* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -#* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -#* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -#* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -#* POSSIBILITY OF SUCH DAMAGE. -#*********************************************************** - -# Author: Blaise Gassend - - -import sys - -if __name__ == '__main__': - import rospy - argv = rospy.myargv() - if len(argv) > 1 and argv[1] == '--help': - print('Usage: %s \'String to say.\'' % argv[0]) - print(' %s < file_to_say.txt' % argv[0]) - print() - print('Says a string. For a string on the command line, you must use quotes as') - print('appropriate. For a string on standard input, the command will wait for') - print('EOF before saying anything.') - exit(-1) - - # Import after printing usage for speed. - from sound_play.msg import SoundRequest - from sound_play.libsoundplay import SoundClient - - if len(argv) == 1: - print('Awaiting something to say on standard input.') - - # Ordered this way to minimize wait time. - rospy.init_node('say', anonymous=True) - soundhandle = SoundClient() - rospy.sleep(1) - - voice = 'voice_kal_diphone' - volume = 1.0 - - if len(argv) == 1: - s = sys.stdin.read() - else: - s = argv[1] - - if len(argv) > 2: - voice = argv[2] - if len(argv) > 3: - volume = float(argv[3]) - - rospy.loginfo('Saying: %s' % s) - rospy.loginfo('Voice: %s' % voice) - rospy.loginfo('Volume: %s' % volume) - - soundhandle.say(s, voice, volume) - rospy.sleep(1) diff --git a/sound_play/scripts/shutup.py b/sound_play/scripts/shutup.py deleted file mode 100755 index e4f6878c3..000000000 --- a/sound_play/scripts/shutup.py +++ /dev/null @@ -1,59 +0,0 @@ -#!/usr/bin/env python - -#*********************************************************** -#* Software License Agreement (BSD License) -#* -#* Copyright (c) 2009, Willow Garage, Inc. -#* All rights reserved. -#* -#* Redistribution and use in source and binary forms, with or without -#* modification, are permitted provided that the following conditions -#* are met: -#* -#* * Redistributions of source code must retain the above copyright -#* notice, this list of conditions and the following disclaimer. -#* * Redistributions in binary form must reproduce the above -#* copyright notice, this list of conditions and the following -#* disclaimer in the documentation and/or other materials provided -#* with the distribution. -#* * Neither the name of the Willow Garage nor the names of its -#* contributors may be used to endorse or promote products derived -#* from this software without specific prior written permission. -#* -#* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -#* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -#* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -#* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -#* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -#* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -#* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -#* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -#* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -#* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -#* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -#* POSSIBILITY OF SUCH DAMAGE. -#*********************************************************** - -# Author: Blaise Gassend - -import rospy -from sound_play.msg import SoundRequest -from sound_play.libsoundplay import SoundClient - -if __name__ == '__main__': - rospy.init_node('shutup', anonymous=True) - - soundhandle = SoundClient() - rospy.sleep(0.5) # let ROS get started... - - rospy.loginfo("Sending stopAll commande every 100 ms.") - rospy.loginfo("Note: This will not prevent a node that is continuing to issue commands") - rospy.loginfo("from producing sound.") - rospy.loginfo("Press Ctrl+C to exit.") - - while not rospy.is_shutdown(): - soundhandle.stopAll() - try: - rospy.sleep(.1) - except: - pass diff --git a/sound_play/scripts/soundclient_example.py b/sound_play/scripts/soundclient_example.py deleted file mode 100755 index 0f4a7b497..000000000 --- a/sound_play/scripts/soundclient_example.py +++ /dev/null @@ -1,91 +0,0 @@ -#!/usr/bin/env python - -""" -Simple example showing how to use the SoundClient provided by libsoundplay, -in blocking, non-blocking, and explicit usage. -""" - -import rospy -from sound_play.libsoundplay import SoundClient -from sound_play.msg import SoundRequest - - -def play_explicit(): - rospy.loginfo('Example: SoundClient play methods can take in an explicit' - ' blocking parameter') - soundhandle = SoundClient() # blocking = False by default - rospy.sleep(0.5) # Ensure publisher connection is successful. - - sound_beep = soundhandle.waveSound("say-beep.wav", volume=0.5) - # Play the same sound twice, once blocking and once not. The first call is - # blocking (explicitly specified). - sound_beep.play(blocking=True) - # This call is not blocking (uses the SoundClient's setting). - sound_beep.play() - rospy.sleep(0.5) # Let sound complete. - - # Play a blocking sound. - soundhandle.play(SoundRequest.NEEDS_UNPLUGGING, blocking=True) - - # Create a new SoundClient where the default behavior *is* to block. - soundhandle = SoundClient(blocking=True) - soundhandle.say('Say-ing stuff while block-ing') - soundhandle.say('Say-ing stuff without block-ing', blocking=False) - rospy.sleep(1) - - -def play_blocking(): - """ - Play various sounds, blocking until each is completed before going to the - next. - """ - rospy.loginfo('Example: Playing sounds in *blocking* mode.') - soundhandle = SoundClient(blocking=True) - - rospy.loginfo('Playing say-beep at full volume.') - soundhandle.playWave('say-beep.wav') - - rospy.loginfo('Playing say-beep at volume 0.3.') - soundhandle.playWave('say-beep.wav', volume=0.3) - - rospy.loginfo('Playing sound for NEEDS_PLUGGING.') - soundhandle.play(SoundRequest.NEEDS_PLUGGING) - - rospy.loginfo('Speaking some long string.') - soundhandle.say('It was the best of times, it was the worst of times.') - - -def play_nonblocking(): - """ - Play the same sounds with manual pauses between them. - """ - rospy.loginfo('Example: Playing sounds in *non-blocking* mode.') - # NOTE: you must sleep at the beginning to let the SoundClient publisher - # establish a connection to the soundplay_node. - soundhandle = SoundClient(blocking=False) - rospy.sleep(1) - - # In the non-blocking version you need to sleep between calls. - rospy.loginfo('Playing say-beep at full volume.') - soundhandle.playWave('say-beep.wav') - rospy.sleep(1) - - rospy.loginfo('Playing say-beep at volume 0.3.') - soundhandle.playWave('say-beep.wav', volume=0.3) - rospy.sleep(1) - - rospy.loginfo('Playing sound for NEEDS_PLUGGING.') - soundhandle.play(SoundRequest.NEEDS_PLUGGING) - rospy.sleep(1) - - rospy.loginfo('Speaking some long string.') - soundhandle.say('It was the best of times, it was the worst of times.') - # Note we will return before the string has finished playing. - - -if __name__ == '__main__': - rospy.init_node('soundclient_example', anonymous=False) - play_explicit() - play_blocking() - play_nonblocking() - rospy.loginfo('Finished') diff --git a/sound_play/scripts/soundplay_node.py b/sound_play/scripts/soundplay_node.py deleted file mode 100755 index 4e7eaf50c..000000000 --- a/sound_play/scripts/soundplay_node.py +++ /dev/null @@ -1,462 +0,0 @@ -#!/usr/bin/env python - -# *********************************************************** -# * Software License Agreement (BSD License) -# * -# * Copyright (c) 2009, Willow Garage, Inc. -# * All rights reserved. -# * -# * Redistribution and use in source and binary forms, with or without -# * modification, are permitted provided that the following conditions -# * are met: -# * -# * * Redistributions of source code must retain the above copyright -# * notice, this list of conditions and the following disclaimer. -# * * Redistributions in binary form must reproduce the above -# * copyright notice, this list of conditions and the following -# * disclaimer in the documentation and/or other materials provided -# * with the distribution. -# * * Neither the name of the Willow Garage nor the names of its -# * contributors may be used to endorse or promote products derived -# * from this software without specific prior written permission. -# * -# * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -# * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -# * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -# * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -# * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -# * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -# * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -# * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# * POSSIBILITY OF SUCH DAMAGE. -# *********************************************************** - -import os -import sys -import threading -import traceback -import yaml - -import actionlib -import roslib -import rospkg -import rospy - -from diagnostic_msgs.msg import DiagnosticArray -from diagnostic_msgs.msg import DiagnosticStatus -from diagnostic_msgs.msg import KeyValue -from sound_play.msg import SoundRequest -from sound_play.msg import SoundRequestAction -from sound_play.msg import SoundRequestFeedback -from sound_play.msg import SoundRequestResult -from sound_play.sound_type import SoundType - -try: - import gi - gi.require_version('Gst', '1.0') - from gi.repository import GObject as GObject - from gi.repository import Gst as Gst -except Exception: - str = """ -************************************************************** -Error opening pygst. Is gstreamer installed? -************************************************************** -""" - rospy.logfatal(str) - # print str - exit(1) - - -class SoundPlayNode(object): - _feedback = SoundRequestFeedback() - _result = SoundRequestResult() - - def stopdict(self, dict): - for sound in dict.values(): - sound.stop() - - def stopall(self): - self.stopdict(self.builtinsounds) - self.stopdict(self.filesounds) - self.stopdict(self.voicesounds) - - def select_sound(self, data): - if data.sound == SoundRequest.PLAY_FILE: - if not data.arg2: - if data.arg not in self.filesounds.keys(): - rospy.logdebug( - 'command for uncached wave: "%s"' % data.arg) - try: - self.filesounds[data.arg] = SoundType( - data.arg, self.device, data.volume) - except Exception: - rospy.logerr( - 'Error setting up to play "%s".' - 'Does this file exist on the machine' - 'on which sound_play is running?' % data.arg) - return - else: - rospy.logdebug('command for cached wave: "%s"' % data.arg) - filesound = self.filesounds[data.arg] - if filesound.sound.get_property('volume') != data.volume: - rospy.logdebug( - 'volume for cached wave has changed,' - 'resetting volume') - filesound.sound.set_property('volume', data.volume) - sound = self.filesounds[data.arg] - else: - absfilename = os.path.join( - roslib.packages.get_pkg_dir(data.arg2), data.arg) - if absfilename not in self.filesounds.keys(): - rospy.logdebug( - 'command for uncached wave: "%s"' % absfilename) - try: - self.filesounds[absfilename] = SoundType( - absfilename, self.device, data.volume) - except Exception: - rospy.logerr( - 'Error setting up to play "%s" from package "%s".' - 'Does this file exist on the machine ' - 'on which sound_play is running?' - % (data.arg, data.arg2)) - return - else: - rospy.logdebug( - 'command for cached wave: "%s"' % absfilename) - filesound = self.filesounds[absfilename] - if filesound.sound.get_property('volume') != data.volume: - rospy.logdebug( - 'volume for cached wave has changed,' - 'resetting volume') - filesound.sound.set_property('volume', data.volume) - sound = self.filesounds[absfilename] - elif data.sound == SoundRequest.SAY: - voice_key = data.arg + '---' + data.arg2 - if voice_key not in self.voicesounds.keys(): - rospy.logdebug('command for uncached text: "%s"' % voice_key) - if self.plugin is None: - rospy.logerr( - 'Plugin is not found {}.'.format(self.plugin_name)) - else: - if data.arg2 == '': - voice = self.default_voice - else: - voice = data.arg2 - wavfilename = self.plugin.sound_play_say_plugin( - data.arg, voice) - if wavfilename is None: - rospy.logerr('Failed to generate wavfile.') - else: - self.voicesounds[voice_key] = SoundType( - wavfilename, self.device, data.volume) - else: - rospy.logdebug('command for cached text: "%s"' % voice_key) - voicesound = self.voicesounds[voice_key] - if voicesound.sound.get_property('volume') != data.volume: - rospy.logdebug( - 'volume for cached text has changed, resetting volume') - voicesound.sound.set_property('volume', data.volume) - sound = self.voicesounds[voice_key] - else: - rospy.logdebug('command for builtin wave: %i' % data.sound) - if ((data.sound in self.builtinsounds and - data.volume != self.builtinsounds[data.sound].volume) - or data.sound not in self.builtinsounds): - params = self.builtinsoundparams[data.sound] - volume = data.volume - # use the second param as a scaling for the input volume - if params[1] != 1: - volume = (volume + params[1])/2 - self.builtinsounds[data.sound] = SoundType( - params[0], self.device, volume) - sound = self.builtinsounds[data.sound] - if sound.staleness != 0 and data.command != SoundRequest.PLAY_STOP: - # This sound isn't counted in active_sounds - rospy.logdebug("activating %i %s" % (data.sound, data.arg)) - self.active_sounds = self.active_sounds + 1 - sound.staleness = 0 - return sound - - def callback(self, data): - if not self.initialized: - return - self.mutex.acquire() - try: - if (data.sound == SoundRequest.ALL - and data.command == SoundRequest.PLAY_STOP): - self.stopall() - else: - sound = self.select_sound(data) - sound.command(data.command) - except Exception as e: - rospy.logerr('Exception in callback: %s' % str(e)) - rospy.loginfo(traceback.format_exc()) - finally: - self.mutex.release() - rospy.logdebug("done callback") - - # Purge sounds that haven't been played in a while. - def cleanupdict(self, dict): - purgelist = [] - for key, sound in iter(dict.items()): - try: - staleness = sound.get_staleness() - except Exception as e: - rospy.logerr( - 'Exception in cleanupdict for sound (%s): %s' - % (str(key), str(e))) - # Something is wrong. Let's purge and try again. - staleness = 100 - # print "%s %i"%(key, staleness) - if staleness >= 10: - purgelist.append(key) - # Sound is playing - if staleness == 0: - self.active_sounds = self.active_sounds + 1 - for key in purgelist: - rospy.logdebug('Purging %s from cache' % key) - # clean up resources - dict[key].dispose() - del dict[key] - - def cleanup(self): - self.mutex.acquire() - try: - self.active_sounds = 0 - self.cleanupdict(self.filesounds) - self.cleanupdict(self.voicesounds) - self.cleanupdict(self.builtinsounds) - except Exception: - rospy.loginfo( - 'Exception in cleanup: %s' % sys.exc_info()[0]) - finally: - self.mutex.release() - - def diagnostics(self, state): - try: - da = DiagnosticArray() - ds = DiagnosticStatus() - ds.name = rospy.get_caller_id().lstrip('/') + ": Node State" - if state == 0: - ds.level = DiagnosticStatus.OK - ds.message = "%i sounds playing" % self.active_sounds - ds.values.append( - KeyValue("Active sounds", str(self.active_sounds))) - ds.values.append( - KeyValue( - "Allocated sound channels", - str(self.num_channels))) - ds.values.append( - KeyValue( - "Buffered builtin sounds", - str(len(self.builtinsounds)))) - ds.values.append( - KeyValue( - "Buffered wave sounds", - str(len(self.filesounds)))) - ds.values.append( - KeyValue( - "Buffered voice sounds", - str(len(self.voicesounds)))) - elif state == 1: - ds.level = DiagnosticStatus.WARN - ds.message = "Sound device not open yet." - else: - ds.level = DiagnosticStatus.ERROR - ds.message = "Can't open sound device." +\ - "See http://wiki.ros.org/sound_play/Troubleshooting" - da.status.append(ds) - da.header.stamp = rospy.get_rostime() - self.diagnostic_pub.publish(da) - except Exception as e: - rospy.loginfo('Exception in diagnostics: %s' % str(e)) - - def execute_cb(self, data): - data = data.sound_request - if not self.initialized: - rospy.logerr('soundplay_node is not initialized yet.') - self._as.set_aborted() - return - self.mutex.acquire() - # Force only one sound at a time - self.stopall() - try: - if (data.sound == SoundRequest.ALL - and data.command == SoundRequest.PLAY_STOP): - self.stopall() - else: - sound = self.select_sound(data) - sound.command(data.command) - - r = rospy.Rate(self.loop_rate) - start_time = rospy.get_rostime() - success = True - while sound.get_playing(): - sound.update() - if self._as.is_preempt_requested(): - rospy.loginfo('sound_play action: Preempted') - sound.stop() - self._as.set_preempted() - success = False - break - - self._feedback.playing = sound.get_playing() - self._feedback.stamp = rospy.get_rostime() - start_time - self._as.publish_feedback(self._feedback) - r.sleep() - - if success: - self._result.playing = self._feedback.playing - self._result.stamp = self._feedback.stamp - rospy.loginfo('sound_play action: Succeeded') - self._as.set_succeeded(self._result) - - except Exception as e: - self._as.set_aborted() - rospy.logerr( - 'Exception in actionlib callback: %s' % str(e)) - rospy.loginfo(traceback.format_exc()) - finally: - self.mutex.release() - rospy.logdebug("done actionlib callback") - - def __init__(self): - Gst.init(None) - - # Start gobject thread to receive gstreamer messages - GObject.threads_init() - self.g_loop = threading.Thread(target=GObject.MainLoop().run) - self.g_loop.daemon = True - self.g_loop.start() - - rospy.init_node('sound_play') - self.loop_rate = rospy.get_param('~loop_rate', 100) - self.device = rospy.get_param("~device", "default") - self.default_voice = rospy.get_param('~default_voice', None) - self.plugin_name = rospy.get_param( - '~plugin', 'sound_play/festival_plugin') - self.diagnostic_pub = rospy.Publisher( - "/diagnostics", DiagnosticArray, queue_size=1) - rootdir = os.path.join( - roslib.packages.get_pkg_dir('sound_play'), 'sounds') - - # load plugin - rospack = rospkg.RosPack() - depend_pkgs = rospack.get_depends_on('sound_play', implicit=False) - depend_pkgs = ['sound_play'] + depend_pkgs - rospy.loginfo("Loading from plugin definitions") - plugin_yamls = [] - for depend_pkg in depend_pkgs: - manifest = rospack.get_manifest(depend_pkg) - plugin_yaml = manifest.get_export('sound_play', 'plugin') - if len(plugin_yaml) != 0: - plugin_yamls += plugin_yaml - for plugin_y in plugin_yaml: - rospy.logdebug('Loading plugin in {}'.format(plugin_y)) - plugin_dict = {} - for plugin_yaml in plugin_yamls: - if not os.path.exists(plugin_yaml): - rospy.logerr( - 'Failed to load plugin yaml: {}'.format(plugin_yaml)) - rospy.logerr( - 'Missing plugin yaml: {}'.format(plugin_yaml)) - continue - with open(plugin_yaml) as f: - plugin_descs = yaml.safe_load(f) - for plugin_desc in plugin_descs: - plugin_dict[plugin_desc['name']] = plugin_desc['module'] - - self.plugin = None - if self.plugin_name in plugin_dict.keys(): - plugin_module = plugin_dict[self.plugin_name] - mod = __import__(plugin_module.split('.')[0]) - for sub_mod in plugin_module.split('.')[1:]: - mod = getattr(mod, sub_mod) - self.plugin = mod() - - self.builtinsoundparams = { - SoundRequest.BACKINGUP: ( - os.path.join(rootdir, 'BACKINGUP.ogg'), 0.1), - SoundRequest.NEEDS_UNPLUGGING: ( - os.path.join(rootdir, 'NEEDS_UNPLUGGING.ogg'), 1), - SoundRequest.NEEDS_PLUGGING: ( - os.path.join(rootdir, 'NEEDS_PLUGGING.ogg'), 1), - SoundRequest.NEEDS_UNPLUGGING_BADLY: ( - os.path.join(rootdir, 'NEEDS_UNPLUGGING_BADLY.ogg'), 1), - SoundRequest.NEEDS_PLUGGING_BADLY: ( - os.path.join(rootdir, 'NEEDS_PLUGGING_BADLY.ogg'), 1), - } - - self.no_error = True - self.initialized = False - self.active_sounds = 0 - - self.mutex = threading.Lock() - self.sub = rospy.Subscriber("robotsound", SoundRequest, self.callback) - self._as = actionlib.SimpleActionServer( - 'sound_play', SoundRequestAction, - execute_cb=self.execute_cb, auto_start=False) - - self.mutex.acquire() - # For ros startup race condition - self.sleep(0.5) - self.diagnostics(1) - - while not rospy.is_shutdown(): - while not rospy.is_shutdown(): - self.init_vars() - self.no_error = True - self.initialized = True - self.mutex.release() - if not self._as.action_server.started: - self._as.start() - try: - self.idle_loop() - # Returns after inactive period to test device availability - # print "Exiting idle" - except Exception: - rospy.loginfo( - 'Exception in idle_loop: %s' % sys.exc_info()[0]) - finally: - self.mutex.acquire() - - self.diagnostics(2) - self.mutex.release() - - def init_vars(self): - self.num_channels = 10 - self.builtinsounds = {} - self.filesounds = {} - self.voicesounds = {} - self.hotlist = [] - if not self.initialized: - rospy.loginfo('sound_play node is ready to play sound') - - def sleep(self, duration): - try: - rospy.sleep(duration) - except rospy.exceptions.ROSInterruptException: - pass - - def get_sound_length(self): - sound_length = len(self.builtinsounds) +\ - len(self.voicesounds) + len(self.filesounds) - return sound_length - - def idle_loop(self): - self.last_activity_time = rospy.get_time() - while (not rospy.is_shutdown() - and (rospy.get_time() - self.last_activity_time < 10 - or self.get_sound_length() > 0)): - # print("idle_loop") - self.diagnostics(0) - self.sleep(1) - self.cleanup() - # print("idle_exiting") - - -if __name__ == '__main__': - SoundPlayNode() diff --git a/sound_play/scripts/test.py b/sound_play/scripts/test.py deleted file mode 100755 index 2bf9d0fbe..000000000 --- a/sound_play/scripts/test.py +++ /dev/null @@ -1,128 +0,0 @@ -#!/usr/bin/env python - -#*********************************************************** -#* Software License Agreement (BSD License) -#* -#* Copyright (c) 2009, Willow Garage, Inc. -#* All rights reserved. -#* -#* Redistribution and use in source and binary forms, with or without -#* modification, are permitted provided that the following conditions -#* are met: -#* -#* * Redistributions of source code must retain the above copyright -#* notice, this list of conditions and the following disclaimer. -#* * Redistributions in binary form must reproduce the above -#* copyright notice, this list of conditions and the following -#* disclaimer in the documentation and/or other materials provided -#* with the distribution. -#* * Neither the name of the Willow Garage nor the names of its -#* contributors may be used to endorse or promote products derived -#* from this software without specific prior written permission. -#* -#* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -#* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -#* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -#* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -#* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -#* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -#* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -#* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -#* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -#* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -#* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -#* POSSIBILITY OF SUCH DAMAGE. -#*********************************************************** - -# Author: Blaise Gassend - -import rospy, os, sys -from sound_play.msg import SoundRequest - -from sound_play.libsoundplay import SoundClient - -def sleep(t): - try: - rospy.sleep(t) - except: - pass - -if __name__ == '__main__': - rospy.init_node('soundplay_test', anonymous = True) - soundhandle = SoundClient() - - rospy.sleep(1) - - soundhandle.stopAll() - - rospy.loginfo("This script will run continuously until you hit CTRL+C, testing various sound_node sound types.") - - #print 'Try to play wave files that do not exist.' - #soundhandle.playWave('17') - #soundhandle.playWave('dummy') - - # print 'say' - # soundhandle.say('Hello world!') - # sleep(3) - - rospy.loginfo('wave') - soundhandle.playWave('say-beep.wav') - sleep(2) - - rospy.loginfo('quiet wave') - soundhandle.playWave('say-beep.wav', 0.3) - sleep(2) - - rospy.loginfo('plugging') - soundhandle.play(SoundRequest.NEEDS_PLUGGING) - sleep(2) - - rospy.loginfo('quiet plugging') - soundhandle.play(SoundRequest.NEEDS_PLUGGING, 0.3) - sleep(2) - - rospy.loginfo('unplugging') - soundhandle.play(SoundRequest.NEEDS_UNPLUGGING) - sleep(2) - - rospy.loginfo('plugging badly') - soundhandle.play(SoundRequest.NEEDS_PLUGGING_BADLY) - sleep(2) - - rospy.loginfo('unplugging badly') - soundhandle.play(SoundRequest.NEEDS_UNPLUGGING_BADLY) - sleep(2) - - s1 = soundhandle.builtinSound(SoundRequest.NEEDS_UNPLUGGING_BADLY) - s2 = soundhandle.waveSound("say-beep.wav") - s3 = soundhandle.voiceSound("Testing the new A P I") - s4 = soundhandle.builtinSound(SoundRequest.NEEDS_UNPLUGGING_BADLY, 0.3) - s5 = soundhandle.waveSound("say-beep.wav", 0.3) - s6 = soundhandle.voiceSound("Testing the new A P I", 0.3) - - rospy.loginfo("New API start voice") - s3.repeat() - sleep(3) - - rospy.loginfo("New API start voice quiet") - s6.play() - sleep(3) - - rospy.loginfo("New API wave") - s2.repeat() - sleep(2) - - rospy.loginfo("New API wave quiet") - s5.play() - sleep(2) - - rospy.loginfo("New API builtin") - s1.play() - sleep(2) - - rospy.loginfo("New API builtin quiet") - s4.play() - sleep(2) - - rospy.loginfo("New API stop") - s3.stop() diff --git a/sound_play/scripts/test/test_sound_client.py b/sound_play/scripts/test/test_sound_client.py deleted file mode 100644 index 89c567802..000000000 --- a/sound_play/scripts/test/test_sound_client.py +++ /dev/null @@ -1,17 +0,0 @@ -#!/usr/bin/env python - -import unittest - -import rospy -import rostest -from sound_play.libsoundplay import SoundClient - -class TestCase(unittest.TestCase): - def test_soundclient_constructor(self): - s = SoundClient() - self.assertIsNotNone(s) - -if __name__ == '__main__': - rostest.rosrun('sound_play', 'test_sound_client', TestCase) - -__author__ = 'Felix Duvallet' diff --git a/sound_play/scripts/test_actionlib_client.py b/sound_play/scripts/test_actionlib_client.py deleted file mode 100755 index 01840b621..000000000 --- a/sound_play/scripts/test_actionlib_client.py +++ /dev/null @@ -1,60 +0,0 @@ -#! /usr/bin/env python - -import roslib; roslib.load_manifest('sound_play') -import rospy -import actionlib -from sound_play.msg import SoundRequest, SoundRequestAction, SoundRequestGoal - -import os - -def sound_play_client(volume=1.0): - client = actionlib.SimpleActionClient('sound_play', SoundRequestAction) - - client.wait_for_server() - - rospy.loginfo("Need Unplugging") - goal = SoundRequestGoal() - goal.sound_request.sound = SoundRequest.NEEDS_UNPLUGGING - goal.sound_request.command = SoundRequest.PLAY_ONCE - goal.sound_request.volume = volume - - client.send_goal(goal) - client.wait_for_result() - # print client.get_result() - rospy.loginfo("End Need Unplugging") - - rospy.loginfo("Need Plugging") - goal = SoundRequestGoal() - goal.sound_request.sound = SoundRequest.NEEDS_PLUGGING - goal.sound_request.command = SoundRequest.PLAY_ONCE - goal.sound_request.volume = volume - client.send_goal(goal) - client.wait_for_result() - # print client.get_result() - rospy.loginfo("End Need Plugging") - - rospy.loginfo("Say") - goal = SoundRequestGoal() - goal.sound_request.sound = SoundRequest.SAY - goal.sound_request.command = SoundRequest.PLAY_ONCE - goal.sound_request.arg = "Testing the actionlib interface A P I" - goal.sound_request.volume = volume - client.send_goal(goal) - client.wait_for_result() - # print client.get_result() - rospy.loginfo("End Say") - - rospy.loginfo("Wav") - goal = SoundRequestGoal() - goal.sound_request.sound = SoundRequest.PLAY_FILE - goal.sound_request.command = SoundRequest.PLAY_ONCE - goal.sound_request.arg = os.path.join(roslib.packages.get_pkg_dir('sound_play'),'sounds') + "/say-beep.wav" - goal.sound_request.volume = volume - client.send_goal(goal) - client.wait_for_result() - # print client.get_result() - rospy.loginfo("End wav") - -if __name__ == '__main__': - rospy.init_node('soundplay_client_test') - sound_play_client() diff --git a/sound_play/setup.py b/sound_play/setup.py deleted file mode 100644 index df3c32f97..000000000 --- a/sound_play/setup.py +++ /dev/null @@ -1,9 +0,0 @@ -from catkin_pkg.python_setup import generate_distutils_setup -from setuptools import setup - -d = generate_distutils_setup( - packages=['sound_play'], - package_dir={'': 'src'} - ) - -setup(**d) diff --git a/sound_play/sound_play_plugin.yaml b/sound_play/sound_play_plugin.yaml deleted file mode 100644 index a5b262ee4..000000000 --- a/sound_play/sound_play_plugin.yaml +++ /dev/null @@ -1,4 +0,0 @@ -- name: sound_play/festival_plugin - module: sound_play.festival_plugin.FestivalPlugin -- name: sound_play/flite_plugin - module: sound_play.flite_plugin.FlitePlugin diff --git a/sound_play/soundplay_node.launch b/sound_play/soundplay_node.launch deleted file mode 100644 index f5110d35e..000000000 --- a/sound_play/soundplay_node.launch +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/sound_play/sounds/BACKINGUP.ogg b/sound_play/sounds/BACKINGUP.ogg deleted file mode 100644 index 4bc6db541..000000000 Binary files a/sound_play/sounds/BACKINGUP.ogg and /dev/null differ diff --git a/sound_play/sounds/NEEDS_PLUGGING.ogg b/sound_play/sounds/NEEDS_PLUGGING.ogg deleted file mode 100644 index 0a15885c3..000000000 Binary files a/sound_play/sounds/NEEDS_PLUGGING.ogg and /dev/null differ diff --git a/sound_play/sounds/NEEDS_PLUGGING_BADLY.ogg b/sound_play/sounds/NEEDS_PLUGGING_BADLY.ogg deleted file mode 100644 index d336822e8..000000000 Binary files a/sound_play/sounds/NEEDS_PLUGGING_BADLY.ogg and /dev/null differ diff --git a/sound_play/sounds/NEEDS_UNPLUGGING.ogg b/sound_play/sounds/NEEDS_UNPLUGGING.ogg deleted file mode 100644 index 1596c734f..000000000 Binary files a/sound_play/sounds/NEEDS_UNPLUGGING.ogg and /dev/null differ diff --git a/sound_play/sounds/NEEDS_UNPLUGGING_BADLY.ogg b/sound_play/sounds/NEEDS_UNPLUGGING_BADLY.ogg deleted file mode 100644 index 028196f3a..000000000 Binary files a/sound_play/sounds/NEEDS_UNPLUGGING_BADLY.ogg and /dev/null differ diff --git a/sound_play/sounds/say-beep.wav b/sound_play/sounds/say-beep.wav deleted file mode 100644 index 161c43c31..000000000 Binary files a/sound_play/sounds/say-beep.wav and /dev/null differ diff --git a/sound_play/src/sound_play/__init__.py b/sound_play/src/sound_play/__init__.py deleted file mode 100644 index e572f45b4..000000000 --- a/sound_play/src/sound_play/__init__.py +++ /dev/null @@ -1,36 +0,0 @@ -# Software License Agreement (BSD License) -# -# Copyright (c) 2013, Willow Garage, Inc. -# All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions -# are met: -# -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# * Redistributions in binary form must reproduce the above -# copyright notice, this list of conditions and the following -# disclaimer in the documentation and/or other materials provided -# with the distribution. -# * Neither the name of Willow Garage, Inc. nor the names of its -# contributors may be used to endorse or promote products derived -# from this software without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. - -from sound_play.festival_plugin import FestivalPlugin -from sound_play.flite_plugin import FlitePlugin -import sound_play.libsoundplay as libsoundplay -from sound_play.sound_play_plugin import SoundPlayPlugin diff --git a/sound_play/src/sound_play/festival_plugin.py b/sound_play/src/sound_play/festival_plugin.py deleted file mode 100644 index fb57e97b3..000000000 --- a/sound_play/src/sound_play/festival_plugin.py +++ /dev/null @@ -1,61 +0,0 @@ -import os -import tempfile - -import rospy - -from sound_play.sound_play_plugin import SoundPlayPlugin - - -class FestivalPlugin(SoundPlayPlugin): - - _default_voice = 'voice_kal_diphone' - - def __init__(self): - super(FestivalPlugin, self).__init__() - - def sound_play_say_plugin(self, text, voice): - if voice is None or voice == '': - voice = self._default_voice - encoding = 'ISO-8859-15' - if ':' in voice: - voice, encoding = voice.split(':', maxsplit=1) - txtfile = tempfile.NamedTemporaryFile( - prefix='sound_play', suffix='.txt') - (wavfile, wavfilename) = tempfile.mkstemp( - prefix='sound_play', suffix='.wav') - txtfilename = txtfile.name - os.close(wavfile) - try: - try: - if hasattr(text, 'decode'): - txtfile.write( - text.decode('UTF-8').encode(encoding)) - else: - txtfile.write( - text.encode(encoding)) - except UnicodeEncodeError: - if hasattr(text, 'decode'): - txtfile.write(text) - else: - txtfile.write(text.encode('UTF-8')) - txtfile.flush() - cmd = "text2wave -eval '({0})' {1} -o {2}".format( - voice, txtfilename, wavfilename) - os.system(cmd) - try: - if os.stat(wavfilename).st_size == 0: - # So we hit the same catch block - raise OSError - except OSError: - rospy.logerr( - 'Sound synthesis failed.' - 'Is festival installed?' - 'Is a festival voice installed?' - 'Try running "rosdep satisfy sound_play|sh".' - 'Refer to http://wiki.ros.org/' - 'sound_play/Troubleshooting' - ) - return None - finally: - txtfile.close() - return wavfilename diff --git a/sound_play/src/sound_play/flite_plugin.py b/sound_play/src/sound_play/flite_plugin.py deleted file mode 100644 index 00334a01c..000000000 --- a/sound_play/src/sound_play/flite_plugin.py +++ /dev/null @@ -1,57 +0,0 @@ -import os -import tempfile - -import resource_retriever -import rospkg -import rospy - -from sound_play.sound_play_plugin import SoundPlayPlugin - - -class FlitePlugin(SoundPlayPlugin): - - _default_voice = 'kal' - - def __init__(self): - super(FlitePlugin, self).__init__() - self._default_voice_path = None - - def get_default_voice_path(self): - if self._default_voice_path is None: - self._default_voice_path = os.path.join( - rospkg.RosPack().get_path('sound_play'), - 'resources/flitevox') - return self._default_voice_path - - def sound_play_say_plugin(self, text, voice): - if voice is None or voice == '': - voice = self._default_voice - if voice.endswith('.flitevox'): - if voice.startswith('package://'): - voice = resource_retriever.get(voice) - elif voice.startswith('/'): - voice = voice - else: - voice = os.path.join( - self.get_default_voice_path(), voice) - (wavfile, wavfilename) = tempfile.mkstemp( - prefix='sound_play', suffix='.wav') - os.close(wavfile) - cmd = "flite -voice {0} -t \"{1}\" -o {2}".format( - voice, text, wavfilename) - os.system(cmd) - try: - if os.stat(wavfilename).st_size == 0: - # So we hit the same catch block - raise OSError - except OSError: - rospy.logerr( - 'Sound synthesis failed.' - 'Is flite installed?' - 'Is a flite voice installed?' - 'Try running "rosdep satisfy sound_play|sh".' - 'Refer to http://wiki.ros.org/' - 'sound_play/Troubleshooting' - ) - return None - return wavfilename diff --git a/sound_play/src/sound_play/libsoundplay.py b/sound_play/src/sound_play/libsoundplay.py deleted file mode 100644 index fa693a145..000000000 --- a/sound_play/src/sound_play/libsoundplay.py +++ /dev/null @@ -1,374 +0,0 @@ -#*********************************************************** -#* Software License Agreement (BSD License) -#* -#* Copyright (c) 2009, Willow Garage, Inc. -#* All rights reserved. -#* -#* Redistribution and use in source and binary forms, with or without -#* modification, are permitted provided that the following conditions -#* are met: -#* -#* * Redistributions of source code must retain the above copyright -#* notice, this list of conditions and the following disclaimer. -#* * Redistributions in binary form must reproduce the above -#* copyright notice, this list of conditions and the following -#* disclaimer in the documentation and/or other materials provided -#* with the distribution. -#* * Neither the name of the Willow Garage nor the names of its -#* contributors may be used to endorse or promote products derived -#* from this software without specific prior written permission. -#* -#* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -#* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -#* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -#* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -#* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -#* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -#* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -#* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -#* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -#* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -#* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -#* POSSIBILITY OF SUCH DAMAGE. -#*********************************************************** - -# Author: Blaise Gassend - -import rospy -import roslib -import actionlib -import os, sys -from actionlib_msgs.msg import GoalStatusArray -from sound_play.msg import SoundRequest -from sound_play.msg import SoundRequestGoal -from sound_play.msg import SoundRequestAction - -## \brief Class that publishes messages to the sound_play node. -## -## This class is a helper class for communicating with the sound_play node -## via the \ref sound_play.SoundRequest message. It has two ways of being used: -## -## - It can create Sound classes that represent a particular sound which -## can be played, repeated or stopped. -## -## - It provides methods for each way in which the sound_play.SoundRequest -## message can be invoked. - -class Sound(object): - def __init__(self, client, snd, arg, volume=1.0): - self.client = client - self.snd = snd - self.arg = arg - self.vol = volume - -## \brief Play the Sound. -## -## This method causes the Sound to be played once. - - def play(self, **kwargs): - self.client.sendMsg(self.snd, SoundRequest.PLAY_ONCE, self.arg, - vol=self.vol, **kwargs) - -## \brief Play the Sound repeatedly. -## -## This method causes the Sound to be played repeatedly until stop() is -## called. - - def repeat(self, **kwargs): - self.client.sendMsg(self.snd, SoundRequest.PLAY_START, self.arg, - vol=self.vol, **kwargs) - -## \brief Stop Sound playback. -## -## This method causes the Sound to stop playing. - - def stop(self): - self.client.sendMsg(self.snd, SoundRequest.PLAY_STOP, self.arg) - -## This class is a helper class for communicating with the sound_play node -## via the \ref sound_play.SoundRequest message. There is a one-to-one mapping -## between methods and invocations of the \ref sound_play.SoundRequest message. - -class SoundClient(object): - - def __init__(self, blocking=False, sound_action='sound_play', sound_topic='robotsound'): - """ - - The SoundClient can send SoundRequests in two modes: non-blocking mode - (by publishing a message to the soundplay_node directly) which will - return as soon as the sound request has been sent, or blocking mode (by - using the actionlib interface) which will wait until the sound has - finished playing completely. - - The blocking parameter here is the standard behavior, but can be - over-ridden. Each say/play/start/repeat method can take in an optional - `blocking=True|False` argument that will over-ride the class-wide - behavior. See soundclient_example.py for an example of this behavior. - - :param blocking: Used as the default behavior unless over-ridden, - (default = false) - - :param sound_action: Namespace of actionlib to play sound. The actionlib interface is used - only if blocking parameter is True. (default='sound_play') - - :param sound_topic: Topic name to play sound. The topic interface is used only if blocking - parameter is False. (default='robotsound') - """ - - self._blocking = blocking - self._playing = False - - # NOTE: only one of these will be used at once, but we need to create - # both the publisher and actionlib client here. - self.actionclient = actionlib.SimpleActionClient( - sound_action, SoundRequestAction) - self.pub = rospy.Publisher(sound_topic, SoundRequest, queue_size=5) - self.sub = rospy.Subscriber( - '{}/status'.format(sound_action), GoalStatusArray, self._action_status_cb) - -## \brief Create a voice Sound. -## -## Creates a Sound corresponding to saying the indicated text. -## -## \param s Text to say - - def voiceSound(self, s, volume=1.0): - return Sound(self, SoundRequest.SAY, s, volume=volume) - -## \brief Create a wave Sound. -## -## Creates a Sound corresponding to indicated file. -## -## \param s File to play. Should be an absolute path that exists on the -## machine running the sound_play node. - def waveSound(self, sound, volume=1.0): - if sound[0] != "/": - rootdir = os.path.join(roslib.packages.get_pkg_dir('sound_play'),'sounds') - sound = rootdir + "/" + sound - return Sound(self, SoundRequest.PLAY_FILE, sound, volume=volume) - -## \brief Create a builtin Sound. -## -## Creates a Sound corresponding to indicated builtin wave. -## -## \param id Identifier of the sound to play. - - def builtinSound(self, id, volume=1.0): - return Sound(self, id, "", volume) - -## \brief Say a string -## -## Send a string to be said by the sound_node. The vocalization can be -## stopped using stopSaying or stopAll. -## -## \param text String to say - - def say(self,text, voice='', volume=1.0, **kwargs): - self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_ONCE, text, voice, - volume, **kwargs) - -## \brief Say a string repeatedly -## -## The string is said repeatedly until stopSaying or stopAll is used. -## -## \param text String to say repeatedly - - def repeat(self,text, volume=1.0, **kwargs): - self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_START, text, - vol=volume, **kwargs) - -## \brief Stop saying a string -## -## Stops saying a string that was previously started by say or repeat. The -## argument indicates which string to stop saying. -## -## \param text Same string as in the say or repeat command - - def stopSaying(self,text): - self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_STOP, text) - -## \brief Plays a WAV or OGG file -## -## Plays a WAV or OGG file once. The playback can be stopped by stopWave or -## stopAll. -## -## \param sound Filename of the WAV or OGG file. Must be an absolute path valid -## on the computer on which the sound_play node is running - - def playWave(self, sound, volume=1.0, **kwargs): - if sound[0] != "/": - rootdir = os.path.join(roslib.packages.get_pkg_dir('sound_play'),'sounds') - sound = rootdir + "/" + sound - self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_ONCE, sound, - vol=volume, **kwargs) - -## \brief Plays a WAV or OGG file repeatedly -## -## Plays a WAV or OGG file repeatedly until stopWave or stopAll is used. -## -## \param sound Filename of the WAV or OGG file. Must be an absolute path valid -## on the computer on which the sound_play node is running. - - def startWave(self, sound, volume=1.0, **kwargs): - if sound[0] != "/": - rootdir = os.path.join(roslib.packages.get_pkg_dir('sound_play'),'sounds') - sound = rootdir + "/" + sound - self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_START, sound, - vol=volume, **kwargs) - -## \brief Stop playing a WAV or OGG file -## -## Stops playing a file that was previously started by playWave or -## startWave. -## -## \param sound Same string as in the playWave or startWave command - - def stopWave(self,sound): - if sound[0] != "/": - rootdir = os.path.join(roslib.package.get_pkg_dir('sound_play'),'sounds') - sound = rootdir + "/" + sound - self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_STOP, sound) - -## \brief Plays a WAV or OGG file -## -## Plays a WAV or OGG file once. The playback can be stopped by stopWaveFromPkg or -## stopAll. -## -## \param package Package name containing the sound file. -## \param sound Filename of the WAV or OGG file. Must be an path relative to the package valid -## on the computer on which the sound_play node is running - - def playWaveFromPkg(self, package, sound, volume=1.0, **kwargs): - self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_ONCE, sound, package, - volume, **kwargs) - -## \brief Plays a WAV or OGG file repeatedly -## -## Plays a WAV or OGG file repeatedly until stopWaveFromPkg or stopAll is used. -## -## \param package Package name containing the sound file. -## \param sound Filename of the WAV or OGG file. Must be an path relative to the package valid -## on the computer on which the sound_play node is running - - def startWaveFromPkg(self, package, sound, volume=1.0, **kwargs): - self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_START, sound, - package, volume, **kwargs) - -## \brief Stop playing a WAV or OGG file -## -## Stops playing a file that was previously started by playWaveFromPkg or -## startWaveFromPkg. -## -## \param package Package name containing the sound file. -## \param sound Filename of the WAV or OGG file. Must be an path relative to the package valid -## on the computer on which the sound_play node is running - - def stopWaveFromPkg(self,sound, package): - self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_STOP, sound, package) - -## \brief Play a buildin sound -## -## Starts playing one of the built-in sounds. built-ing sounds are documented -## in \ref SoundRequest.msg. Playback can be stopped by stopall. -## -## \param sound Identifier of the sound to play. - - def play(self,sound, volume=1.0, **kwargs): - self.sendMsg(sound, SoundRequest.PLAY_ONCE, "", vol=volume, **kwargs) - -## \brief Play a buildin sound repeatedly -## -## Starts playing one of the built-in sounds repeatedly until stop or -## stopall is used. Built-in sounds are documented in \ref SoundRequest.msg. -## -## \param sound Identifier of the sound to play. - - def start(self,sound, volume=1.0, **kwargs): - self.sendMsg(sound, SoundRequest.PLAY_START, "", vol=volume, **kwargs) - -## \brief Stop playing a built-in sound -## -## Stops playing a built-in sound started with play or start. -## -## \param sound Same sound that was used to start playback - - def stop(self,sound): - self.sendMsg(sound, SoundRequest.PLAY_STOP, "") - -## \brief Stop all currently playing sounds -## -## This method stops all speech, wave file, and built-in sound playback. - - def stopAll(self): - self.stop(SoundRequest.ALL) - - def sendMsg( - self, snd, cmd, s, arg2="", vol=1.0, replace=True, - server_timeout=None, result_timeout=None, - **kwargs - ): - """ - Internal method that publishes the sound request, either directly as a - SoundRequest to the soundplay_node or through the actionlib interface - (which blocks until the sound has finished playing). - - The blocking behavior is nominally the class-wide setting unless it has - been explicitly specified in the play call. - """ - - # Use the passed-in argument if it exists, otherwise fall back to the - # class-wide setting. - blocking = kwargs.get('blocking', self._blocking) - - msg = SoundRequest() - msg.sound = snd - # Threshold volume between 0 and 1. - msg.volume = max(0, min(1, vol)) - msg.command = cmd - msg.arg = s - msg.arg2 = arg2 - - rospy.logdebug('Sending sound request with volume = {}' - ' and blocking = {}'.format(msg.volume, blocking)) - - # Defensive check for the existence of the correct communicator. - if not blocking and not self.pub: - rospy.logerr('Publisher for SoundRequest must exist') - return - if blocking and not self.actionclient: - rospy.logerr('Action client for SoundRequest does not exist.') - return - - if not blocking: # Publish message directly and return immediately - self.pub.publish(msg) - if self.pub.get_num_connections() < 1: - rospy.logwarn("Sound command issued, but no node is subscribed" - " to the topic. Perhaps you forgot to run" - " soundplay_node.py?") - else: # Block until result comes back. - assert self.actionclient, 'Actionclient must exist' - rospy.logdebug('Sending action client sound request [blocking]') - - if server_timeout is None or server_timeout > rospy.Duration(0): - if server_timeout is None: - server_timeout = rospy.Duration() - if not self.actionclient.wait_for_server(timeout=server_timeout): - return - - goal = SoundRequestGoal() - goal.sound_request = msg - while not replace and self._playing: - rospy.sleep(0.1) - self.actionclient.send_goal(goal) - if result_timeout is None or result_timeout > rospy.Duration(0): - if result_timeout is None: - result_timeout = rospy.Duration() - if self.actionclient.wait_for_result(timeout=result_timeout): - rospy.logdebug('sound request response received') - return - - def _action_status_cb(self, msg): - if 1 in [s.status for s in msg.status_list]: - self._playing = True - else: - self._playing = False diff --git a/sound_play/src/sound_play/sound_play_plugin.py b/sound_play/src/sound_play/sound_play_plugin.py deleted file mode 100644 index f8ef500c2..000000000 --- a/sound_play/src/sound_play/sound_play_plugin.py +++ /dev/null @@ -1,30 +0,0 @@ -class SoundPlayPlugin(object): - - """Base class for sound_play plugin - - This is a base class for sound_play plugin. - sound_play plugin has one method; sound_play_say_plugin. - sound_play_start_plugin run when command is SAY. - - sound_play plugin is defined in yaml format as below; - - name: sound_play/festival_plugin # plugin name - module: sound_play.festival_plugin.FestivalPlugin - # plugin module name - - Also, sound_play plugin yaml file is exported in package.xml as below; - - - - """ - - def __init__(self): - pass - - def sound_play_say_plugin(self, text, voice): - """Start plugin for sound_play - - Args: - text (string): speech text - voice (string): speech voice - """ - return None diff --git a/sound_play/src/sound_play/sound_type.py b/sound_play/src/sound_play/sound_type.py deleted file mode 100644 index e5f089bf4..000000000 --- a/sound_play/src/sound_play/sound_type.py +++ /dev/null @@ -1,154 +0,0 @@ -import os -import threading - -import rospy - -from sound_play.msg import SoundRequest - -try: - import gi - gi.require_version('Gst', '1.0') - from gi.repository import Gst as Gst -except Exception: - str = """ -************************************************************** -Error opening pygst. Is gstreamer installed? -************************************************************** -""" - rospy.logfatal(str) - # print str - exit(1) - - -class SoundType(object): - STOPPED = 0 - LOOPING = 1 - COUNTING = 2 - - def __init__(self, file, device, volume=1.0): - self.lock = threading.RLock() - self.state = self.STOPPED - self.sound = Gst.ElementFactory.make("playbin", None) - if self.sound is None: - raise Exception("Could not create sound player") - - if device: - self.sink = Gst.ElementFactory.make("alsasink", "sink") - self.sink.set_property("device", device) - self.sound.set_property("audio-sink", self.sink) - - if (":" in file): - uri = file - elif os.path.isfile(file): - uri = "file://" + os.path.abspath(file) - else: - rospy.logerr('Error: URI is invalid: %s' % file) - - self.uri = uri - self.volume = volume - self.sound.set_property('uri', uri) - self.sound.set_property("volume", volume) - self.staleness = 1 - self.file = file - - self.bus = self.sound.get_bus() - self.bus.add_signal_watch() - self.bus_conn_id = self.bus.connect("message", self.on_stream_end) - - def on_stream_end(self, bus, message): - if message.type == Gst.MessageType.EOS: - if (self.state == self.LOOPING): - self.sound.seek_simple(Gst.Format.TIME, Gst.SeekFlags.FLUSH, 0) - else: - self.stop() - - def __del__(self): - # stop our GST object so that it gets garbage-collected - self.dispose() - - def update(self): - if self.bus is not None: - self.bus.poll(Gst.MessageType.ERROR, 10) - - def loop(self): - self.lock.acquire() - try: - self.staleness = 0 - if self.state == self.COUNTING: - self.stop() - - if self.state == self.STOPPED: - self.sound.seek_simple(Gst.Format.TIME, Gst.SeekFlags.FLUSH, 0) - self.sound.set_state(Gst.State.PLAYING) - self.state = self.LOOPING - finally: - self.lock.release() - - def dispose(self): - self.lock.acquire() - try: - if self.bus is not None: - self.sound.set_state(Gst.State.NULL) - self.bus.disconnect(self.bus_conn_id) - self.bus.remove_signal_watch() - self.bus = None - self.sound = None - self.sink = None - self.state = self.STOPPED - except Exception as e: - rospy.logerr('Exception in dispose: %s' % str(e)) - finally: - self.lock.release() - - def stop(self): - if self.state != self.STOPPED: - self.lock.acquire() - try: - self.sound.set_state(Gst.State.NULL) - self.state = self.STOPPED - finally: - self.lock.release() - - def single(self): - self.lock.acquire() - try: - rospy.logdebug("Playing %s" % self.uri) - self.staleness = 0 - if self.state == self.LOOPING: - self.stop() - - self.sound.seek_simple(Gst.Format.TIME, Gst.SeekFlags.FLUSH, 0) - self.sound.set_state(Gst.State.PLAYING) - self.state = self.COUNTING - finally: - self.lock.release() - - def command(self, cmd): - if cmd == SoundRequest.PLAY_STOP: - self.stop() - elif cmd == SoundRequest.PLAY_ONCE: - self.single() - elif cmd == SoundRequest.PLAY_START: - self.loop() - - def get_staleness(self): - self.lock.acquire() - position = 0 - duration = 0 - try: - position = self.sound.query_position(Gst.Format.TIME)[1] - duration = self.sound.query_duration(Gst.Format.TIME)[1] - except Exception: - position = 0 - duration = 0 - finally: - self.lock.release() - - if position != duration: - self.staleness = 0 - else: - self.staleness = self.staleness + 1 - return self.staleness - - def get_playing(self): - return self.state == self.COUNTING diff --git a/sound_play/test.launch b/sound_play/test.launch deleted file mode 100644 index 743d8272a..000000000 --- a/sound_play/test.launch +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - diff --git a/sound_play/test/CMakeLists.txt b/sound_play/test/CMakeLists.txt deleted file mode 100644 index 8a6f8e810..000000000 --- a/sound_play/test/CMakeLists.txt +++ /dev/null @@ -1,4 +0,0 @@ -add_executable(test_sound_play test.cpp) -target_link_libraries(test_sound_play ${catkin_LIBRARIES}) -add_dependencies(test_sound_play sound_play_gencpp) -set_target_properties(test_sound_play PROPERTIES OUTPUT_NAME test) diff --git a/sound_play/test/test.cpp b/sound_play/test/test.cpp deleted file mode 100644 index a272d7faa..000000000 --- a/sound_play/test/test.cpp +++ /dev/null @@ -1,147 +0,0 @@ -/********************************************************************* -* Software License Agreement (BSD License) -* -* Copyright (c) 2009, Willow Garage, Inc. -* All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* * Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* * Redistributions in binary form must reproduce the above -* copyright notice, this list of conditions and the following -* disclaimer in the documentation and/or other materials provided -* with the distribution. -* * Neither the name of the Willow Garage nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -*********************************************************************/ - -#include -#include - -void sleepok(int t, ros::NodeHandle &nh) -{ - if (nh.ok()) - sleep(t); -} - -int main(int argc, char **argv) -{ - ros::init(argc, argv, "sound_play_test"); - - ros::NodeHandle nh; - sound_play::SoundClient sc; - sound_play::SoundClient quiet_sc; - - sleepok(1, nh); - - while(nh.ok()) - { - sc.say("Hello world!"); - sleepok(2, nh); - quiet_sc.say("Hello world!"); - sleepok(2, nh); - - const char *str1 = "I am annoying."; - sc.repeat(str1); - sleepok(4, nh); - sc.stopSaying(str1); - quiet_sc.repeat(str1); - sleepok(4, nh); - quiet_sc.stopSaying(str1); - - sc.playWave("/usr/share/xemacs21/xemacs-packages/etc/sounds/boing.wav"); - sleepok(2, nh); - quiet_sc.playWave("/usr/share/xemacs21/xemacs-packages/etc/sounds/boing.wav"); - sleepok(2, nh); - - const char *str2 = "/usr/share/xemacs21/xemacs-packages/etc/sounds/piano-beep.wav"; - sc.startWave(str2); - sleepok(4, nh); - sc.stopWave(str2); - quiet_sc.startWave(str2); - sleepok(4, nh); - quiet_sc.stopWave(str2); - - sc.play(sound_play::SoundRequest::NEEDS_UNPLUGGING); - sleepok(2, nh); - quiet_sc.play(sound_play::SoundRequest::NEEDS_UNPLUGGING); - sleepok(2, nh); - - sc.play(sound_play::SoundRequest::NEEDS_UNPLUGGING); - sleepok(2, nh); - quiet_sc.play(sound_play::SoundRequest::NEEDS_UNPLUGGING); - sleepok(2, nh); - - sc.start(sound_play::SoundRequest::BACKINGUP); - sleepok(4, nh); - sc.stop(sound_play::SoundRequest::BACKINGUP); - quiet_sc.start(sound_play::SoundRequest::BACKINGUP); - sleepok(4, nh); - quiet_sc.stop(sound_play::SoundRequest::BACKINGUP); - - sleepok(2, nh); - sound_play::Sound s1 = sc.waveSound("/usr/share/xemacs21/xemacs-packages/etc/sounds/boing.wav"); - s1.repeat(); - sleepok(1, nh); - s1.stop(); - - sleepok(2, nh); - sound_play::Sound s2 = quiet_sc.waveSound("/usr/share/xemacs21/xemacs-packages/etc/sounds/boing.wav"); - s2.repeat(); - sleepok(1, nh); - s2.stop(); - - sleepok(2, nh); - sound_play::Sound s3 = sc.voiceSound("This is a really long sentence that will get cut off."); - s3.play(); - sleepok(1, nh); - s3.stop(); - - sleepok(2, nh); - sound_play::Sound s4 = quiet_sc.voiceSound("This is a really long sentence that will get cut off."); - s4.play(); - sleepok(1, nh); - s4.stop(); - - sleepok(2, nh); - sound_play::Sound s5 = sc.builtinSound(sound_play::SoundRequest::NEEDS_UNPLUGGING_BADLY); - s5.play(); - sleepok(1, nh); - s5.stop(); - - sleepok(2, nh); - sound_play::Sound s6 = quiet_sc.builtinSound(sound_play::SoundRequest::NEEDS_UNPLUGGING_BADLY); - s6.play(); - sleepok(1, nh); - s6.stop(); - - sleepok(2, nh); - sound_play::Sound s7 = sc.waveSoundFromPkg("sound_play", "sounds/BACKINGUP.ogg"); - s7.play(); - sleepok(1, nh); - s7.stop(); - - sleepok(2, nh); - sound_play::Sound s8 = quiet_sc.waveSoundFromPkg("sound_play", "sounds/BACKINGUP.ogg"); - s8.play(); - sleepok(1, nh); - s8.stop(); - } -} diff --git a/audio_play/src/audio_play.cpp b/src/audio_play.cpp similarity index 100% rename from audio_play/src/audio_play.cpp rename to src/audio_play.cpp