speak-test.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 from __future__ import print_function
4 
5 import unittest
6 
7 import rospy
8 from sound_play.msg import SoundRequest
9 
10 PKG = 'pr2eus'
11 NAME = 'test_speack'
12 
13 class TestSpeak(unittest.TestCase):
14 
15  speak_msg = None
16  speak_msg_jp = None
17 
18  def cb(self, msg):
19  rospy.logwarn("received speak_msg")
20  self.speak_msg = msg
21 
22  def cb_jp(self, msg):
23  rospy.logwarn("received speak_msg_jp")
24  self.speak_msg_jp = msg
25 
26  def setUp(self):
27  rospy.init_node(NAME)
28  rospy.Subscriber('/robotsound', SoundRequest, self.cb)
29  rospy.Subscriber('/robotsound_jp', SoundRequest, self.cb_jp)
30 
31  def test_speak(self):
32  rospy.sleep(10)
33  rospy.logwarn(self.speak_msg)
34  rospy.logwarn(self.speak_msg_jp)
35  while self.speak_msg == None:
36  rospy.logwarn("waiting for speak_msg")
37  rospy.sleep(1)
38  rospy.logwarn("check speak_msg")
39  self.assertTrue(self.speak_msg.command == SoundRequest.PLAY_ONCE)
40  if hasattr(SoundRequest, 'volume'): # volume is added from 0.3.0 https://github.com/ros-drivers/audio_common/commit/da9623414f381642e52f59701c09928c72a54be7#diff-fe2d85580f1ccfed4e23a608df44a7f7
41  self.assertTrue(self.speak_msg.volume > 0)
42  self.assertTrue(len(self.speak_msg.arg) > 0)
43 
44  while self.speak_msg_jp == None:
45  rospy.logwarn("waiting for speak_msg_jp")
46  rospy.sleep(1)
47  rospy.logwarn("check speak_msg")
48  self.assertTrue(self.speak_msg_jp.command == SoundRequest.PLAY_ONCE)
49  if hasattr(SoundRequest, 'volume'):
50  self.assertTrue(self.speak_msg_jp.volume > 0)
51  self.assertTrue(len(self.speak_msg_jp.arg) > 0)
52 
53 if __name__ == '__main__':
54  import rostest
55  rostest.rosrun(PKG, NAME, TestSpeak)
def test_speak(self)
Definition: speak-test.py:31
def cb(self, msg)
Definition: speak-test.py:18
def cb_jp(self, msg)
Definition: speak-test.py:22


pr2eus
Author(s): Kei Okada
autogenerated on Fri Mar 5 2021 04:00:40