3 import unittest, rostest
6 from raspicat.msg
import LightSensorValues
11 rospy.Subscriber(
'/lightsensors', LightSensorValues, self.
callback)
20 self.assertEqual(vs.left_forward, lf,
"different value: left_forward")
21 self.assertEqual(vs.left_side, ls,
"different value: left_side")
22 self.assertEqual(vs.right_side, rs,
"different value: right_side")
23 self.assertEqual(vs.right_forward, rf,
"different value: right_forward")
24 self.assertEqual(vs.sum_all, lf+ls+rs+rf,
"different value: sum_all")
25 self.assertEqual(vs.sum_forward, lf+rf,
"different value: sum_forward")
28 nodes = rosnode.get_node_names()
29 self.assertIn(
'/lightsensors',nodes,
"node does not exist")
32 rospy.set_param(
'/lightsensors/frequency',10)
34 with open(
"/dev/rtlightsensor0",
"w")
as f:
35 f.write(
"-1 0 123 4321\n")
39 self.assertFalse(self.
count == 0,
"cannot subscribe the topic")
43 rospy.set_param(
'/lightsensors/frequency',1)
48 self.assertTrue(self.
count < c_prev + 4,
"freq does not change")
49 self.assertFalse(self.
count == c_prev,
"subscriber is stopped")
51 if __name__ ==
'__main__':
53 rospy.init_node(
'travis_test_lightsensors')
54 rostest.rosrun(
'raspicat',
'travis_test_lightsensors',LightsensorTest)
def check_values(self, lf, ls, rs, rf)
count
コールバック関数が最低1回は呼ばれ、値が取得できているかを確認###
def test_node_exist(self)
def test_change_parameter(self)