Skip to content

Commit

Permalink
Bigger nperseg shows more detail in the spectrogram
Browse files Browse the repository at this point in the history
  • Loading branch information
lucasw committed May 19, 2023
1 parent 8bae90d commit f6a80dc
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 1 deletion.
4 changes: 3 additions & 1 deletion audio_to_float/scripts/spectrogram.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,9 @@ def update(self, event):
if len(self.buffer) < self.buffer_len:
return
samples = np.asarray(self.buffer)
f, t, Sxx = signal.spectrogram(samples, self.sample_rate)
# TODO(lucasw) this is hugely inefficient if it is re-calculating
# for samples that were processed in previous update.
f, t, Sxx = signal.spectrogram(samples, self.sample_rate, nperseg=512)
# TODO(lucasw) is there a standard spectrogram conversion?
Sxx = np.log(1.0 + Sxx * 2**16)
mins = np.min(Sxx)
Expand Down
2 changes: 2 additions & 0 deletions float_to_audio/scripts/gen_float.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
# In order to support this a fifo buffer will store all the samples to be
# played back, and grow it as needed to support the longest sample received.

import random
import rospy

from sensor_msgs.msg import ChannelFloat32
Expand Down Expand Up @@ -56,6 +57,7 @@ def update(self, event):
val += sc * (fr * 4.0 - 1.0)
else:
val += sc * (1.0 - ((fr - 0.5) * 4.0))
val += random.random() * 0.2
self.msg.values[i] = val
self.counter += 1

Expand Down

0 comments on commit f6a80dc

Please sign in to comment.