WUT Velma robot API
test_jimp_endless.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 *
46 from control_msgs.msg import FollowJointTrajectoryResult
47 
48 def exitError(code):
49  if code == 0:
50  print "OK"
51  exit(0)
52  print "ERROR:", code
53  exit(code)
54 
55 if __name__ == "__main__":
56  # define some configurations
57 
58  # every joint in position 0
59  q_map_0 = {'torso_0_joint':0, 'right_arm_0_joint':0, 'right_arm_1_joint':0,
60  'right_arm_2_joint':0, 'right_arm_3_joint':0, 'right_arm_4_joint':0, 'right_arm_5_joint':0,
61  'right_arm_6_joint':0, 'left_arm_0_joint':0, 'left_arm_1_joint':0, 'left_arm_2_joint':0,
62  'left_arm_3_joint':0, 'left_arm_4_joint':0, 'left_arm_5_joint':0, 'left_arm_6_joint':0 }
63 
64  # starting position
65  q_map_starting = {'torso_0_joint':0, 'right_arm_0_joint':-0.3, 'right_arm_1_joint':-1.8,
66  'right_arm_2_joint':1.25, 'right_arm_3_joint':0.85, 'right_arm_4_joint':0, 'right_arm_5_joint':-0.5,
67  'right_arm_6_joint':0, 'left_arm_0_joint':0.3, 'left_arm_1_joint':1.8, 'left_arm_2_joint':-1.25,
68  'left_arm_3_joint':-0.85, 'left_arm_4_joint':0, 'left_arm_5_joint':0.5, 'left_arm_6_joint':0 }
69 
70  q_map_left = {'torso_0_joint':45.0/180.0*math.pi, 'right_arm_0_joint':-0.3, 'right_arm_1_joint':-1.8,
71  'right_arm_2_joint':1.25, 'right_arm_3_joint':0.85, 'right_arm_4_joint':0, 'right_arm_5_joint':-0.5,
72  'right_arm_6_joint':0, 'left_arm_0_joint':0.3, 'left_arm_1_joint':1.8, 'left_arm_2_joint':-1.25,
73  'left_arm_3_joint':-0.85, 'left_arm_4_joint':0, 'left_arm_5_joint':0.5, 'left_arm_6_joint':0 }
74 
75  q_map_right = {'torso_0_joint':-45.0/180.0*math.pi, 'right_arm_0_joint':-0.3, 'right_arm_1_joint':-1.8,
76  'right_arm_2_joint':1.25, 'right_arm_3_joint':0.85, 'right_arm_4_joint':0, 'right_arm_5_joint':-0.5,
77  'right_arm_6_joint':0, 'left_arm_0_joint':0.3, 'left_arm_1_joint':1.8, 'left_arm_2_joint':-1.25,
78  'left_arm_3_joint':-0.85, 'left_arm_4_joint':0, 'left_arm_5_joint':0.5, 'left_arm_6_joint':0 }
79 
80  rospy.init_node('test_jimp')
81 
82  rospy.sleep(0.5)
83 
84  print "This test/tutorial executes simple motions"\
85  " in joint impedance mode. Planning is not used"\
86  " in this example.\n"
87 
88  print "Running python interface for Velma..."
89  velma = VelmaInterface()
90  print "Waiting for VelmaInterface initialization..."
91  if not velma.waitForInit(timeout_s=10.0):
92  print "Could not initialize VelmaInterface\n"
93  exitError(1)
94  print "Initialization ok!\n"
95 
96  print "Motors must be enabled every time after the robot enters safe state."
97  print "If the motors are already enabled, enabling them has no effect."
98  print "Enabling motors..."
99  if velma.enableMotors() != 0:
100  exitError(2)
101 
102  rospy.sleep(0.5)
103 
104  diag = velma.getCoreCsDiag()
105  if not diag.motorsReady():
106  print "Motors must be homed and ready to use for this test."
107  exitError(1)
108 
109  print "Switch to jnt_imp mode (no trajectory)..."
110  velma.moveJointImpToCurrentPos(start_time=0.5)
111  error = velma.waitForJoint()
112  if error != 0:
113  print "The action should have ended without error, but the error code is", error
114  exitError(3)
115 
116  while not rospy.is_shutdown():
117  print "Checking if the starting configuration is as expected..."
118  rospy.sleep(0.5)
119  js = velma.getLastJointState()
120  if not isConfigurationClose(q_map_starting, js[1], tolerance=0.3):
121  print "This test requires starting pose:"
122  print q_map_starting
123  # exitError(10)
124 
125  print "Moving to position 0 (slowly)."
126  velma.moveJoint(q_map_0, 9.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
127  velma.waitForJoint()
128 
129  rospy.sleep(0.5)
130  js = velma.getLastJointState()
131  if not isConfigurationClose(q_map_0, js[1], tolerance=0.1):
132  exitError(10)
133 
134  rospy.sleep(1.0)
135 
136  print "Moving to the starting position..."
137  velma.moveJoint(q_map_starting, 9.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
138  error = velma.waitForJoint()
139  if error != 0:
140  print "The action should have ended without error, but the error code is", error
141  exitError(6)
142 
143  rospy.sleep(0.5)
144  js = velma.getLastJointState()
145  if not isConfigurationClose(q_map_starting, js[1], tolerance=0.1):
146  exitError(10)
147 
148 
149  print "Moving to the left position..."
150  velma.moveJoint(q_map_left, 5.0, start_time=0.5, position_tol=20.0/180.0*math.pi)
151  error = velma.waitForJoint()
152  if error != 0:
153  print "The action should have ended without error, but the error code is", error
154  exitError(6)
155 
156  rospy.sleep(0.5)
157  js = velma.getLastJointState()
158  if not isConfigurationClose(q_map_left, js[1], tolerance=0.1):
159  exitError(10)
160 
161  print "Moving to the right position..."
162  velma.moveJoint(q_map_right, 10.0, start_time=0.5, position_tol=20.0/180.0*math.pi)
163  error = velma.waitForJoint()
164  if error != 0:
165  print "The action should have ended without error, but the error code is", error
166  exitError(6)
167 
168  rospy.sleep(0.5)
169  js = velma.getLastJointState()
170  if not isConfigurationClose(q_map_right, js[1], tolerance=0.1):
171  exitError(10)
172 
173 
174  print "Moving to the starting position..."
175  velma.moveJoint(q_map_starting, 5.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
176  error = velma.waitForJoint()
177  if error != 0:
178  print "The action should have ended without error, but the error code is", error
179  exitError(6)
180 
181  rospy.sleep(0.5)
182  js = velma.getLastJointState()
183  if not isConfigurationClose(q_map_starting, js[1], tolerance=0.1):
184  exitError(10)
185 
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.