Go to the documentation of this file.00001
00002
00003 from __future__ import print_function
00004
00005 import unittest
00006
00007 import rospy
00008 from sound_play.msg import SoundRequest, SoundRequestAction, SoundRequestResult
00009
00010 import actionlib
00011
00012 PKG = 'pr2eus'
00013 NAME = 'test_speack_action'
00014
00015 class TestSpeakAction(unittest.TestCase):
00016 _result = SoundRequestResult()
00017
00018 speak_msg = []
00019 speak_msg_jp = []
00020
00021 def cb(self, msg):
00022 rospy.logwarn("received speak_msg")
00023 self.speak_msg.append(msg.sound_request)
00024 self._as_en.set_succeeded(self._result)
00025
00026 def cb_jp(self, msg):
00027 rospy.logwarn("received speak_msg_jp")
00028 self.speak_msg_jp.append(msg.sound_request)
00029 self._as_jp.set_succeeded(self._result)
00030
00031 def setUp(self):
00032 rospy.init_node(NAME)
00033 self._as_en = actionlib.SimpleActionServer('/robotsound', SoundRequestAction, execute_cb=self.cb, auto_start=False)
00034 self._as_jp = actionlib.SimpleActionServer('/robotsound_jp', SoundRequestAction, execute_cb=self.cb_jp, auto_start=False)
00035 self._as_en.start()
00036 self._as_jp.start()
00037
00038 def test_speak(self):
00039 rospy.sleep(10)
00040 rospy.logwarn("test speak")
00041 rospy.logwarn(self.speak_msg)
00042 rospy.logwarn(self.speak_msg_jp)
00043 while self.speak_msg == []:
00044 rospy.logwarn("waiting for speak_msg")
00045 rospy.sleep(1)
00046 rospy.logwarn("check speak_msg")
00047 rospy.logwarn(self.speak_msg)
00048 while self.speak_msg_jp == []:
00049 rospy.logwarn("waiting for speak_msg_jp")
00050 rospy.sleep(1)
00051 rospy.logwarn("check speak_msg_jp")
00052 rospy.logwarn(self.speak_msg_jp)
00053 rospy.logwarn("test speak_msg + speak_msg_jp")
00054 for msg in self.speak_msg + self.speak_msg_jp:
00055 rospy.logwarn(msg)
00056 self.assertTrue(msg.command == SoundRequest.PLAY_ONCE)
00057 if hasattr(SoundRequest, 'volume'):
00058 self.assertTrue(msg.volume > 0)
00059 self.assertTrue((msg.sound == SoundRequest.SAY and len(msg.arg) > 0) or
00060 (msg.sound == SoundRequest.PLAY_FILE and len(msg.arg) > 0) or
00061 (msg.sound > 0))
00062
00063 if __name__ == '__main__':
00064 import rostest
00065 rostest.rosrun(PKG, NAME, TestSpeakAction)