WUT Velma robot API
test_head.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=False)
50 
51  rospy.sleep(0.5)
52 
53  print "This test/tutorial executes simple motions"\
54  " of head."
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  js_start = velma.getLastJointState()
77  velma.moveJoint(js_start[1], 0.5, start_time=0.5, position_tol=15.0/180.0*math.pi)
78  error = velma.waitForJoint()
79  if error != 0:
80  print "The action should have ended without error, but the error code is", error
81  exitError(3)
82 
83  print "moving head to position: 0"
84  q_dest = (0,0)
85  velma.moveHead(q_dest, 1.0, start_time=0.5)
86  if velma.waitForHead() != 0:
87  exitError(4)
88  rospy.sleep(0.5)
89  if not isHeadConfigurationClose( velma.getHeadCurrentConfiguration(), q_dest, 0.1 ):
90  exitError(5)
91 
92  print "moving head to position: left"
93  q_dest = (1.56, 0)
94  velma.moveHead(q_dest, 3.0, start_time=0.5)
95  if velma.waitForHead() != 0:
96  exitError(6)
97  rospy.sleep(0.5)
98  if not isHeadConfigurationClose( velma.getHeadCurrentConfiguration(), q_dest, 0.1 ):
99  exitError(7)
100 
101  print "moving head to position: left down"
102  q_dest = (1.56, 0.7)
103  velma.moveHead(q_dest, 2.0, start_time=0.5)
104  if velma.waitForHead() != 0:
105  exitError(6)
106  rospy.sleep(0.5)
107  if not isHeadConfigurationClose( velma.getHeadCurrentConfiguration(), q_dest, 0.1 ):
108  exitError(7)
109 
110  print "moving head to position: right down"
111  q_dest = (-1.56, 0.7)
112  velma.moveHead(q_dest, 5.0, start_time=0.5)
113  if velma.waitForHead() != 0:
114  exitError(8)
115  rospy.sleep(0.5)
116  if not isHeadConfigurationClose( velma.getHeadCurrentConfiguration(), q_dest, 0.1 ):
117  exitError(9)
118 
119  print "moving head to position: right"
120  q_dest = (-1.56, 0)
121  velma.moveHead(q_dest, 2.0, start_time=0.5)
122  if velma.waitForHead() != 0:
123  exitError(8)
124  rospy.sleep(0.5)
125  if not isHeadConfigurationClose( velma.getHeadCurrentConfiguration(), q_dest, 0.1 ):
126  exitError(9)
127 
128  print "moving head to position: 0"
129  q_dest = (0,0)
130  velma.moveHead(q_dest, 3.0, start_time=0.5)
131  if velma.waitForHead() != 0:
132  exitError(14)
133  if not isHeadConfigurationClose( velma.getHeadCurrentConfiguration(), q_dest, 0.1 ):
134  exitError(15)
135 
136  exitError(0)
137 
def isHeadConfigurationClose(q1, q2, tolerance=0.1)
Check if two configurations of robot neck are close within tolerance.