4 from os
import makedirs
5 from os
import path
as osp
7 from cv_bridge
import CvBridge
10 from sensor_msgs.msg
import Image
15 Collect noise spectrum (no_sound spectrum)
16 which is used for both sound detection and noise subtraction
18 Kill this node by Ctrl-c, then, noise.npy is saved
23 rospack = rospkg.RosPack()
25 'sound_classification'),
'train_data')
33 self.
sub = rospy.Subscriber(
"~raw_spectrogram", Image, self.
cb)
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
45 'Saved noise.npy with {} data'.format(len(self.
spectrums)))
53 Main process of NoiseSaver class
54 Append spectrum data to self.spectrums at self.save_data_rate
67 rospy.loginfo(
'Save {} noise samples.'.format(len(self.
spectrums)))
70 if __name__ ==
'__main__':
71 rospy.init_node(
'noise_saver')