WUT Velma robot API
step_run_simulation.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 from simulation_control_msgs.srv import EnableSim, EnableSimRequest
48 
49 if __name__ == "__main__":
50  rospy.init_node('step_run_simulation', anonymous=False)
51 
52  rospy.sleep(0.5)
53 
54  try:
55  rospy.wait_for_service('/gazebo/enable_sim', timeout=10.0)
56  except rospy.ServiceException, e:
57  print "wait_for_service failed: %s"%e
58  exit(0)
59 
60  enable_sim = rospy.ServiceProxy('/gazebo/enable_sim', EnableSim)
61 
62  #req = EnableSimRequest()
63  #req.run_steps = -1
64  #req.block = False
65  #enable_sim(req)
66  #rospy.sleep(0.5)
67 
68  iteration = 0
69  while not rospy.is_shutdown():
70  #rospy.sleep(0.001)
71  req = EnableSimRequest()
72  req.run_steps = 1
73  req.block = True
74  enable_sim(req)
75 
76  iteration += 1
77  if iteration > 500:
78  break
79 
80  time.sleep(0.01)
81 
82  #req = EnableSimRequest()
83  #req.run_steps = -1
84  #req.block = False
85  #enable_sim(req)
86 
87  exit(0)
88 
89  print "This test/tutorial executes simple motions"\
90  " of head."
91 
92  print "Running python interface for Velma..."
93  velma = VelmaInterface()
94  print "Waiting for VelmaInterface initialization..."
95  if not velma.waitForInit(timeout_s=10.0):
96  print "Could not initialize VelmaInterface\n"
97  exitError(1)
98  print "Initialization ok!\n"
99 
100  diag = velma.getCoreCsDiag()
101  if not diag.motorsReady():
102  print "Motors must be homed and ready to use for this test."
103  exitError(1)
104 
105  print "Motors must be enabled every time after the robot enters safe state."
106  print "If the motors are already enabled, enabling them has no effect."
107  print "Enabling motors..."
108  if velma.enableMotors() != 0:
109  exitError(2)
110 
111  print "Moving to the current position..."
112  js_start = velma.getLastJointState()
113  velma.moveJoint(js_start[1], 0.5, start_time=0.5, position_tol=15.0/180.0*math.pi)
114  error = velma.waitForJoint()
115  if error != 0:
116  print "The action should have ended without error, but the error code is", error
117  exitError(3)
118 
119  print "moving head to position: 0"
120  q_dest = (0,0)
121  velma.moveHead(q_dest, 1.0, start_time=0.5)
122  if velma.waitForHead() != 0:
123  exitError(4)
124  rospy.sleep(0.5)
125  if not isHeadConfigurationClose( velma.getHeadCurrentConfiguration(), q_dest, 0.1 ):
126  exitError(5)
127 
128  print "moving head to position: left"
129  q_dest = (1.56, 0)
130  velma.moveHead(q_dest, 3.0, start_time=0.5)
131  if velma.waitForHead() != 0:
132  exitError(6)
133  rospy.sleep(0.5)
134  if not isHeadConfigurationClose( velma.getHeadCurrentConfiguration(), q_dest, 0.1 ):
135  exitError(7)
136 
137  print "moving head to position: left down"
138  q_dest = (1.56, 0.7)
139  velma.moveHead(q_dest, 2.0, start_time=0.5)
140  if velma.waitForHead() != 0:
141  exitError(6)
142  rospy.sleep(0.5)
143  if not isHeadConfigurationClose( velma.getHeadCurrentConfiguration(), q_dest, 0.1 ):
144  exitError(7)
145 
146  print "moving head to position: right down"
147  q_dest = (-1.56, 0.7)
148  velma.moveHead(q_dest, 5.0, start_time=0.5)
149  if velma.waitForHead() != 0:
150  exitError(8)
151  rospy.sleep(0.5)
152  if not isHeadConfigurationClose( velma.getHeadCurrentConfiguration(), q_dest, 0.1 ):
153  exitError(9)
154 
155  print "moving head to position: right"
156  q_dest = (-1.56, 0)
157  velma.moveHead(q_dest, 2.0, start_time=0.5)
158  if velma.waitForHead() != 0:
159  exitError(8)
160  rospy.sleep(0.5)
161  if not isHeadConfigurationClose( velma.getHeadCurrentConfiguration(), q_dest, 0.1 ):
162  exitError(9)
163 
164  print "moving head to position: 0"
165  q_dest = (0,0)
166  velma.moveHead(q_dest, 3.0, start_time=0.5)
167  if velma.waitForHead() != 0:
168  exitError(14)
169  if not isHeadConfigurationClose( velma.getHeadCurrentConfiguration(), q_dest, 0.1 ):
170  exitError(15)
171 
172  exitError(0)
173 
def isHeadConfigurationClose(q1, q2, tolerance=0.1)
Check if two configurations of robot neck are close within tolerance.