From 286441573040e499d616bdbc075be47e91e20469 Mon Sep 17 00:00:00 2001 From: Hongyu Li Date: Wed, 23 Mar 2022 18:04:05 -0400 Subject: [PATCH] I FIXED THE SHUTTING DOWN ISSUE!!!! --- vz_acoustic_scene_analysis/msg/MyAudioData.msg | 2 +- vz_acoustic_scene_analysis/scripts/stretch_audio.py | 13 +++++++++---- 2 files changed, 10 insertions(+), 5 deletions(-) diff --git a/vz_acoustic_scene_analysis/msg/MyAudioData.msg b/vz_acoustic_scene_analysis/msg/MyAudioData.msg index 38c1e43..d66c32c 100644 --- a/vz_acoustic_scene_analysis/msg/MyAudioData.msg +++ b/vz_acoustic_scene_analysis/msg/MyAudioData.msg @@ -1 +1 @@ -uint16[] data \ No newline at end of file +int16[] data \ No newline at end of file diff --git a/vz_acoustic_scene_analysis/scripts/stretch_audio.py b/vz_acoustic_scene_analysis/scripts/stretch_audio.py index ac78448..274367d 100755 --- a/vz_acoustic_scene_analysis/scripts/stretch_audio.py +++ b/vz_acoustic_scene_analysis/scripts/stretch_audio.py @@ -202,6 +202,7 @@ class Audio: self.file_name = "/home/hello-robot/Desktop/output_audio.wav" self.secs = rospy.get_param("/seconds") self.chunk_size = rospy.get_param("/chunk_size") + self.respeaker = Tuning() # Publisher for Audio Data self.audio_data_pub = rospy.Publisher("/wav_data", numpy_msg(MyAudioData), queue_size=10) @@ -236,7 +237,7 @@ class Audio: frames = [] for i in range(0, int(RESPEAKER_RATE / CHUNK * seconds)): data = stream.read(CHUNK) - a = np.frombuffer(data,dtype=np.uint16)[0::6] # extracts fused channel 0 + a = np.frombuffer(data,dtype=np.int16)[0::6] # extracts fused channel 0 print("a type: ", type(a[0])) print("a length: ", len(a)) self.audio_data_pub.publish(a) @@ -257,14 +258,12 @@ class Audio: def process_audio_loop(self): - rospy.init_node("audio_capture") audio_count = 0 dev = usb.core.find(idVendor=0x2886, idProduct=0x0018) try: if dev: - respeaker = Tuning() while True: - if respeaker.is_voice() == 1: + if self.respeaker.is_voice() == 1: # wav_data = list of lists of bytes wav_data = self.get_audio() # if (str(type(wav_data)) == ""): @@ -279,11 +278,17 @@ class Audio: except usb.core.USBError: print('Respeaker not on USB bus') + def shutdown(self): + self.respeaker.close() + print("shutting down") + if __name__ == "__main__": try: + rospy.init_node("audio_capture") audio = Audio() audio.process_audio_loop() except rospy.ROSInterruptException: print('Audio processing node failed!') + rospy.on_shutdown(audio.shutdown) pass \ No newline at end of file