WUT Velma robot API
test_cimp_pose.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 import rospy
41 
42 from velma_common import *
43 from rcprg_planner import *
44 from rcprg_ros_utils import exitError
45 
46 if __name__ == "__main__":
47  # define some configurations
48  q_map_starting = {'torso_0_joint':0,
49  'right_arm_0_joint':-0.3, 'left_arm_0_joint':0.3,
50  'right_arm_1_joint':-1.8, 'left_arm_1_joint':1.8,
51  'right_arm_2_joint':1.25, 'left_arm_2_joint':-1.25,
52  'right_arm_3_joint':0.85, 'left_arm_3_joint':-0.85,
53  'right_arm_4_joint':0, 'left_arm_4_joint':0,
54  'right_arm_5_joint':-0.5, 'left_arm_5_joint':0.5,
55  'right_arm_6_joint':0, 'left_arm_6_joint':0 }
56 
57  q_map_1 = {'torso_0_joint':0.0,
58  'right_arm_0_joint':-0.3, 'left_arm_0_joint':0.3,
59  'right_arm_1_joint':-1.57, 'left_arm_1_joint':1.57,
60  'right_arm_2_joint':1.57, 'left_arm_2_joint':-1.57,
61  'right_arm_3_joint':1.57, 'left_arm_3_joint':-1.7,
62  'right_arm_4_joint':0.0, 'left_arm_4_joint':0.0,
63  'right_arm_5_joint':-1.57, 'left_arm_5_joint':1.57,
64  'right_arm_6_joint':0.0, 'left_arm_6_joint':0.0 }
65 
66  rospy.init_node('test_cimp_pose')
67 
68  rospy.sleep(0.5)
69 
70  print "This test/tutorial executes simple motions"\
71  " in Cartesian impedance mode.\n"
72 
73  print "Running python interface for Velma..."
74  velma = VelmaInterface()
75  print "Waiting for VelmaInterface initialization..."
76  if not velma.waitForInit(timeout_s=10.0):
77  print "Could not initialize VelmaInterface\n"
78  exitError(1)
79  print "Initialization ok!\n"
80 
81  diag = velma.getCoreCsDiag()
82  if not diag.motorsReady():
83  print "Motors must be homed and ready to use for this test."
84  exitError(1)
85 
86  print "waiting for Planner init..."
87  p = Planner(velma.maxJointTrajLen())
88  if not p.waitForInit():
89  print "could not initialize PLanner"
90  exitError(2)
91  print "Planner init ok"
92 
93  # define a function for frequently used routine in this test
94  def planAndExecute(q_dest):
95  print "Planning motion to the goal position using set of all joints..."
96  print "Moving to valid position, using planned trajectory."
97  goal_constraint = qMapToConstraints(q_dest, 0.01, group=velma.getJointGroup("impedance_joints"))
98  for i in range(5):
99  rospy.sleep(0.5)
100  js = velma.getLastJointState()
101  print "Planning (try", i, ")..."
102  traj = p.plan(js[1], [goal_constraint], "impedance_joints", max_velocity_scaling_factor=0.15, planner_id="RRTConnect")
103  if traj == None:
104  continue
105  print "Executing trajectory..."
106  if not velma.moveJointTraj(traj, start_time=0.5):
107  exitError(5)
108  if velma.waitForJoint() == 0:
109  break
110  else:
111  print "The trajectory could not be completed, retrying..."
112  continue
113  rospy.sleep(0.5)
114  js = velma.getLastJointState()
115  if not isConfigurationClose(q_dest, js[1]):
116  exitError(6)
117 
118 
119  if velma.enableMotors() != 0:
120  exitError(14)
121 
122  print "Switch to jnt_imp mode (no trajectory)..."
123  velma.moveJointImpToCurrentPos(start_time=0.2)
124  error = velma.waitForJoint()
125  if error != 0:
126  print "The action should have ended without error, but the error code is", error
127  exitError(3)
128 
129  rospy.sleep(0.5)
130  diag = velma.getCoreCsDiag()
131  if not diag.inStateJntImp():
132  print "The core_cs should be in jnt_imp state, but it is not"
133  exitError(3)
134 
135  print "Checking if the starting configuration is as expected..."
136  rospy.sleep(0.5)
137  js = velma.getLastJointState()
138  if not isConfigurationClose(q_map_starting, js[1], tolerance=0.2):
139  print "This test requires starting pose:"
140  print q_map_starting
141  exitError(10)
142 
143  # get initial configuration
144  js_init = velma.getLastJointState()
145 
146  planAndExecute(q_map_1)
147 
148  print "Switch to cart_imp mode (no trajectory)..."
149  if not velma.moveCartImpRightCurrentPos(start_time=0.2):
150  exitError(8)
151  if velma.waitForEffectorRight() != 0:
152  exitError(9)
153 
154  rospy.sleep(0.5)
155 
156  diag = velma.getCoreCsDiag()
157  if not diag.inStateCartImp():
158  print "The core_cs should be in cart_imp state, but it is not"
159  exitError(3)
160 
161  print "Reset tools for both arms..."
162  T_B_Wr = velma.getTf("B", "Wr")
163  T_B_Wl = velma.getTf("B", "Wl")
164  if not velma.moveCartImpRight([T_B_Wr], [0.1], [PyKDL.Frame()], [0.1], None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
165  exitError(8)
166  if not velma.moveCartImpLeft([T_B_Wl], [0.1], [PyKDL.Frame()], [0.1], None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
167  exitError(8)
168  if velma.waitForEffectorRight() != 0:
169  exitError(9)
170  if velma.waitForEffectorLeft() != 0:
171  exitError(9)
172 
173  print "Moving right wrist to pose defined in world frame..."
174  T_B_Trd = PyKDL.Frame(PyKDL.Rotation.Quaternion( 0.0 , 0.0 , 0.0 , 1.0 ), PyKDL.Vector( 0.7 , -0.3 , 1.3 ))
175  if not velma.moveCartImpRight([T_B_Trd], [3.0], None, None, None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
176  exitError(8)
177  if velma.waitForEffectorRight() != 0:
178  exitError(9)
179  rospy.sleep(0.5)
180  print "calculating difference between desiread and reached pose..."
181  T_B_T_diff = PyKDL.diff(T_B_Trd, velma.getTf("B", "Tr"), 1.0)
182  print T_B_T_diff
183  if T_B_T_diff.vel.Norm() > 0.05 or T_B_T_diff.rot.Norm() > 0.05:
184  exitError(10)
185 
186 
187  print "Rotating right writs by 30 deg around local z axis (right-hand side matrix multiplication)"
188  T_B_Tr = velma.getTf("B", "Tr")
189  T_B_Trd = T_B_Tr * PyKDL.Frame(PyKDL.Rotation.RotZ(30.0/180.0*math.pi))
190  if not velma.moveCartImpRight([T_B_Trd], [2.0], None, None, None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
191  exitError(8)
192  if velma.waitForEffectorRight() != 0:
193  exitError(9)
194  rospy.sleep(0.5)
195 
196  print "Rotating right writs by 30 deg around local y axis (right-hand side matrix multiplication)"
197  T_B_Tr = velma.getTf("B", "Tr")
198  T_B_Trd = T_B_Tr * PyKDL.Frame(PyKDL.Rotation.RotY(30.0/180.0*math.pi))
199  if not velma.moveCartImpRight([T_B_Trd], [2.0], None, None, None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
200  exitError(8)
201  if velma.waitForEffectorRight() != 0:
202  exitError(9)
203  rospy.sleep(0.5)
204 
205  print "Rotating right writs by 30 deg around local x axis (right-hand side matrix multiplication)"
206  T_B_Tr = velma.getTf("B", "Tr")
207  T_B_Trd = T_B_Tr * PyKDL.Frame(PyKDL.Rotation.RotX(30.0/180.0*math.pi))
208  if not velma.moveCartImpRight([T_B_Trd], [2.0], None, None, None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
209  exitError(8)
210  if velma.waitForEffectorRight() != 0:
211  exitError(9)
212  rospy.sleep(0.5)
213 
214  planAndExecute(q_map_1)
215 
216  print "Moving right wrist to pose defined in world frame..."
217  T_B_Trd = PyKDL.Frame(PyKDL.Rotation.Quaternion( 0.0 , 0.0 , 0.0 , 1.0 ), PyKDL.Vector( 0.7 , -0.3 , 1.3 ))
218  if not velma.moveCartImpRight([T_B_Trd], [3.0], None, None, None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
219  exitError(8)
220  if velma.waitForEffectorRight() != 0:
221  exitError(9)
222  rospy.sleep(0.5)
223  print "calculating difference between desiread and reached pose..."
224  T_B_T_diff = PyKDL.diff(T_B_Trd, velma.getTf("B", "Tr"), 1.0)
225  print T_B_T_diff
226  if T_B_T_diff.vel.Norm() > 0.05 or T_B_T_diff.rot.Norm() > 0.05:
227  exitError(10)
228 
229 
230  print "Rotating right writs by 30 deg around global z axis (left-hand side matrix multiplication)"
231  T_B_Tr = velma.getTf("B", "Tr")
232  T_B_Tr_old = T_B_Tr
233  T_B_Trd = PyKDL.Frame(PyKDL.Rotation.RotZ(30.0/180.0*math.pi)) * T_B_Tr
234  if not velma.moveCartImpRight([T_B_Trd], [3.0], None, None, None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
235  exitError(8)
236  if velma.waitForEffectorRight() != 0:
237  exitError(9)
238  rospy.sleep(0.5)
239 
240  print "Moving right wrist to the previous pose (cart_imp)..."
241  if not velma.moveCartImpRight([T_B_Tr_old], [3.0], None, None, None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
242  exitError(8)
243  if velma.waitForEffectorRight() != 0:
244  exitError(9)
245  rospy.sleep(0.5)
246 
247  print "Rotating right writs by 30 deg around global z axis (left-hand side matrix multiplication for rotation only, position is constant)"
248  T_B_Tr = velma.getTf("B", "Tr")
249  T_B_Trd = PyKDL.Frame( PyKDL.Rotation.RotZ(30.0/180.0*math.pi) * T_B_Tr.M, T_B_Tr.p )
250  if not velma.moveCartImpRight([T_B_Trd], [2.0], None, None, None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
251  exitError(8)
252  if velma.waitForEffectorRight() != 0:
253  exitError(9)
254  rospy.sleep(0.5)
255 
256  print "Rotating right writs by 30 deg around global y axis (left-hand side matrix multiplication for rotation only, position is constant)"
257  T_B_Tr = velma.getTf("B", "Tr")
258  T_B_Trd = PyKDL.Frame( PyKDL.Rotation.RotY(30.0/180.0*math.pi) * T_B_Tr.M, T_B_Tr.p )
259  if not velma.moveCartImpRight([T_B_Trd], [2.0], None, None, None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
260  exitError(8)
261  if velma.waitForEffectorRight() != 0:
262  exitError(9)
263  rospy.sleep(0.5)
264 
265  print "Rotating right writs by 30 deg around global x axis (left-hand side matrix multiplication for rotation only, position is constant)"
266  T_B_Tr = velma.getTf("B", "Tr")
267  T_B_Trd = PyKDL.Frame( PyKDL.Rotation.RotX(30.0/180.0*math.pi) * T_B_Tr.M, T_B_Tr.p )
268  if not velma.moveCartImpRight([T_B_Trd], [2.0], None, None, None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
269  exitError(8)
270  if velma.waitForEffectorRight() != 0:
271  exitError(9)
272  rospy.sleep(0.5)
273 
274  planAndExecute(q_map_1)
275 
276  print "Switch to cart_imp mode (no trajectory)..."
277  if not velma.moveCartImpRightCurrentPos(start_time=0.2):
278  exitError(8)
279  if velma.waitForEffectorRight() != 0:
280  exitError(9)
281 
282  print "Rotating right writs by 45 deg around local z axis and left wrist by -45 deg (right-hand side matrix multiplication)"
283  synchronized_time = rospy.Time.now() + rospy.Duration(0.5)
284  T_B_Tr = velma.getTf("B", "Tr")
285  T_B_Trd = T_B_Tr * PyKDL.Frame(PyKDL.Rotation.RotZ(30.0/180.0*math.pi))
286  T_B_Tl = velma.getTf("B", "Tl")
287  T_B_Tld = T_B_Tl * PyKDL.Frame(PyKDL.Rotation.RotZ(-30.0/180.0*math.pi))
288  if not velma.moveCartImpRight([T_B_Trd], [2.0], None, None, None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), stamp=synchronized_time):
289  exitError(8)
290  if not velma.moveCartImpLeft([T_B_Tld], [2.0], None, None, None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), stamp=synchronized_time):
291  exitError(8)
292  if velma.waitForEffectorRight() != 0:
293  exitError(9)
294  if velma.waitForEffectorLeft() != 0:
295  exitError(9)
296  rospy.sleep(0.5)
297 
298  print "Rotating both writs by 30 deg around local x axis (right-hand side matrix multiplication)"
299  synchronized_time = rospy.Time.now() + rospy.Duration(0.5)
300  T_B_Tr = velma.getTf("B", "Tr")
301  T_B_Trd = T_B_Tr * PyKDL.Frame(PyKDL.Rotation.RotX(30.0/180.0*math.pi))
302  T_B_Tl = velma.getTf("B", "Tl")
303  T_B_Tld = T_B_Tl * PyKDL.Frame(PyKDL.Rotation.RotX(30.0/180.0*math.pi))
304  if not velma.moveCartImpRight([T_B_Trd, T_B_Tr], [2.0, 4.0], None, None, None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), stamp=synchronized_time):
305  exitError(8)
306  if not velma.moveCartImpLeft([T_B_Tld, T_B_Tl], [2.0, 4.0], None, None, None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), stamp=synchronized_time):
307  exitError(8)
308  if velma.waitForEffectorRight() != 0:
309  exitError(9)
310  if velma.waitForEffectorLeft() != 0:
311  exitError(9)
312  rospy.sleep(0.5)
313 
314  print "Rotating right writs by 30 deg around global x axis (left-hand side matrix multiplication for rotation only, position is constant)"
315  synchronized_time = rospy.Time.now() + rospy.Duration(0.5)
316  T_B_Tr = velma.getTf("B", "Tr")
317  T_B_Trd = PyKDL.Frame( PyKDL.Rotation.RotX(30.0/180.0*math.pi) * T_B_Tr.M, T_B_Tr.p )
318  T_B_Tl = velma.getTf("B", "Tl")
319  T_B_Tld = PyKDL.Frame( PyKDL.Rotation.RotX(30.0/180.0*math.pi) * T_B_Tl.M, T_B_Tl.p )
320  if not velma.moveCartImpRight([T_B_Trd, T_B_Tr], [2.0, 4.0], None, None, None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), stamp=synchronized_time):
321  exitError(8)
322  if not velma.moveCartImpLeft([T_B_Tld, T_B_Tl], [2.0, 4.0], None, None, None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), stamp=synchronized_time):
323  exitError(8)
324  if velma.waitForEffectorRight() != 0:
325  exitError(9)
326  if velma.waitForEffectorLeft() != 0:
327  exitError(9)
328  rospy.sleep(0.5)
329 
330  planAndExecute(q_map_starting)
331 
332  exitError(0)
333 
def planAndExecute(q_dest)
def qMapToConstraints(q_map, tolerance=0.01, group=None)
This function converts dictionary of joint positions to moveit_msgs.Constraints structure.
def isConfigurationClose(q_map1, q_map2, tolerance=0.1, allow_subset=False)
Check if two configurations of robot body are close within tolerance.