noise_saver.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import numpy as np
4 from os import makedirs
5 from os import path as osp
6 
7 from cv_bridge import CvBridge
8 import rospkg
9 import rospy
10 from sensor_msgs.msg import Image
11 
12 
13 class NoiseSaver(object):
14  """
15  Collect noise spectrum (no_sound spectrum)
16  which is used for both sound detection and noise subtraction
17 
18  Kill this node by Ctrl-c, then, noise.npy is saved
19  """
20 
21  def __init__(self):
22  # Config for loading noise data
23  rospack = rospkg.RosPack()
24  self.train_dir = osp.join(rospack.get_path(
25  'sound_classification'), 'train_data')
26  if not osp.exists(self.train_dir):
27  makedirs(self.train_dir)
28  self.noise_data_path = osp.join(self.train_dir, 'noise.npy')
29  self.spectrums = np.array([])
30  # ROS
31  rospy.on_shutdown(self.save_noise_spectrum)
32  self.bridge = CvBridge()
33  self.sub = rospy.Subscriber("~raw_spectrogram", Image, self.cb)
34  self.spectrogram = None
35  self.save_data_rate = rospy.get_param('~save_data_rate')
36  rospy.Timer(rospy.Duration(1. / self.save_data_rate), self.timer_cb)
37 
39  """
40  This method is called when this node is killed by Ctrl-c
41  save noise spectrum in 1 file, because it is easy to load
42  """
43 
44  rospy.loginfo(
45  'Saved noise.npy with {} data'.format(len(self.spectrums)))
46  np.save(self.noise_data_path, self.spectrums)
47 
48  def cb(self, msg):
49  self.spectrogram = msg
50 
51  def timer_cb(self, timer):
52  """
53  Main process of NoiseSaver class
54  Append spectrum data to self.spectrums at self.save_data_rate
55  """
56 
57  if self.spectrogram is None:
58  return
59  spectrogram = self.bridge.imgmsg_to_cv2(self.spectrogram)
60  self.current_spectrum = np.mean(spectrogram, axis=1)
61  if len(self.spectrums) == 0:
62  self.spectrums = self.current_spectrum[None]
63  else:
64  self.spectrums = np.append(self.spectrums,
65  self.current_spectrum[None],
66  axis=0)
67  rospy.loginfo('Save {} noise samples.'.format(len(self.spectrums)))
68 
69 
70 if __name__ == '__main__':
71  rospy.init_node('noise_saver')
72  n = NoiseSaver()
73  rospy.spin()
noise_saver.NoiseSaver.current_spectrum
current_spectrum
Definition: noise_saver.py:60
noise_saver.NoiseSaver.noise_data_path
noise_data_path
Definition: noise_saver.py:28
noise_saver.NoiseSaver.save_data_rate
save_data_rate
Definition: noise_saver.py:35
noise_saver.NoiseSaver.spectrums
spectrums
Definition: noise_saver.py:29
noise_saver.NoiseSaver.__init__
def __init__(self)
Definition: noise_saver.py:21
noise_saver.NoiseSaver.timer_cb
def timer_cb(self, timer)
Definition: noise_saver.py:51
noise_saver.NoiseSaver
Definition: noise_saver.py:13
noise_saver.NoiseSaver.spectrogram
spectrogram
Definition: noise_saver.py:34
noise_saver.NoiseSaver.cb
def cb(self, msg)
Definition: noise_saver.py:48
noise_saver.NoiseSaver.train_dir
train_dir
Definition: noise_saver.py:24
noise_saver.NoiseSaver.sub
sub
Definition: noise_saver.py:33
noise_saver.NoiseSaver.save_noise_spectrum
def save_noise_spectrum(self)
Definition: noise_saver.py:38
noise_saver.NoiseSaver.bridge
bridge
Definition: noise_saver.py:32


sound_classification
Author(s):
autogenerated on Fri May 16 2025 03:12:55