diff --git a/.gitmodules b/.gitmodules index fdec6a11..e9026c5b 100644 --- a/.gitmodules +++ b/.gitmodules @@ -55,3 +55,4 @@ [submodule "external_equipment/PlayStation-JoyInterface-ROS2"] path = external_equipment/PlayStation-JoyInterface-ROS2 url = https://github.com/HarvestX/PlayStation-JoyInterface-ROS2 + branch = humble diff --git a/utilities/smarc_utilities/setup.py b/utilities/smarc_utilities/setup.py index b2d786f9..a2d659fb 100644 --- a/utilities/smarc_utilities/setup.py +++ b/utilities/smarc_utilities/setup.py @@ -20,6 +20,7 @@ tests_require=['pytest'], entry_points={ 'console_scripts': [ + 'simple_tts = smarc_utilities.tts:main', ], }, ) diff --git a/utilities/smarc_utilities/smarc_utilities/tts.py b/utilities/smarc_utilities/smarc_utilities/tts.py new file mode 100644 index 00000000..319ff327 --- /dev/null +++ b/utilities/smarc_utilities/smarc_utilities/tts.py @@ -0,0 +1,51 @@ +import subprocess +from rclpy.node import Node +from std_msgs.msg import String + + +class TTS: + def __init__(self, + node: Node, + topic: str = "speak", + engine : str = "spd-say"): + + self._node = node + self._topic = topic + self._engine = engine + + self._speak_sub = self._node.create_subscription( + String, + self._topic, + self.speak, + 10 + ) + + def speak(self, text: String): + t = text.data + if not t: + self._node.get_logger().warn("Received empty text for TTS.") + return + self._node.get_logger().info(f"Speaking: {t}") + subprocess.run([self._engine, t]) + + + +def main(): + import rclpy + from rclpy.executors import SingleThreadedExecutor + + rclpy.init() + node = Node("tts_node") + tts = TTS(node) + + executor = SingleThreadedExecutor() + executor.add_node(node) + + try: + executor.spin() + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + rclpy.shutdown() +