test_hironx_ros_bridge_send.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 # Software License Agreement (BSD License)
5 #
6 # Copyright (c) 2014, JSK Lab, University of Tokyo
7 # Copyright (c) 2014, TORK
8 # All rights reserved.
9 #
10 # Redistribution and use in source and binary forms, with or without
11 # modification, are permitted provided that the following conditions
12 # are met:
13 #
14 # * Redistributions of source code must retain the above copyright
15 # notice, this list of conditions and the following disclaimer.
16 # * Redistributions in binary form must reproduce the above
17 # copyright notice, this list of conditions and the following
18 # disclaimer in the documentation and/or other materials provided
19 # with the distribution.
20 # * Neither the name of JSK Lab, University of Tokyo, TORK, nor the
21 # names of its contributors may be used to endorse or promote products
22 # derived from this software without specific prior written permission.
23 #
24 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35 # POSSIBILITY OF SUCH DAMAGE.
36 
37 import rospy
38 from tf.transformations import quaternion_matrix, euler_from_matrix
39 import time
40 
41 from hironx_ros_bridge.testutil.test_rosbridge import TestHiroROSBridge
42 
43 PKG = 'hironx_ros_bridge'
44 
45 
47 
49  #self.rarm.send_goal(self.setup_Positions(self.goal_LArm(), [[-0.6, 0, -120, 15.2, 9.4, 3.2]])) this should returns error
50  self.rarm.send_goal(self.setup_Positions(self.goal_RArm(), [[-0.6, 0, -120, 15.2, 9.4, 3.2]], 5))
51  self.rarm.wait_for_result()
52  self.joint_states = []
53  time.sleep(1.0);
54  tm0 = rospy.Time.now()
55  self.rarm.send_goal(self.setup_Positions(self.goal_RArm(), [[-0.6, 0, -140, 15.2, 9.4, 3.2]], 5))
56  self.rarm.wait_for_result()
57  self.rarm.send_goal(self.setup_Positions(self.goal_RArm(), [[-0.6, 0, -100, 15.2, 9.4, 3.2]], 5))
58  self.rarm.wait_for_result()
59  self.rarm.send_goal(self.setup_Positions(self.goal_RArm(), [[-0.6, 0, -100, 15.2, 9.4, 3.2]], 5))
60  self.rarm.wait_for_result()
61  tm1 = rospy.Time.now()
62  data_time = (tm1 - tm0).to_sec()
63  filename = self.filename_base + "-wait"
64  data = self.check_q_data(filename)
65  min_data = min([d[1] for d in data])
66  max_data = max([d[1] for d in data])
67  print "check setJointAnglesOfGroup(wait=True), tm = ", data_time, ", ok?", abs(data_time - 15.0) < 0.1
68  self.assertTrue(abs(data_time - 15.0) < 1.0)
69  print " min = ", min_data, ", ok?", abs(min_data - -140) < 5
70  self.assertTrue(abs(min_data - -140) < 5)
71  print " max = ", max_data, ", ok?", abs(max_data - -100) < 5
72  self.assertTrue(abs(max_data - -100) < 5)
73 
75  clear_time = [4.5, 4.0, 3.5, 3.0, 2.5, 2.0, 1.5, 1.0]
76  clear_time = [4.5, 3.0, 1.0]
77  for i in range(len(clear_time)):
78  self.rarm.send_goal(self.setup_Positions(self.goal_RArm(), [[-0.6, 0, -120, 15.2, 9.4, 3.2]], 5))
79  self.rarm.wait_for_result()
80  self.joint_states = []
81  rospy.sleep(1.0)
82  tm0 = rospy.Time.now()
83  self.rarm.send_goal(self.setup_Positions(self.goal_RArm(), [[-0.6, 0, -140, 15.2, 9.4, 3.2]], 5))
84  rospy.sleep(clear_time[i]);
85  self.rarm.send_goal(self.setup_Positions(self.goal_RArm(), [[-0.6, 0, -100, 15.2, 9.4, 3.2]], 5))
86  self.rarm.wait_for_result()
87  tm1 = rospy.Time.now()
88  rospy.sleep(1.0)
89  filename = self.filename_base + "-no-wait-"+str(clear_time[i])
90  data = self.check_q_data(filename)
91  data_time = (tm1 - tm0).to_sec()
92  min_data = min([d[1] for d in data])
93  max_data = max([d[1] for d in data])
94  print "check setJointAnglesOfGroup(wait=False), tm = ", data_time, ", ok?", abs(data_time - (10.0 - (5 - clear_time[i]))) < 1.5, " ", (10.0 - (5 - clear_time[i]))
95  self.assertTrue(abs(data_time - (10.0 - (5 - clear_time[i]))) < 1.5)
96  print " min = ", min_data, ", ok?", abs(min_data - (-140+i*40/len(clear_time))) < 20, " ", -140+i*40/len(clear_time)
97  self.assertTrue(abs(min_data - (-140+i*40/len(clear_time))) < 20)
98  print " max = ", max_data, ", ok?", abs(max_data - -100) < 5
99  self.assertTrue(abs(max_data - -100) < 5)
100 
102  clear_time = [1.0, 1.5, 2.0, 2.5, 3.0, 3.5, 4.0, 4.5]
103  clear_time = [4.5, 4.0, 3.5, 3.0, 2.5, 2.0, 1.5, 1.0]
104  clear_time = [4.5, 3.0, 1.0]
105  for i in range(len(clear_time)):
106  self.rarm.send_goal(self.setup_Positions(self.goal_RArm(), [[-0.6, 0, -100, 15.2, 9.4, 3.2]], 5))
107  self.rarm.wait_for_result()
108  self.joint_states = []
109  rospy.sleep(1.0)
110  tm0 = rospy.Time.now()
111  self.rarm.send_goal(self.setup_Positions(self.goal_RArm(), [[-0.6, 0, -100, 15.2, 9.4, 3.2]], 5))
112  self.rarm.wait_for_result()
113  self.rarm.send_goal(self.setup_Positions(self.goal_RArm(), [[-0.6, 0, -140, 15.2, 9.4, 3.2]], 5))
114  rospy.sleep(clear_time[i])
115  self.rarm.cancel_goal()
116  self.rarm.wait_for_result()
117  tm1 = rospy.Time.now()
118  rospy.sleep(1.0)
119  filename = self.filename_base + "-clear-"+str(clear_time[i])
120  data = self.check_q_data(filename)
121  data_time = (tm1 - tm0).to_sec()
122  min_data = min([d[1] for d in data])
123  max_data = max([d[1] for d in data])
124  print "check setJointAnglesOfGroup(clear "+str(clear_time[i])+"), tm = ", data_time, ", ok?", abs(data_time - (10 - (5 - clear_time[i]))) < 0.5, " ", (10 - (5 - clear_time[i]))
125  self.assertTrue(abs(data_time - (10 - (5 - clear_time[i]))) < 0.5)
126  print " min = ", min_data, ", ok?", abs(min_data - (-140+(i+1)*40/len(clear_time))) < 35, " ", -140+(i+1)*40/len(clear_time)
127  self.assertTrue(abs(min_data - (-140+(i+1)*40/len(clear_time))) < 35)
128  print " max = ", max_data, ", ok?", abs(max_data - -100) < 5
129  self.assertTrue(abs(max_data - -100) < 5)
130 
131 if __name__ == '__main__':
132  import rostest
133  rostest.rosrun(PKG, 'test_hronx_ros_bridge_send', TestHiroROSBridgeSend)
134 
135 
136 
#define min(a, b)


hironx_ros_bridge
Author(s): Kei Okada , Isaac I.Y. Saito
autogenerated on Thu May 14 2020 03:52:05