3 import rospy, unittest, rostest, actionlib
6 from std_msgs.msg
import UInt16
7 from raspicat.msg
import MusicAction, MusicResult, MusicFeedback, MusicGoal
15 nodes = rosnode.get_node_names()
16 self.assertIn(
'/buzzer',nodes,
"node does not exist")
19 pub = rospy.Publisher(
'/buzzer', UInt16)
24 with open(
"/dev/rtbuzzer0",
"r") as f: 26 self.assertEqual(data,"1234\n",
"value does not written to rtbuzzer0")
32 goal.freqs = [100, 200, 300, 0]
33 goal.durations = [2,2,2,2]
35 self.client.wait_for_server()
36 self.client.send_goal(goal,feedback_cb=self.
feedback_cb)
37 self.client.wait_for_result()
39 self.assertTrue(self.client.get_result(),
"invalid result")
40 self.assertEqual(goal.freqs,self.
device_values,
"invalid feedback:" 45 self.client.send_goal(goal,feedback_cb=self.
feedback_cb)
46 self.client.wait_for_result(rospy.Duration.from_sec(0.5))
48 self.assertFalse(self.client.get_result(),
"stop is requested but return true")
49 self.assertFalse(goal.freqs == self.
device_values,
"not stopped")
52 with open(
"/dev/rtbuzzer0",
"r") as f: 54 self.device_values.append(int(data.rstrip())) 56 if __name__ ==
'__main__':
58 rospy.init_node(
'travis_test_buzzer')
59 rostest.rosrun(
'raspicat',
'travis_test_buzzer',BuzzerTest)
device_values
skip this test because a problem of this test code ###
def test_node_exist(self)
def feedback_cb(self, feedback)