WUT Velma robot API
test_jimp.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 math
43 import PyKDL
44 
45 from velma_common.velma_interface import VelmaInterface, isConfigurationClose,\
46  symmetricalConfiguration
47 from control_msgs.msg import FollowJointTrajectoryResult
48 from rcprg_ros_utils import exitError
49 
50 if __name__ == "__main__":
51  # Define some configurations
52 
53  # every joint in position 0
54  q_map_0 = symmetricalConfiguration( {'torso_0_joint':0,
55  'right_arm_0_joint':0, 'right_arm_1_joint':0, 'right_arm_2_joint':0,
56  'right_arm_3_joint':0, 'right_arm_4_joint':0, 'right_arm_5_joint':0,
57  'right_arm_6_joint':0} )
58 
59  # starting position
60  q_map_starting = symmetricalConfiguration( {'torso_0_joint':0,
61  'right_arm_0_joint':-0.3, 'right_arm_1_joint':-1.8, 'right_arm_2_joint':1.25,
62  'right_arm_3_joint':0.85, 'right_arm_4_joint':0, 'right_arm_5_joint':-0.5,
63  'right_arm_6_joint':0,} )
64 
65  # goal position
66  q_map_goal = {'torso_0_joint':0,
67  'right_arm_0_joint':-0.3, 'right_arm_1_joint':-1.8, 'right_arm_2_joint':-1.25,
68  'right_arm_3_joint':2.0, 'right_arm_4_joint':0, 'right_arm_5_joint':-0.5,
69  'right_arm_6_joint':0,
70  'left_arm_0_joint':0.3, 'left_arm_1_joint':1.8, 'left_arm_2_joint':-1.25,
71  'left_arm_3_joint':-0.85, 'left_arm_4_joint':0, 'left_arm_5_joint':0.5,
72  'left_arm_6_joint':0 }
73 
74  # intermediate position
75  q_map_intermediate = {'torso_0_joint':0,
76  'right_arm_0_joint':-0.3, 'right_arm_1_joint':-1.6, 'right_arm_2_joint':-1.25,
77  'right_arm_3_joint':-0.85, 'right_arm_4_joint':0, 'right_arm_5_joint':-0.5,
78  'right_arm_6_joint':0,
79  'left_arm_0_joint':0.3, 'left_arm_1_joint':1.8, 'left_arm_2_joint':-1.25,
80  'left_arm_3_joint':-0.85, 'left_arm_4_joint':0, 'left_arm_5_joint':0.5,
81  'left_arm_6_joint':0 }
82 
83  rospy.init_node('test_jimp')
84 
85  rospy.sleep(0.5)
86 
87  print("This test/tutorial executes simple motions"\
88  " in joint impedance mode. Planning is not used"\
89  " in this example.")
90 
91  print("Running python interface for Velma...")
92  velma = VelmaInterface()
93  print("Waiting for VelmaInterface initialization...")
94  if not velma.waitForInit(timeout_s=10.0):
95  exitError(1, msg="Could not initialize VelmaInterface")
96  print("Initialization ok!")
97 
98  print("Motors must be enabled every time after the robot enters safe state.")
99  print("If the motors are already enabled, enabling them has no effect.")
100  print("Enabling motors...")
101  if velma.enableMotors() != 0:
102  exitError(2, msg="Could not enable motors")
103 
104  rospy.sleep(0.5)
105 
106  diag = velma.getCoreCsDiag()
107  if not diag.motorsReady():
108  exitError(1, msg="Motors must be homed and ready to use for this test.")
109 
110 
111  print("Switch to jnt_imp mode (no trajectory)...")
112  velma.moveJointImpToCurrentPos(start_time=0.5)
113  error = velma.waitForJoint()
114  if error != 0:
115  exitError(3, msg="The action should have ended without error,"\
116  " but the error code is {}".format(error))
117 
118  print("Checking if the starting configuration is as expected...")
119  rospy.sleep(0.5)
120  js = velma.getLastJointState()
121  if not isConfigurationClose(q_map_starting, js[1], tolerance=0.3):
122  exitError(10, msg="This test requires starting pose: {}".format(q_map_starting))
123 
124  print("Moving to position 0 (this motion is too fast and should cause error condition,"\
125  " that leads to safe mode in velma_core_cs).")
126  velma.moveJoint(q_map_0, 0.05, start_time=0.5, position_tol=0, velocity_tol=0)
127  error = velma.waitForJoint()
128  if error != FollowJointTrajectoryResult.PATH_TOLERANCE_VIOLATED:
129  exitError(4, msg="The action should have ended with PATH_TOLERANCE_VIOLATED"\
130  " error status, but the error code is {}".format(error) )
131 
132  print("Checking if current pose is close to the starting pose...")
133  rospy.sleep(0.5)
134  js = velma.getLastJointState()
135  if not isConfigurationClose(q_map_starting, js[1], tolerance=0.3):
136  exitError(10)
137 
138  print("waiting 2 seconds...")
139  rospy.sleep(2)
140 
141  print("Motors must be enabled every time after the robot enters safe state.")
142  print("If the motors are already enabled, enabling them has no effect.")
143  print("Enabling motors...")
144  if velma.enableMotors() != 0:
145  exitError(5)
146 
147  print("Moving to position 0 (slowly).")
148  velma.moveJoint(q_map_0, 9.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
149  velma.waitForJoint()
150 
151  rospy.sleep(0.5)
152  js = velma.getLastJointState()
153  if not isConfigurationClose(q_map_0, js[1], tolerance=0.1):
154  exitError(10)
155 
156  rospy.sleep(1.0)
157 
158  print("Moving to the starting position...")
159  velma.moveJoint(q_map_starting, 9.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
160  error = velma.waitForJoint()
161  if error != 0:
162  exitError(6, msg="The action should have ended without error,"\
163  " but the error code is {}".format(error))
164 
165  rospy.sleep(0.5)
166  js = velma.getLastJointState()
167  if not isConfigurationClose(q_map_starting, js[1], tolerance=0.1):
168  exitError(10)
169 
170  print("Moving to valid position, using invalid self-colliding trajectory"\
171  " (this motion should cause error condition, that leads to safe mode in velma_core_cs).")
172  velma.moveJoint(q_map_goal, 9.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
173  error = velma.waitForJoint()
174  if error != FollowJointTrajectoryResult.PATH_TOLERANCE_VIOLATED:
175  exitError(7, msg="The action should have ended with PATH_TOLERANCE_VIOLATED"\
176  " error status, but the error code is {}".format(error) )
177 
178  print("Using relax behavior to exit self collision...")
179  velma.switchToRelaxBehavior()
180 
181  print("waiting 2 seconds...")
182  rospy.sleep(2)
183 
184  print("Motors must be enabled every time after the robot enters safe state.")
185  print("If the motors are already enabled, enabling them has no effect.")
186  print("Enabling motors...")
187  if velma.enableMotors() != 0:
188  exitError(8)
189 
190  print("Moving to the starting position...")
191  velma.moveJoint(q_map_starting, 4.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
192  error = velma.waitForJoint()
193  if error != 0:
194  exitError(9, msg="The action should have ended without error,"\
195  " but the error code is {}".format(error))
196 
197  rospy.sleep(0.5)
198  js = velma.getLastJointState()
199  if not isConfigurationClose(q_map_starting, js[1], tolerance=0.1):
200  exitError(10)
201 
202  print("To reach the goal position, some trajectory must be exetuted that contains additional,"\
203  " intermediate nodes")
204 
205  print("Moving to the intermediate position...")
206  velma.moveJoint(q_map_intermediate, 8.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
207  error = velma.waitForJoint()
208  if error != 0:
209  exitError(10, msg="The action should have ended without error,"\
210  " but the error code is {}".format(error))
211 
212  rospy.sleep(0.5)
213  js = velma.getLastJointState()
214  if not isConfigurationClose(q_map_intermediate, js[1], tolerance=0.1):
215  exitError(10)
216 
217  print("Moving to the goal position.")
218  velma.moveJoint(q_map_goal, 8.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
219  error = velma.waitForJoint()
220  if error != 0:
221  exitError(11, msg="The action should have ended with PATH_TOLERANCE_VIOLATED"\
222  " error status, but the error code is {}".format(error) )
223 
224  rospy.sleep(0.5)
225  js = velma.getLastJointState()
226  if not isConfigurationClose(q_map_goal, js[1], tolerance=0.1):
227  exitError(10)
228 
229  print("Moving to the intermediate position...")
230  velma.moveJoint(q_map_intermediate, 8.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
231  error = velma.waitForJoint()
232  if error != 0:
233  exitError(12, msg="The action should have ended without error,"\
234  " but the error code is {}".format(error))
235 
236  rospy.sleep(0.5)
237  js = velma.getLastJointState()
238  if not isConfigurationClose(q_map_intermediate, js[1], tolerance=0.1):
239  exitError(10)
240 
241  print("Moving to the starting position...")
242  velma.moveJoint(q_map_starting, 5.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
243  error = velma.waitForJoint()
244  if error != 0:
245  exitError(13, msg="The action should have ended without error,"\
246  " but the error code is {}".format(error))
247 
248  rospy.sleep(0.5)
249  js = velma.getLastJointState()
250  if not isConfigurationClose(q_map_starting, js[1], tolerance=0.1):
251  exitError(10)
252 
253  exitError(0)
254 
def isConfigurationClose(q_map1, q_map2, tolerance=0.1, allow_subset=False)
Check if two configurations of robot body are close within tolerance.
ROS-based, Python interface class for WUT Velma Robot.
def symmetricalConfiguration(q_map)
Get configuration based on the input configuration such that all joint positions are symmetrical...