Browse Source

more edits to audio node and added parameters

pull/65/head
Hongyu Li 2 years ago
parent
commit
79c44cbed7
6 changed files with 40 additions and 23 deletions
  1. +10
    -10
      vz_acoustic_scene_analysis/CMakeLists.txt
  2. +11
    -0
      vz_acoustic_scene_analysis/config/audio_params.yaml
  3. +2
    -2
      vz_acoustic_scene_analysis/launch/wav_audio.launch
  4. +1
    -1
      vz_acoustic_scene_analysis/msg/MyAudioData.msg
  5. +1
    -1
      vz_acoustic_scene_analysis/package.xml
  6. +15
    -9
      vz_acoustic_scene_analysis/scripts/stretch_audio.py

+ 10
- 10
vz_acoustic_scene_analysis/CMakeLists.txt View File

@ -143,7 +143,7 @@ include_directories(
## Declare a C++ executable ## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context ## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide ## The recommended prefix ensures that target names across packages don't collide
add_executable(audio_capture scripts/audio_capture.cpp)
# add_executable(audio_capture scripts/audio_capture.cpp)
## Rename C++ executable without prefix ## Rename C++ executable without prefix
@ -154,14 +154,14 @@ add_executable(audio_capture scripts/audio_capture.cpp)
## Add cmake target dependencies of the executable ## Add cmake target dependencies of the executable
## same as for the library above ## same as for the library above
add_dependencies(audio_capture ${catkin_EXPORTED_TARGETS})
# add_dependencies(audio_capture ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against ## Specify libraries to link a library or executable target against
target_link_libraries(audio_capture
${catkin_LIBRARIES}
${GST1.0_LIBRARIES}
${Boost_LIBRARIES}
)
# target_link_libraries(audio_capture
# ${catkin_LIBRARIES}
# ${GST1.0_LIBRARIES}
# ${Boost_LIBRARIES}
# )
############# #############
@ -180,9 +180,9 @@ target_link_libraries(audio_capture
## Mark executables for installation ## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html ## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
install(TARGETS audio_capture
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
# install(TARGETS audio_capture
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark libraries for installation ## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html ## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html

+ 11
- 0
vz_acoustic_scene_analysis/config/audio_params.yaml View File

@ -0,0 +1,11 @@
---
TIMEOUT: 100000
VENDOR_ID: 0x2886
PRODUCT_ID: 0x0018
RESPEAKER_RATE: 16000
RESPEAKER_CHANNELS: 6 # must flash 6_channels_firmware.bin first
RESPEAKER_WIDTH: 2
RESPEAKER_INDEX: get_respeaker_device_id()
CHUNK: 1024
chunk_size: 0.5
seconds: 5

+ 2
- 2
vz_acoustic_scene_analysis/launch/wav_audio.launch View File

@ -1,4 +1,4 @@
<launch> <launch>
<node name="stretch_audio" pkg="respeaker_ros" type="stretch_audio.py" />
<!-- <rosparam file="$(find respeaker_ros)/config/audio_params.yaml" /> -->
<node name="stretch_audio" pkg="vz_acoustic_scene_analysis" type="stretch_audio.py" />
<rosparam file="$(find vz_acoustic_scene_analysis)/config/audio_params.yaml" />
</launch> </launch>

+ 1
- 1
vz_acoustic_scene_analysis/msg/MyAudioData.msg View File

@ -1 +1 @@
uint8[] data
string[] data

+ 1
- 1
vz_acoustic_scene_analysis/package.xml View File

@ -82,4 +82,4 @@
<!-- Other tools can request additional information be placed here --> <!-- Other tools can request additional information be placed here -->
</export> </export>
</package>
</package>

+ 15
- 9
vz_acoustic_scene_analysis/scripts/stretch_audio.py View File

@ -4,6 +4,7 @@ from __future__ import print_function
import pyaudio import pyaudio
import wave import wave
import numpy as np import numpy as np
from sympy import re
import usb.core import usb.core
import struct import struct
import time import time
@ -13,6 +14,7 @@ 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
# what does this mean # what does this mean
@contextmanager @contextmanager
@ -185,11 +187,11 @@ def get_respeaker_device_id():
return device_id return device_id
RESPEAKER_RATE = 16000
RESPEAKER_CHANNELS = 6 # must flash 6_channels_firmware.bin first
RESPEAKER_WIDTH = 2
RESPEAKER_RATE = 16000 #rospy.get_param("/RESPEAKER_RATE") #16000
RESPEAKER_CHANNELS = rospy.get_param("/RESPEAKER_CHANNELS") # 6 must flash 6_channels_firmware.bin first
RESPEAKER_WIDTH = rospy.get_param("/RESPEAKER_WIDTH") # 2
RESPEAKER_INDEX = get_respeaker_device_id() RESPEAKER_INDEX = get_respeaker_device_id()
CHUNK = 1024
CHUNK = rospy.get_param("/RESPEAKER_RATE") # 1024
class Audio: class Audio:
@ -198,17 +200,22 @@ class Audio:
self.wav_list = [] self.wav_list = []
self.record_count = 0 # Count how many times we've recorded f seconds of audio 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.file_name = "/home/hello-robot/Desktop/output_audio.wav"
self.secs = rospy.get_param("/seconds")
self.chunk_size = rospy.get_param("/chunk_size")
# Publisher for Audio Data # Publisher for Audio Data
# self.audio_data_pub = rospy.Publisher("/wav_data", )
self.audio_data_pub = rospy.Publisher("/wav_data", MyAudioData, queue_size=10)
def get_audio(self): def get_audio(self):
recorded_frames = self.record_audio(.2) # set param here chunk size
recorded_frames = self.record_audio(self.chunk_size) # set param here chunk size
# print(str(recorded_frames))
self.audio_data_pub.publish(recorded_frames)
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 % 2) == 0): # set param sequence size
if ((self.record_count % (self.secs/self.chunk_size)) == 0): # set param sequence size
return_list = self.wav_list return_list = self.wav_list
# Remove the first object (0.2 seconds of audio data)
# Remove 0.2 seconds of audio data
self.wav_list.pop(0)
self.wav_list.pop(0) self.wav_list.pop(0)
# send the frames at the beginning of the list (save as wav for now) # send the frames at the beginning of the list (save as wav for now)
return return_list return return_list
@ -240,7 +247,6 @@ class Audio:
def process_audio_loop(self): def process_audio_loop(self):
rospy.init_node("audio_capture") rospy.init_node("audio_capture")
rospy.param
audio_count = 0 audio_count = 0
dev = usb.core.find(idVendor=0x2886, idProduct=0x0018) dev = usb.core.find(idVendor=0x2886, idProduct=0x0018)
try: try:

Loading…
Cancel
Save