|
| 1 | +#!/usr/bin/env python |
| 2 | + |
| 3 | +import collections |
| 4 | +import cv2 |
| 5 | +import numpy as np |
| 6 | +import rospy |
| 7 | + |
| 8 | +# from audio_common_msgs.msg import AudioData |
| 9 | +from cv_bridge import CvBridge, CvBridgeError |
| 10 | +from scipy import signal |
| 11 | +from sensor_msgs.msg import ChannelFloat32, Image |
| 12 | + |
| 13 | + |
| 14 | +class View(): |
| 15 | + def __init__(self): |
| 16 | + self.bridge = CvBridge() |
| 17 | + self.buffer_len = rospy.get_param("~buffer_len", 2**16) |
| 18 | + self.buffer = collections.deque(maxlen=self.buffer_len) |
| 19 | + self.sample_rate = rospy.get_param("~sample_rate", 44100) |
| 20 | + # self.window = 256 |
| 21 | + self.im = None |
| 22 | + self.pub = rospy.Publisher("image_spectrogram", Image, queue_size=1) |
| 23 | + self.sub = rospy.Subscriber("samples", ChannelFloat32, |
| 24 | + self.audio_callback, queue_size=1) |
| 25 | + self.timer = rospy.Timer(rospy.Duration(0.2), self.update) |
| 26 | + |
| 27 | + def audio_callback(self, msg): |
| 28 | + for i in range(len(msg.values)): |
| 29 | + self.buffer.append(msg.values[i]) |
| 30 | + |
| 31 | + def update(self, event): |
| 32 | + if len(self.buffer) < self.buffer_len: |
| 33 | + return |
| 34 | + samples = np.asarray(self.buffer) |
| 35 | + f, t, Sxx = signal.spectrogram(samples, self.sample_rate) |
| 36 | + # TODO(lucasw) is there a standard spectrogram conversion? |
| 37 | + Sxx = np.log(1.0 + Sxx * 2**16) |
| 38 | + mins = np.min(Sxx) |
| 39 | + maxs = np.max(Sxx) |
| 40 | + Sxx -= mins |
| 41 | + print Sxx.shape, mins, maxs |
| 42 | + self.im = (Sxx * 50).astype(np.uint8) |
| 43 | + # self.im[y0:y1+1, i, :] = 255 |
| 44 | + self.pub.publish(self.bridge.cv2_to_imgmsg(self.im, "mono8")) |
| 45 | + # rospy.signal_shutdown("") |
| 46 | + |
| 47 | +if __name__ == '__main__': |
| 48 | + rospy.init_node('spectrogram') |
| 49 | + view = View() |
| 50 | + rospy.spin() |
0 commit comments