WUT Velma robot API
test_grippers.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 
7 
8 # Copyright (c) 2017, Robot Control and Pattern Recognition Group,
9 # Institute of Control and Computation Engineering
10 # Warsaw University of Technology
11 #
12 # All rights reserved.
13 #
14 # Redistribution and use in source and binary forms, with or without
15 # modification, are permitted provided that the following conditions are met:
16 # * Redistributions of source code must retain the above copyright
17 # notice, this list of conditions and the following disclaimer.
18 # * Redistributions in binary form must reproduce the above copyright
19 # notice, this list of conditions and the following disclaimer in the
20 # documentation and/or other materials provided with the distribution.
21 # * Neither the name of the Warsaw University of Technology nor the
22 # names of its contributors may be used to endorse or promote products
23 # derived from this software without specific prior written permission.
24 #
25 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
26 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
27 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
28 # DISCLAIMED. IN NO EVENT SHALL <COPYright HOLDER> BE LIABLE FOR ANY
29 # DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
30 # (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
32 # ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
33 # (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
34 # SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
35 #
36 # Author: Dawid Seredynski
37 #
38 
39 import roslib; roslib.load_manifest('velma_task_cs_ros_interface')
40 import rospy
41 import math
42 from velma_common import *
43 from rcprg_ros_utils import exitError
44 
45 def deg2rad(deg):
46  return float(deg)/180.0*math.pi
47 
48 if __name__ == "__main__":
49 
50  rospy.init_node('grippers_test', anonymous=False)
51  rospy.sleep(1)
52  print "waiting for init..."
53 
54  velma = VelmaInterface()
55 
56  print "Waiting for VelmaInterface initialization..."
57  if not velma.waitForInit(timeout_s=10.0):
58  print "Could not initialize VelmaInterface\n"
59  exitError(1)
60 
61  print "Initialization ok!\n"
62 
63  diag = velma.getCoreCsDiag()
64  if not diag.motorsReady():
65  print "Motors must be homed and ready to use for this test."
66  exitError(1)
67 
68  if velma.enableMotors() != 0:
69  exitError(14)
70 
71  print "Switch to jnt_imp mode (no trajectory)..."
72  velma.moveJointImpToCurrentPos(start_time=0.5)
73  error = velma.waitForJoint()
74  if error != 0:
75  print "The action should have ended without error, but the error code is", error
76  exitError(3)
77 
78  reset_left = True
79  reset_right = True
80  move_both = True
81  if reset_left:
82  print "reset left"
83  velma.resetHandLeft()
84  if velma.waitForHandLeft() != 0:
85  exitError(2)
86 
87  rospy.sleep(0.5)
88  if not isHandConfigurationClose( velma.getHandLeftCurrentConfiguration(), [0,0,0,0]):
89  exitError(3, msg="configuration of hand should be 0")
90 
91  if reset_right:
92  print "reset right"
93  velma.resetHandRight()
94  if velma.waitForHandRight() != 0:
95  exitError(4)
96 
97  rospy.sleep(0.5)
98  if not isHandConfigurationClose( velma.getHandRightCurrentConfiguration(), [0,0,0,0]):
99  exitError(5, msg="configuration of hand should be 0")
100 
101  if move_both:
102  for it in range(3):
103  for dest_q in [[deg2rad(30), deg2rad(30), deg2rad(30), deg2rad(30)], [deg2rad(10), deg2rad(10), deg2rad(10), deg2rad(10)]]:
104  velma.moveHandLeft(dest_q, [1, 1, 1, 1], [8000, 8000, 8000, 8000], 100000000, hold=False)
105  velma.moveHandRight(dest_q, [1.25, 1.25, 1.25, 1.25], [4000,4000,4000,4000], 1000, hold=False)
106  if velma.waitForHandLeft() != 0:
107  exitError(2)
108  if velma.waitForHandRight() != 0:
109  exitError(4)
110 
111  dest_q = [deg2rad(30), deg2rad(30), deg2rad(30), deg2rad(180)]
112  velma.moveHandLeft(dest_q, [1, 1, 1, 1], [8000, 8000, 8000, 8000], 100000000, hold=False)
113  velma.moveHandRight(dest_q, [1.25, 1.25, 1.25, 1.25], [4000,4000,4000,4000], 1000, hold=False)
114  if velma.waitForHandLeft() != 0:
115  exitError(2)
116  if velma.waitForHandRight() != 0:
117  exitError(2)
118 
119  dest_q = [deg2rad(140), deg2rad(140), deg2rad(140), deg2rad(180)]
120  velma.moveHandLeft(dest_q, [1, 1, 1, 1], [8000, 8000, 8000, 8000], 100000000, hold=False)
121  velma.moveHandRight(dest_q, [1.25, 1.25, 1.25, 1.25], [4000,4000,4000,4000], 1000, hold=False)
122  if velma.waitForHandLeft() != 0:
123  exitError(2)
124  if velma.waitForHandRight() != 0:
125  exitError(2)
126 
127  exitError(0)
def isHandConfigurationClose(current_q, dest_q, tolerance=0.1)
Check if two configurations of robot hand are close within tolerance.