Browse Source

updated audio node name and removed prints

pull/65/head
Hongyu Li 2 years ago
parent
commit
8e37484dd7
5 changed files with 14 additions and 8 deletions
  1. +1
    -1
      vz_acoustic_scene_analysis/launch/wav_audio.launch
  2. +2
    -4
      vz_acoustic_scene_analysis/scripts/ros_interface.py
  3. +3
    -1
      vz_ros_wrappers/launch/D435i_and_Lepton.launch
  4. +4
    -1
      vz_ros_wrappers/scripts/grab_D435i.py
  5. +4
    -1
      vz_ros_wrappers/scripts/grab_thermal.py

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

@ -1,4 +1,4 @@
<launch> <launch>
<rosparam ns="VZ_ACOUSTIC_SCENE_ANALYSIS" command="load" file="$(find vz_acoustic_scene_analysis)/config/audio_params.yaml" /> <rosparam ns="VZ_ACOUSTIC_SCENE_ANALYSIS" command="load" file="$(find vz_acoustic_scene_analysis)/config/audio_params.yaml" />
<node name="stretch_audio" pkg="vz_acoustic_scene_analysis" type="stretch_audio.py" output="screen" />
<node name="stretch_audio" pkg="vz_acoustic_scene_analysis" type="ros_interface.py" output="screen" />
</launch> </launch>

vz_acoustic_scene_analysis/scripts/stretch_audio.py → vz_acoustic_scene_analysis/scripts/ros_interface.py View File

@ -222,6 +222,7 @@ class ROSInterface:
self.sequence_size = 3 # self.secs/self.chunk_size self.sequence_size = 3 # self.secs/self.chunk_size
if (self.record_count % self.sequence_size == 0): if (self.record_count % self.sequence_size == 0):
return_list = self.wav_list return_list = self.wav_list
print("Collected %d seconds of audio" %(self.secs))
# Remove fist two objects in array to remove 0.2 seconds of audio data from array # Remove fist two objects in array to remove 0.2 seconds of audio data from array
self.wav_list.pop(0) self.wav_list.pop(0)
self.wav_list.pop(0) self.wav_list.pop(0)
@ -245,8 +246,6 @@ class ROSInterface:
for i in range(0, arr_length): for i in range(0, arr_length):
data = stream.read(CHUNK) data = stream.read(CHUNK)
a = np.frombuffer(data,dtype=np.int16)[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) self.audio_data_pub.publish(a)
frames.append(a.tobytes()) frames.append(a.tobytes())
@ -275,10 +274,9 @@ class ROSInterface:
if(isinstance(wav_data, list)): if(isinstance(wav_data, list)):
# flatten list # flatten list
flat_list = [item for sublist in wav_data for item in sublist] flat_list = [item for sublist in wav_data for item in sublist]
print(type(flat_list[0]))
# Call of Utku's function # Call of Utku's function
self.cough_prob = dsp.classify_cough(flat_list,RESPEAKER_RATE,self.loaded_model,self.loaded_scaler) self.cough_prob = dsp.classify_cough(flat_list,RESPEAKER_RATE,self.loaded_model,self.loaded_scaler)
print(self.cough_prob)
print("%d %% probability of cough" %(self.cough_prob))
# do something with probability (publish?) # do something with probability (publish?)
except usb.core.USBError: except usb.core.USBError:
print('Respeaker not on USB bus') print('Respeaker not on USB bus')

+ 3
- 1
vz_ros_wrappers/launch/D435i_and_Lepton.launch View File

@ -4,5 +4,7 @@
<node pkg="image_transport" type="republish" name="D435iCompressed" <node pkg="image_transport" type="republish" name="D435iCompressed"
args="raw in:=/D435i/image_raw compressed out:=/D435i/image_raw" /> args="raw in:=/D435i/image_raw compressed out:=/D435i/image_raw" />
<!-- Flip images and display when collecting data? --> <!-- Flip images and display when collecting data? -->
<param name="flip_images_grab_data" type="bool" value="true" />
<param name="flip_images_grab_data" type="bool" value="true" />
<param name="rgbd_topic" type="string" value="/D435i/image_raw" />
<param name="thermal_topic" type="string" value="/Lepton/image_raw" />
</launch> </launch>

+ 4
- 1
vz_ros_wrappers/scripts/grab_D435i.py View File

@ -44,10 +44,13 @@ class D435i:
self.D435i_cap = cv2.VideoCapture('/dev/video4') self.D435i_cap = cv2.VideoCapture('/dev/video4')
# self.D435i_cap = cv2.VideoCapture('/home/ananya/Downloads/2022-02-09-16-20-58(2).mp4') # self.D435i_cap = cv2.VideoCapture('/home/ananya/Downloads/2022-02-09-16-20-58(2).mp4')
# Get topic parameter
self.rgbd_topic = rospy.get_param("rgbd_topic")
if not self.D435i_cap.isOpened(): if not self.D435i_cap.isOpened():
raise(Exception,'Unable to open video stream') raise(Exception,'Unable to open video stream')
self.bridge = CvBridge() self.bridge = CvBridge()
self.D435i_pub = rospy.Publisher('/D435i/image_raw', Image, queue_size=100)
self.D435i_pub = rospy.Publisher(self.rgbd_topic, Image, queue_size=100)
self.timer = rospy.Timer(rospy.Duration(0, UPDATE_RATE), self.publish_image) self.timer = rospy.Timer(rospy.Duration(0, UPDATE_RATE), self.publish_image)
self.timer_display = rospy.Timer(rospy.Duration(0, UPDATE_RATE), self.display_images) self.timer_display = rospy.Timer(rospy.Duration(0, UPDATE_RATE), self.display_images)

+ 4
- 1
vz_ros_wrappers/scripts/grab_thermal.py View File

@ -49,11 +49,14 @@ class FLIR_LEPTON:
self.thermal_cap = cv2.VideoCapture('/dev/video6') self.thermal_cap = cv2.VideoCapture('/dev/video6')
# self.thermal_cap = cv2.VideoCapture('/home/ananya/Downloads/Thermal-3(2).mp4') # self.thermal_cap = cv2.VideoCapture('/home/ananya/Downloads/Thermal-3(2).mp4')
# Get topic parameter
self.thermal_topic = rospy.get_param("thermal_topic")
if not self.thermal_cap.isOpened(): if not self.thermal_cap.isOpened():
raise(Exception,'Unable to open video stream') raise(Exception,'Unable to open video stream')
self.bridge = CvBridge() self.bridge = CvBridge()
self.thermal_pub = rospy.Publisher('/flir_3_5_near_realsense_raw', Image, queue_size=100)
self.thermal_pub = rospy.Publisher(self.thermal_topic, Image, queue_size=100)
self.timer = rospy.Timer(rospy.Duration(0, UPDATE_RATE), self.publish_image) self.timer = rospy.Timer(rospy.Duration(0, UPDATE_RATE), self.publish_image)
self.timer_display = rospy.Timer(rospy.Duration(0, UPDATE_RATE), self.display_images) self.timer_display = rospy.Timer(rospy.Duration(0, UPDATE_RATE), self.display_images)

Loading…
Cancel
Save