spectrum_plot.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 from __future__ import division
5 
6 import matplotlib.pyplot as plt
7 import numpy as np
8 import rospy
9 
10 from jsk_recognition_msgs.msg import Spectrum
11 
12 
13 class SpectrumPlot():
14 
15  def __init__(self):
16  # Set matplotlib config
17  self.fig = plt.figure(figsize=(8, 5))
18  self.fig.suptitle('Spectrum plot', size=12)
19  self.fig.subplots_adjust(left=0.1, right=0.95, top=0.90, bottom=0.1,
20  wspace=0.2, hspace=0.6)
21  self.ax = self.fig.add_subplot(1, 1, 1)
22  self.ax.grid(True)
23  self.ax.set_xlabel('Frequency [Hz]', fontsize=12)
24  self.ax.set_ylabel('Amplitude', fontsize=12)
25  self.line, = self.ax.plot([0, 0], label='Amplitude of Spectrum')
26  # ROS subscriber
27  self.sub_spectrum = rospy.Subscriber(
28  '~spectrum', Spectrum, self._cb, queue_size=1000)
29 
30  def _cb(self, msg):
31  # Plot spectrum
32  self.amp = np.array(msg.amplitude)
33  self.freq = np.array(msg.frequency)
34  self.line.set_data(self.freq, self.amp)
35  self.ax.set_xlim((self.freq.min(), self.freq.max()))
36  self.ax.set_ylim((0.0, 20))
37  self.ax.legend(loc='upper right')
38 
39 
40 if __name__ == '__main__':
41  rospy.init_node('spectrum_plot')
42  SpectrumPlot()
43  while not rospy.is_shutdown():
44  plt.pause(.1) # real-time plotting


audio_to_spectrogram
Author(s):
autogenerated on Mon May 3 2021 03:02:58