WUT Velma robot API
test_head_complex.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 
41 import rospy
42 import copy
43 
44 from velma_common import *
45 from rcprg_ros_utils import exitError
46 
47 if __name__ == "__main__":
48 
49  rospy.init_node('head_test', anonymous=True)
50 
51  rospy.sleep(0.5)
52 
53  print "This test/tutorial executes complex motions"\
54  " of head along with motions in Joint Impedance mode."
55 
56  print "Running python interface for Velma..."
57  velma = VelmaInterface()
58  print "Waiting for VelmaInterface initialization..."
59  if not velma.waitForInit(timeout_s=10.0):
60  print "Could not initialize VelmaInterface\n"
61  exitError(1)
62  print "Initialization ok!\n"
63 
64  diag = velma.getCoreCsDiag()
65  if not diag.motorsReady():
66  print "Motors must be homed and ready to use for this test."
67  exitError(1)
68 
69  print "Motors must be enabled every time after the robot enters safe state."
70  print "If the motors are already enabled, enabling them has no effect."
71  print "Enabling motors..."
72  if velma.enableMotors() != 0:
73  exitError(2)
74 
75  print "Moving to the current position..."
76  velma.moveJointImpToCurrentPos(start_time=0.5)
77  error = velma.waitForJoint()
78  if error != 0:
79  print "The action should have ended without error, but the error code is", error
80  exitError(3)
81 
82  print "moving head to position: left"
83  q_dest = (1.56, 0)
84  velma.moveHead(q_dest, 2.0, start_time=0.5)
85  if velma.waitForHead() != 0:
86  exitError(4)
87  if not isHeadConfigurationClose( velma.getHeadCurrentConfiguration(), q_dest, 0.1 ):
88  exitError(5)
89 
90  print "moving head to position: right (interrupted by invalid motion in Joint Impedance mode)"
91  q_dest = (-1.56, 0)
92  velma.moveHead(q_dest, 10.0, start_time=0.5)
93 
94  rospy.sleep(0.5)
95 
96  print "Moving too fast to another position (safe mode in velma_core_ve_body)..."
97  q_map_0 = {'torso_0_joint':0,
98  'right_arm_0_joint':0,
99  'right_arm_1_joint':0,
100  'right_arm_2_joint':0,
101  'right_arm_3_joint':0,
102  'right_arm_4_joint':0,
103  'right_arm_5_joint':0,
104  'right_arm_6_joint':0,
105  'left_arm_0_joint':0,
106  'left_arm_1_joint':0,
107  'left_arm_2_joint':0,
108  'left_arm_3_joint':0,
109  'left_arm_4_joint':0,
110  'left_arm_5_joint':0,
111  'left_arm_6_joint':0}
112 
113  velma.moveJoint(q_map_0, 0.05, start_time=0.5, position_tol=0, velocity_tol=0)
114  error = velma.waitForJoint()
115  if error == 0:
116  print "The action should have ended with error, but the error code is", error
117  exitError(6)
118 
119  if velma.waitForHead() == 0:
120  exitError(7)
121  rospy.sleep(0.5)
122 
123  if isHeadConfigurationClose( velma.getHeadCurrentConfiguration(), q_dest, 0.1 ):
124  exitError(8)
125 
126  rospy.sleep(1.0)
127 
128  print "Motors must be enabled every time after the robot enters safe state."
129  print "If the motors are already enabled, enabling them has no effect."
130  print "Enabling motors..."
131  if velma.enableMotors() != 0:
132  exitError(9)
133 
134  print "Moving to the current position..."
135  js = velma.getLastJointState()
136  velma.moveJoint(js[1], 0.5, start_time=0.5, position_tol=15.0/180.0*math.pi)
137  error = velma.waitForJoint()
138  if error != 0:
139  print "The action should have ended without error, but the error code is", error
140  exitError(10)
141 
142  print "Checking if old trajectory for head is continued..."
143  rospy.sleep(2.0)
144  if isHeadConfigurationClose( velma.getHeadCurrentConfiguration(), q_dest, 0.1 ):
145  exitError(11)
146 
147  print "moving head to position: 0"
148  q_dest = (0,0)
149  velma.moveHead(q_dest, 2.0, start_time=0.5)
150  if velma.waitForHead() != 0:
151  exitError(20)
152  if not isHeadConfigurationClose( velma.getHeadCurrentConfiguration(), q_dest, 0.1 ):
153  exitError(21)
154 
155  exitError(0)
156 
def isHeadConfigurationClose(q1, q2, tolerance=0.1)
Check if two configurations of robot neck are close within tolerance.