travis_test_motors1.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #encoding: utf8
3 import unittest, rostest
4 import rosnode, rospy
5 import time
6 from raspicat.msg import MotorFreqs
7 from geometry_msgs.msg import Twist
8 
9 class MotorTest(unittest.TestCase):
10  def file_check(self,dev,value,message):
11  with open("/dev/" + dev,"r") as f:
12  self.assertEqual(f.readline(),str(value)+"\n",message)
13 
14  def test_node_exist(self):
15  nodes = rosnode.get_node_names()
16  self.assertIn('/motors', nodes, "node does not exist")
17 
18  def test_put_freq(self):
19  pub = rospy.Publisher('/motor_raw', MotorFreqs)
20  m = MotorFreqs()
21  m.left_hz = 123
22  m.right_hz = 456
23  for i in range(10):
24  pub.publish(m)
25  time.sleep(0.1)
26 
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")
29 
30  def test_put_cmd_vel(self):
31  pub = rospy.Publisher('/cmd_vel', Twist)
32  m = Twist()
33  m.linear.x = 0.4775
34  m.angular.z = 1.7115
35  for i in range(10):
36  pub.publish(m)
37  time.sleep(0.1)
38 
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")
41 
42  time.sleep(1.1)
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]")
45 
46 if __name__ == '__main__':
47  time.sleep(3)
48  rospy.init_node('travis_test_motors')
49  rostest.rosrun('raspicat','travis_test_motors', MotorTest)
def file_check(self, dev, value, message)


raspicat
Author(s): Ryuichi Ueda , Daisuke Sato
autogenerated on Mon Jun 10 2019 14:27:50