sound_detector_volume.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 from cv_bridge import CvBridge
4 from sound_classification.msg import InSound
5 from sensor_msgs.msg import Image
6 import rospy
7 from topic_tools import LazyTransport
8 
9 
11  """
12  Detect whether the robot is in sound or not by sound volume.
13 
14  Robot is detected as 'in_sound' when
15  the average power of pixels is more then 'power_per_pixel_threshold'
16  """
17 
18  def __init__(self):
19  super(self.__class__, self).__init__()
20  # ROS
21  self.threshold = rospy.get_param('~power_per_pixel_threshold', 0)
22  self.pub = self.advertise('~in_sound', InSound, queue_size=1)
23  self.cv_bridge = CvBridge()
24 
25  def subscribe(self):
26  self.sub = rospy.Subscriber('~input', Image, self._cb)
27 
28  def unsubscribe(self):
29  self.sub.unregister()
30 
31  def _cb(self, msg):
32  img = self.cv_bridge.imgmsg_to_cv2(msg)
33  pub_msg = InSound()
34  pub_msg.header = msg.header
35  power_per_pixel = img.sum() / img.size
36  rospy.logdebug('power_per_pixel: {}, threshold: {}'.format(
37  power_per_pixel, self.threshold))
38  if power_per_pixel > self.threshold:
39  rospy.logdebug('### In sound ###')
40  pub_msg.in_sound = True
41  else:
42  rospy.logdebug('No sound')
43  pub_msg.in_sound = False
44  self.pub.publish(pub_msg)
45 
46 
47 if __name__ == '__main__':
48  rospy.init_node('sound_detector_volume')
50  rospy.spin()
sound_detector_volume.SoundDetectorVolume
Definition: sound_detector_volume.py:10
sound_detector_volume.SoundDetectorVolume.unsubscribe
def unsubscribe(self)
Definition: sound_detector_volume.py:28
sound_detector_volume.SoundDetectorVolume.threshold
threshold
Definition: sound_detector_volume.py:21
sound_detector_volume.SoundDetectorVolume.__init__
def __init__(self)
Definition: sound_detector_volume.py:18
sound_detector_volume.SoundDetectorVolume.pub
pub
Definition: sound_detector_volume.py:22
topic_tools::LazyTransport::advertise
def advertise(self, *args, **kwargs)
sound_detector_volume.SoundDetectorVolume.subscribe
def subscribe(self)
Definition: sound_detector_volume.py:25
sound_detector_volume.SoundDetectorVolume.sub
sub
Definition: sound_detector_volume.py:26
topic_tools::LazyTransport
sound_detector_volume.SoundDetectorVolume.cv_bridge
cv_bridge
Definition: sound_detector_volume.py:23
sound_detector_volume.SoundDetectorVolume._cb
def _cb(self, msg)
Definition: sound_detector_volume.py:31


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