Skip to content

Commit

Permalink
fix: move to speaker pkg to platform repo
Browse files Browse the repository at this point in the history
Doing this to quickly test if it merges and works... preventing issues from building up
  • Loading branch information
cooperj committed Feb 24, 2025
1 parent dc2d19d commit 83b7278
Show file tree
Hide file tree
Showing 14 changed files with 398 additions and 1 deletion.
18 changes: 18 additions & 0 deletions src/limo_speaker/launch/limo_speaker.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
return LaunchDescription([
Node(
package='limo_speaker',
executable='play_audio',
name='play_audio',
output='screen'
),
Node(
package='limo_speaker',
executable='play_tts',
name='play_tts',
output='screen'
),
])
Empty file.
53 changes: 53 additions & 0 deletions src/limo_speaker/limo_speaker/consoleHorn.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
import rclpy
from rclpy.node import Node
from std_msgs.msg import String

class LimoSpeakerConsoleHorn(Node):
def __init__(self):
super().__init__('limo_speaker_console_horn_publisher')
self.publisher_ = self.create_publisher(String, '/speaker/play', 10)
self.timer = self.create_timer(1.0, self.timer_callback)

def timer_callback(self):
user_input = input("> ").strip().replace('"', "'").replace("!,", "")

if user_input.__len__() <= 1:
# catch empty lines
if user_input == "":
user_input = "car"
elif user_input == "1":
user_input = "car"
elif user_input == "2":
user_input = "truck"
elif user_input == "3":
user_input = "clown"
elif user_input == "4":
user_input = "train"
# default catch!
else:
user_input = "car"

msg = String()
msg.data = user_input
self.publisher_.publish(msg)
# Print the command to teach users how to do it manually
print(f"ros2 topic pub -1 /speaker/play std_msgs/msg/String \"data: '{user_input}'\"\n")

def main(args=None):
rclpy.init(args=args)
horn_pub = LimoSpeakerConsoleHorn()
rclpy.spin(horn_pub)

# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
horn_pub.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
print("\033[1mLimo Horn Publisher\n\033[0mWhich horn would you like to honk?")
print("*"*16)
print(" 1) Car Horn\n 2) Truck Horn \n 3) Clown Horn \n 4) Train Horn")
print("*"*16, "\n")
main()
33 changes: 33 additions & 0 deletions src/limo_speaker/limo_speaker/consoleTTS.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
import rclpy
from rclpy.node import Node
from std_msgs.msg import String

class LimoSpeakerConsoleTTS(Node):
def __init__(self):
super().__init__('limo_speaker_console_tts_publisher')
self.publisher_ = self.create_publisher(String, '/speaker/tts', 10)
self.timer = self.create_timer(1.0, self.timer_callback)

def timer_callback(self):
user_input = input("> ").strip().replace('"', "'").replace("!,", "")
msg = String()
msg.data = user_input
self.publisher_.publish(msg)
# Print the command to teach users how to do it manually
print(f"ros2 topic pub -1 /speaker/tts std_msgs/msg/String \"data: '{user_input}'\"\n")

def main(args=None):
rclpy.init(args=args)
tts_pub = LimoSpeakerConsoleTTS()
rclpy.spin(tts_pub)

# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
tts_pub.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
print("What do you want me to say?\n\n")
main()
74 changes: 74 additions & 0 deletions src/limo_speaker/limo_speaker/playAudio.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
import rclpy
from rclpy.node import Node
import sounddevice as sd
import numpy as np
import wave
from std_msgs.msg import String

class LimoSpeakerPlayAudio(Node):
def __init__(self):
super().__init__('limo_speaker_play_audio')
self.subscription = self.create_subscription(
String,
'/speaker/play',
self.listener_callback,
10)

def listener_callback(self, msg):
self.get_logger().info('Trying to play sound: "%s"' % msg.data)
self.play_wav(msg.data)

# Plays a WAV file on the specified sound device.
def play_wav(self, sound, device_name="USB PnP Audio Device"):
device_index = self.get_speaker_by_name(device_name)
if device_index is None:
self.get_logger().warning(f"No sound device found with name containing '{device_name}'")
return

## This puts it in the limo_platform/configs/sounds folder in the repo!
file_path = f"/home/ros/robot_home/limo_platform/configs/sounds/{sound}.wav"

try:
with wave.open(file_path, 'rb') as wf:
samplerate = wf.getframerate()
frames = wf.readframes(wf.getnframes())

# Convert bytes to NumPy array
data = np.frombuffer(frames, dtype=np.int16)

# Reshape if stereo
channels = wf.getnchannels()
if channels > 1:
data = data.reshape(-1, channels)

self.get_logger().info(f"Playing {sound} sound on device {device_index} - {device_name}")

sd.play(data, samplerate=samplerate, device=device_index)
sd.wait()
except:
self.get_logger().warning(f"Couldn't play file {file_path}, does the file exist?")

# Finds the first audio device containing the given name.
def get_speaker_by_name(self, name_contains):
devices = sd.query_devices()
for idx, device in enumerate(devices):
if name_contains.lower() in device['name'].lower():
return idx # Return the device index
return None # Return None if not found

def main(args=None):
rclpy.init(args=args)

playAudio = LimoSpeakerPlayAudio()

rclpy.spin(playAudio)

# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
playAudio.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
main()
83 changes: 83 additions & 0 deletions src/limo_speaker/limo_speaker/playTTS.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
import rclpy
from rclpy.node import Node
import sounddevice as sd
import numpy as np
import wave
import os
from std_msgs.msg import String
from time import sleep
from scipy.io import wavfile
from scipy.signal import resample
import tempfile

class LimoSpeakerPlayTTS(Node):
def __init__(self):
super().__init__('limo_speaker_play_tts')
self.subscription = self.create_subscription(
String,
'/speaker/tts',
self.listener_callback,
10)

def listener_callback(self, msg):
self.get_logger().info('I am saying: "%s"' % msg.data)
self.play_speech(msg.data)

# Sends text to speech and then to the specified sound device.
def play_speech(self, text, device_name="USB PnP Audio Device"):
device_index = self.get_speaker_by_name(device_name)
if device_index is None:
self.get_logger().warning(f"No sound device found with name containing '{device_name}'")
return

file_path = f"/tmp/tts.wav" ### doing this temporarily, will change to using tempfile later

try:
with wave.open(file_path, 'rb') as wf:
os.system(f'espeak "{text}" -w {file_path}')

samplerate = wf.getframerate()
frames = wf.readframes(wf.getnframes())

# Convert bytes to NumPy array
data = np.frombuffer(frames, dtype=np.int16)

self.get_logger().info(f"Playing tts sound file on device {device_index} - {device_name}")

# Get the supported sample rates for the device
device_info = sd.query_devices(device_index, 'output')
supported_samplerates = device_info['default_samplerate']

# Resample if the file samplerate is not supported
if samplerate != supported_samplerates:
self.get_logger().info(f"Resampling from {samplerate} to {supported_samplerates}")
data = resample(data, int(len(data) * supported_samplerates / samplerate))
data = np.asarray(data, dtype=np.int16) # Ensure data is int16
samplerate = supported_samplerates

sd.play(data, samplerate=samplerate, device=device_index)
sd.wait()
except Exception as e:
self.get_logger().warning(f"Couldn't play file {file_path}, does the file exist? Error: {e}")

# Finds the first audio device containing the given name.
def get_speaker_by_name(self, name_contains):
devices = sd.query_devices()
for idx, device in enumerate(devices):
if name_contains.lower() in device['name'].lower():
return idx # Return the device index
return None # Return None if not found

def main(args=None):
rclpy.init(args=args)
playTTS = LimoSpeakerPlayTTS()
rclpy.spin(playTTS)

# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
playTTS.destroy_node()
rclpy.shutdown()

if __name__ == '__main__':
main()
25 changes: 25 additions & 0 deletions src/limo_speaker/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>limo_speaker</name>
<version>0.0.0</version>
<description>AgileX LIMO Speaker Wrapper</description>
<maintainer email="[email protected]">Josh Cooper</maintainer>
<license>Apache License 2.0</license>

<!-- System dependencies -->
<depend>python3-pip</depend>
<exec_depend>portaudio19-dev</exec_depend>
<exec_depend>alsa-utils</exec_depend>
<exec_depend>espeak</exec_depend>
<exec_depend>libespeak-dev</exec_depend>

<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<test_depend>python3-pytest</test_depend>

<export>
<build_type>ament_python</build_type>
</export>
</package>
Empty file.
4 changes: 4 additions & 0 deletions src/limo_speaker/setup.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
[develop]
script_dir=$base/lib/limo_speaker
[install]
install_scripts=$base/lib/limo_speaker
34 changes: 34 additions & 0 deletions src/limo_speaker/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
from setuptools import setup
import os
from glob import glob

package_name = 'limo_speaker'

setup(
name=package_name,
version='0.0.2',
packages=[package_name],
data_files=[
(os.path.join('share', package_name), ['package.xml']),
(os.path.join('share', package_name, 'launch'), glob('launch/*.py')),
(os.path.join('share', package_name), ['resource/' + package_name]),
],
install_requires=[
'setuptools',
'sounddevice',
],
zip_safe=True,
maintainer='Josh Cooper',
maintainer_email='[email protected]',
description='Package description',
license='Apache License 2.0',
tests_require=['pytest'],
entry_points={
'console_scripts': [
'play_audio = limo_speaker.playAudio:main',
'play_tts = limo_speaker.playTTS:main',
'console_tts = limo_speaker.consoleTTS:main',
'console_horn = limo_speaker.consoleHorn:main',
],
},
)
25 changes: 25 additions & 0 deletions src/limo_speaker/test/test_copyright.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# Copyright 2015 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from ament_copyright.main import main
import pytest


# Remove the `skip` decorator once the source file(s) have a copyright header
@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
@pytest.mark.copyright
@pytest.mark.linter
def test_copyright():
rc = main(argv=['.', 'test'])
assert rc == 0, 'Found errors'
25 changes: 25 additions & 0 deletions src/limo_speaker/test/test_flake8.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# Copyright 2017 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from ament_flake8.main import main_with_errors
import pytest


@pytest.mark.flake8
@pytest.mark.linter
def test_flake8():
rc, errors = main_with_errors(argv=[])
assert rc == 0, \
'Found %d code style errors / warnings:\n' % len(errors) + \
'\n'.join(errors)
Loading

0 comments on commit 83b7278

Please sign in to comment.