From 635001bf12cb63f23ebb98e12ac9e326cb0f4e24 Mon Sep 17 00:00:00 2001
From: Hongyu Li
Date: Tue, 29 Mar 2022 14:11:18 -0400
Subject: [PATCH] Added namespace and units for params
---
.../config/audio_params.yaml | 2 +-
.../launch/wav_audio.launch | 2 +-
.../scripts/stretch_audio.py | 16 ++++++++--------
3 files changed, 10 insertions(+), 10 deletions(-)
diff --git a/vz_acoustic_scene_analysis/config/audio_params.yaml b/vz_acoustic_scene_analysis/config/audio_params.yaml
index 4f25a13..1a280d3 100644
--- a/vz_acoustic_scene_analysis/config/audio_params.yaml
+++ b/vz_acoustic_scene_analysis/config/audio_params.yaml
@@ -1,4 +1,4 @@
-TIMEOUT: 100000
+TIMEOUT_SECONDS: 100000
VENDOR_ID: 0x2886
PRODUCT_ID: 0x0018
RESPEAKER_RATE: 16000
diff --git a/vz_acoustic_scene_analysis/launch/wav_audio.launch b/vz_acoustic_scene_analysis/launch/wav_audio.launch
index 62d5536..ce95e91 100644
--- a/vz_acoustic_scene_analysis/launch/wav_audio.launch
+++ b/vz_acoustic_scene_analysis/launch/wav_audio.launch
@@ -1,4 +1,4 @@
-
+
\ 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 d7c148d..05a54f1 100755
--- a/vz_acoustic_scene_analysis/scripts/stretch_audio.py
+++ b/vz_acoustic_scene_analysis/scripts/stretch_audio.py
@@ -86,11 +86,11 @@ PARAMETERS = {
class Tuning:
- TIMEOUT = 100000
+ # TIMEOUT = rospy.get_param("/TIMEOUT_SECONDS", 100000)
audio_list = []
def __init__(self):
- self.TIMEOUT = 100000
+ self.TIMEOUT = rospy.get_param("/VZ_ACOUSTIC_SCENE_ANALYSIS/TIMEOUT_SECONDS", 100000)
self.dev = usb.core.find(idVendor=0x2886, idProduct=0x0018)
if not self.dev:
@@ -185,11 +185,11 @@ def get_respeaker_device_id():
return device_id
-RESPEAKER_RATE = rospy.get_param("/RESPEAKER_RATE", 16000)
-RESPEAKER_CHANNELS = rospy.get_param("/RESPEAKER_CHANNELS", 6) # 6 must flash 6_channels_firmware.bin first
-RESPEAKER_WIDTH = rospy.get_param("/RESPEAKER_WIDTH", 2)
+RESPEAKER_RATE = rospy.get_param("/VZ_ACOUSTIC_SCENE_ANALYSIS/RESPEAKER_RATE", 16000)
+RESPEAKER_CHANNELS = rospy.get_param("/VZ_ACOUSTIC_SCENE_ANALYSIS/RESPEAKER_CHANNELS", 6) # 6 must flash 6_channels_firmware.bin first
+RESPEAKER_WIDTH = rospy.get_param("/VZ_ACOUSTIC_SCENE_ANALYSIS/RESPEAKER_WIDTH", 2)
RESPEAKER_INDEX = get_respeaker_device_id()
-CHUNK = rospy.get_param("/CHUNK", 1024)
+CHUNK = rospy.get_param("/VZ_ACOUSTIC_SCENE_ANALYSIS/CHUNK", 1024)
class ROSInterface:
def __init__(self):
@@ -197,8 +197,8 @@ class ROSInterface:
self.wav_list = []
self.record_count = 0 # Count how many times we've recorded f seconds of 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.secs = rospy.get_param("/VZ_ACOUSTIC_SCENE_ANALYSIS/seconds")
+ self.chunk_size = rospy.get_param("/VZ_ACOUSTIC_SCENE_ANALYSIS/chunk_size")
self.respeaker = Tuning()
# Publisher for Audio Data
self.audio_data_pub = rospy.Publisher("/wav_data", numpy_msg(VZ_AudioData), queue_size=10)