travis_test_motors2.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 from std_srvs.srv import Trigger, TriggerResponse #追加
9 
10 class MotorTest(unittest.TestCase):
11  def setUp(self): #このメソッドを追加
12  rospy.wait_for_service('/motor_on')
13  rospy.wait_for_service('/motor_off')
14  on = rospy.ServiceProxy('/motor_on', Trigger)
15  ret = on()
16 
17  def file_check(self,dev,value,message):
18  with open("/dev/" + dev,"r") as f:
19  self.assertEqual(f.readline(),str(value)+"\n",message)
20 
21  def test_node_exist(self):
22  nodes = rosnode.get_node_names()
23  self.assertIn('/motors', nodes, "node does not exist")
24 
25  def test_put_freq(self):
26  pub = rospy.Publisher('/motor_raw', MotorFreqs)
27  m = MotorFreqs()
28  m.left_hz = 123
29  m.right_hz = 456
30  for i in range(10):
31  pub.publish(m)
32  time.sleep(0.1)
33 
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")
36 
37  def test_put_cmd_vel(self):
38  pub = rospy.Publisher('/cmd_vel', Twist)
39  m = Twist()
40  m.linear.x = 0.4775
41  m.angular.z = 1.7115
42  for i in range(10):
43  pub.publish(m)
44  time.sleep(0.1)
45 
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")
48 
49  time.sleep(1.1)
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]")
52 
53  def test_on_off(self): #このメソッドも追加
54  off = rospy.ServiceProxy('/motor_off', Trigger)
55  ret = off()
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:
59  data = f.readline()
60  self.assertEqual(data,"0\n","wrong value in rtmotor0 at motor off")
61 
62  on = rospy.ServiceProxy('/motor_on', Trigger)
63  ret = on()
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:
67  data = f.readline()
68  self.assertEqual(data,"1\n","wrong value in rtmotor0 at motor on")
69 
70 if __name__ == '__main__':
71  rospy.init_node('travis_test_motors')
72  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