audio_player.py
Go to the documentation of this file.
1 #!/usr/bin/env python3
2 
3 import rospy
4 import queue
5 from audio_common_msgs.msg import AudioData
6 
7 from pydub import AudioSegment
8 import io
9 import pygame
10 import numpy as np
11 
12 from threading import Thread
13 
14 
15 class AudioPlay:
16  def __init__(self):
17 
18  rospy.init_node("audio_subscriber", anonymous=True)
19 
20  self.rate = rospy.Rate(30)
21  self.audio_data = queue.Queue(maxsize=100000)
22 
23  # Sottoscrizione al topic 'audio' con la callback audio_callback
24  audio_sub = rospy.Subscriber("/nicla/audio", AudioData, self.audio_callback)
25 
26  rospy.loginfo("Nodo audio_subscriber pronto per ricevere audio...")
27 
28  # Initialize pygame mixer
29  pygame.mixer.init()
30 
31  self.thread_regularizer = True
32 
33  self.player_thread = Thread(target=self.audio_play)
34  self.player_thread.start()
35 
36  def audio_callback(self, audio):
37  # print(audio.data)
38  data = np.frombuffer(audio.data, dtype=np.uint8)
39 
40  non_zero_mask = data != 0
41 
42  filtered_data = data[non_zero_mask]
43 
44  if filtered_data.size > 0:
45  self.audio_data.put_nowait(filtered_data.tobytes())
46 
47  def audio_play(self):
48 
49  while self.thread_regularizer:
50 
51  try:
52  pcm_data = self.audio_data.get_nowait()
53 
54  # Create an AudioSegment instance from the raw PCM data
55  # audio_segment = AudioSegment(
56  # data=pcm_data,
57  # sample_width=1, # 8-bit samples
58  # frame_rate=16000, # 16 kHz sample rate
59  # channels=1 # mono
60  # )
61 
62  # Export the audio segment to an in-memory MP3 file
63  # mp3_io = io.BytesIO()
64  # audio_segment.export(mp3_io, format="mp3")
65  # mp3_io.seek(0)
66 
67  # # Initialize pygame mixer
68  # pygame.mixer.init()
69 
70  # Load the MP3 data into a pygame Sound object
71  # mp3_data = mp3_io.read()
72  sound = pygame.mixer.Sound(
73  buffer=pcm_data
74  ) # file=io.BytesIO(mp3_data) ) #buffer=mp3_data)
75 
76  # Play the sound
77  sound.play()
78 
79  # Keep the program running until the sound is finished
80  # while pygame.mixer.get_busy():
81  # pygame.time.Clock().tick(10)
82 
83  except Exception as e:
84  rospy.logerr(f"Error playing audio: {e}")
85  pass
86 
87  def run(self):
88 
89  while not rospy.is_shutdown():
90  # self.audio_play()
91  self.rate.sleep()
92 
93  self.player_thread.join()
94  self.thread_regularizer = False
95 
96 
97 if __name__ == "__main__":
98  try:
99  player = AudioPlay()
100  player.run()
101  except rospy.ROSInterruptException:
102  pass
audio_player.AudioPlay.rate
rate
Definition: audio_player.py:20
audio_player.AudioPlay.audio_play
def audio_play(self)
Definition: audio_player.py:47
audio_player.AudioPlay.audio_data
audio_data
Definition: audio_player.py:21
audio_player.AudioPlay.run
def run(self)
Definition: audio_player.py:87
audio_player.AudioPlay.player_thread
player_thread
Definition: audio_player.py:33
audio_player.AudioPlay.thread_regularizer
thread_regularizer
Definition: audio_player.py:31
audio_player.AudioPlay
Definition: audio_player.py:15
audio_player.AudioPlay.audio_callback
def audio_callback(self, audio)
Definition: audio_player.py:36
audio_player.AudioPlay.__init__
def __init__(self)
Definition: audio_player.py:16


nicla_vision_ros
Author(s): Davide Torielli , Damiano Gasperini , Edoardo Del Bianco , Federico Rollo
autogenerated on Sat Nov 16 2024 03:38:18