Browse Source

Node dying gracefully and interating with Utku's

pull/65/head
Hongyu Li 2 years ago
parent
commit
442232d608
1 changed files with 23 additions and 23 deletions
  1. +23
    -23
      vz_acoustic_scene_analysis/scripts/stretch_audio.py

+ 23
- 23
vz_acoustic_scene_analysis/scripts/stretch_audio.py View File

@ -9,13 +9,19 @@ import usb.core
import struct import struct
import time import time
import os import os
import sys
import rospy import rospy
from contextlib import contextmanager from contextlib import contextmanager
import stretch_body.hello_utils as hu import stretch_body.hello_utils as hu
hu.print_stretch_re_use() hu.print_stretch_re_use()
from vz_acoustic_scene_analysis.msg import MyAudioData from vz_acoustic_scene_analysis.msg import MyAudioData
from rospy.numpy_msg import numpy_msg from rospy.numpy_msg import numpy_msg
# Utku's script
# import segmentation as seg
import sys
sys.path.append('/home/hello-robot/vz_modules/NEU_VZ_ASA/MehrshadTesting/codes/A_CoughDetection/src')
import feature_class
import DSP
# what does this mean # what does this mean
@contextmanager @contextmanager
@ -94,10 +100,6 @@ class Tuning:
if not self.dev: if not self.dev:
raise RuntimeError("Failed to find Respeaker device") raise RuntimeError("Failed to find Respeaker device")
rospy.loginfo("Initializing Respeaker device") rospy.loginfo("Initializing Respeaker device")
# Initialize inputs and outputs to other module code
self.audio_signal = None
self.prediction = None
# self.param = rospy.get_param('')
def write(self, name, value): def write(self, name, value):
@ -129,7 +131,6 @@ class Tuning:
id = data[0] id = data[0]
# not sure what is happening here
cmd = 0x80 | data[1] cmd = 0x80 | data[1]
if data[2] == 'int': if data[2] == 'int':
cmd |= 0x40 cmd |= 0x40
@ -194,7 +195,7 @@ RESPEAKER_WIDTH = rospy.get_param("/RESPEAKER_WIDTH", 2)
RESPEAKER_INDEX = get_respeaker_device_id() RESPEAKER_INDEX = get_respeaker_device_id()
CHUNK = rospy.get_param("/CHUNK", 1024) CHUNK = rospy.get_param("/CHUNK", 1024)
class Audio:
class ROSInterface:
def __init__(self): def __init__(self):
# Initialiaze list to store audio segments # Initialiaze list to store audio segments
self.wav_list = [] self.wav_list = []
@ -205,16 +206,15 @@ class Audio:
self.respeaker = Tuning() self.respeaker = Tuning()
# Publisher for Audio Data # Publisher for Audio Data
self.audio_data_pub = rospy.Publisher("/wav_data", numpy_msg(MyAudioData), queue_size=10) self.audio_data_pub = rospy.Publisher("/wav_data", numpy_msg(MyAudioData), queue_size=10)
# Connect to Utku's code
def get_audio(self): def get_audio(self):
recorded_frames = self.record_audio(self.chunk_size) # set param here chunk size recorded_frames = self.record_audio(self.chunk_size) # set param here chunk size
# audio = MyAudioData()
# audio.data = np.array(recorded_frames, dtype=np.uint16)
# self.audio_data_pub.publish(audio)
self.wav_list.append(recorded_frames) self.wav_list.append(recorded_frames)
self.record_count += 1 self.record_count += 1
# Every 5 seconds for # Every 5 seconds for
if ((self.record_count % (self.secs/self.chunk_size)) == 0): # set param sequence size
# if ((self.record_count % (self.secs/self.chunk_size)) == 0): # set param sequence size
if (self.record_count % 3 == 0):
return_list = self.wav_list return_list = self.wav_list
# Remove 0.2 seconds of audio data # Remove 0.2 seconds of audio data
self.wav_list.pop(0) self.wav_list.pop(0)
@ -243,7 +243,6 @@ class Audio:
self.audio_data_pub.publish(a) self.audio_data_pub.publish(a)
frames.append(a.tobytes()) frames.append(a.tobytes())
# print("Length of frames: ", len(frames))
# Check to prevent empty frames list # Check to prevent empty frames list
if (len(frames) == 0): if (len(frames) == 0):
# add garbage data # add garbage data
@ -262,23 +261,24 @@ class Audio:
dev = usb.core.find(idVendor=0x2886, idProduct=0x0018) dev = usb.core.find(idVendor=0x2886, idProduct=0x0018)
try: try:
if dev: if dev:
while True:
while not rospy.is_shutdown():
if self.respeaker.is_voice() == 1: if self.respeaker.is_voice() == 1:
# wav_data = list of lists of bytes # wav_data = list of lists of bytes
wav_data = self.get_audio() wav_data = self.get_audio()
# if (str(type(wav_data)) == "<class 'list'>"):
# # Maybe publish wav_data as ROS message?
# pass
# publish_wav(wav_data) # lol
# Call of Utku's function
# asa_out = process_wav(wav_data, asa_params)
# Convert asa_out to ROS message
# if wav_data is a list
if(isinstance(wav_data, list)):
# flatten list
flat_list = [item for sublist in wav_data for item in sublist]
print(type(flat_list[0]))
# Call of Utku's function
# asa_out = process_wav(wav_data, asa_params)
# Convert asa_out to ROS message
audio_count += 1 audio_count += 1
print("Audio count: ", audio_count) print("Audio count: ", audio_count)
except usb.core.USBError: except usb.core.USBError:
print('Respeaker not on USB bus') print('Respeaker not on USB bus')
def shutdown(self):
def cleanup(self):
self.respeaker.close() self.respeaker.close()
print("shutting down") print("shutting down")
@ -286,9 +286,9 @@ class Audio:
if __name__ == "__main__": if __name__ == "__main__":
try: try:
rospy.init_node("audio_capture") rospy.init_node("audio_capture")
audio = Audio()
audio = ROSInterface()
audio.process_audio_loop() audio.process_audio_loop()
except rospy.ROSInterruptException: except rospy.ROSInterruptException:
print('Audio processing node failed!') print('Audio processing node failed!')
rospy.on_shutdown(audio.shutdown)
rospy.on_shutdown(audio.cleanup)
pass pass

Loading…
Cancel
Save