3 import unittest, rostest
6 from raspicat.msg
import MotorFreqs
7 from geometry_msgs.msg
import Twist
8 from std_srvs.srv
import Trigger, TriggerResponse
12 rospy.wait_for_service(
'/motor_on')
13 rospy.wait_for_service(
'/motor_off')
14 on = rospy.ServiceProxy(
'/motor_on', Trigger)
18 with open(
"/dev/" + dev,
"r") as f: 19 self.assertEqual(f.readline(),str(value)+"\n",message)
22 nodes = rosnode.get_node_names()
23 self.assertIn(
'/motors', nodes,
"node does not exist")
26 pub = rospy.Publisher(
'/motor_raw', MotorFreqs)
34 self.
file_check(
"rtmotor_raw_l0",m.left_hz,
"wrong left value from motor_raw")
35 self.
file_check(
"rtmotor_raw_r0",m.right_hz,
"wrong right value from motor_raw")
38 pub = rospy.Publisher(
'/cmd_vel', Twist)
46 self.
file_check(
"rtmotor_raw_l0",200,
"wrong left value from cmd_vel")
47 self.
file_check(
"rtmotor_raw_r0",600,
"wrong right value from cmd_vel")
50 self.
file_check(
"rtmotor_raw_r0",0,
"don't stop after 1[s]")
51 self.
file_check(
"rtmotor_raw_l0",0,
"don't stop after 1[s]")
54 off = rospy.ServiceProxy(
'/motor_off', Trigger)
56 self.assertEqual(ret.success,
True,
"motor off does not succeeded")
57 self.assertEqual(ret.message,
"OFF",
"motor off wrong message")
58 with open(
"/dev/rtmotoren0",
"r") as f: 60 self.assertEqual(data,"0\n",
"wrong value in rtmotor0 at motor off")
62 on = rospy.ServiceProxy(
'/motor_on', Trigger)
64 self.assertEqual(ret.success,
True,
"motor on does not succeeded")
65 self.assertEqual(ret.message,
"ON",
"motor on wrong message")
66 with open(
"/dev/rtmotoren0",
"r") as f: 68 self.assertEqual(data,"1\n",
"wrong value in rtmotor0 at motor on")
70 if __name__ ==
'__main__':
71 rospy.init_node(
'travis_test_motors')
72 rostest.rosrun(
'raspicat',
'travis_test_motors', MotorTest)
def test_node_exist(self)
def file_check(self, dev, value, message)
def test_put_cmd_vel(self)