3 import unittest, rostest
6 from raspicat.msg
import MotorFreqs
7 from geometry_msgs.msg
import Twist
11 with open(
"/dev/" + dev,
"r") as f: 12 self.assertEqual(f.readline(),str(value)+"\n",message)
15 nodes = rosnode.get_node_names()
16 self.assertIn(
'/motors', nodes,
"node does not exist")
19 pub = rospy.Publisher(
'/motor_raw', MotorFreqs)
27 self.
file_check(
"rtmotor_raw_l0",m.left_hz,
"wrong left value from motor_raw")
28 self.
file_check(
"rtmotor_raw_r0",m.right_hz,
"wrong right value from motor_raw")
31 pub = rospy.Publisher(
'/cmd_vel', Twist)
39 self.
file_check(
"rtmotor_raw_l0",200,
"wrong left value from cmd_vel")
40 self.
file_check(
"rtmotor_raw_r0",600,
"wrong right value from cmd_vel")
43 self.
file_check(
"rtmotor_raw_r0",0,
"don't stop after 1[s]")
44 self.
file_check(
"rtmotor_raw_l0",0,
"don't stop after 1[s]")
46 if __name__ ==
'__main__':
48 rospy.init_node(
'travis_test_motors')
49 rostest.rosrun(
'raspicat',
'travis_test_motors', MotorTest)
def file_check(self, dev, value, message)
def test_node_exist(self)
def test_put_cmd_vel(self)