WUT Velma robot API
object_manipulation_hardware.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 from __future__ import print_function
3 from __future__ import division
4 
5 import roslib; roslib.load_manifest('velma_task_cs_ros_interface')
6 import rospy
7 import math
8 import tf
9 
10 from velma_common import *
11 from rcprg_ros_utils import exitError
12 
13 def move_jnt_imp(q_dest, time):
14  global velma
15  print("Moving to the required position...")
16  velma.moveJoint(q_dest, time, start_time=0.5, position_tol=15.0/180.0*math.pi)
17  error = velma.waitForJoint()
18  if error != 0:
19  print("The action should have ended without error, but the error code is", error)
20  exitError(5)
21 
22 def switch2cart_imp_mode(rORl, timeout):
23  global velma
24  print("Switch to cart_imp mode (no trajectory)...")
25  if (rORl == "right"):
26  if not velma.moveCartImpRightCurrentPos(start_time=0.5):
27  exitError(7)
28  if velma.waitForEffectorRight(timeout_s=timeout) != 0:
29  exitError(8)
30  elif (rORl == "left"):
31  if not velma.moveCartImpLeftCurrentPos(start_time=0.5):
32  exitError(9)
33  if velma.waitForEffectorLeft(timeout_s=timeout) != 0:
34  exitError(10)
35  rospy.sleep(1.0)
36  diag = velma.getCoreCsDiag()
37  if not diag.inStateCartImp():
38  print("The core_cs should be in cart_imp state, but it is not")
39  exitError(11)
40 
42  global velma
43  print("Switch to jnt_imp mode (no trajectory)...")
44  velma.moveJointImpToCurrentPos(start_time=0.5)
45  error = velma.waitForJoint()
46  if error != 0:
47  print("The action should have ended without error, but the error code is", error)
48  exitError(12)
49  rospy.sleep(1.0)
50  diag = velma.getCoreCsDiag()
51  if not diag.inStateJntImp():
52  print("The core_cs should be in jnt_imp state, but it is not")
53  exitError(13)
54 
55 def closeORopen_gripper(rORl, dest_q):
56  global velma
57  if (rORl == "right"):
58  print("move of right gripper:", dest_q)
59  velma.moveHandRight(dest_q, [1.5,1.5,1.5,1.5], [5000,5000,5000,5000], 2000, hold=True)
60  if velma.waitForHandRight() != 0:
61  exitError(14)
62  rospy.sleep(0.1)
63  if not isHandConfigurationClose( velma.getHandRightCurrentConfiguration(), dest_q, tolerance=2.0):
64  exitError(15)
65  elif (rORl == "left"):
66  print("move of left gripper:", dest_q)
67  velma.moveHandLeft(dest_q, [1.5,1.5,1.5,1.5], [5000,5000,5000,5000], 2000, hold=True)
68  if velma.waitForHandLeft() != 0:
69  exitError(16)
70  rospy.sleep(0.1)
71  if not isHandConfigurationClose( velma.getHandLeftCurrentConfiguration(), dest_q, tolerance=2.0):
72  exitError(17)
73 
74 def tool2grip_pose(rORl):
75  if (rORl == "right"):
76  print("Moving the right tool and equilibrium pose from 'wrist' to 'grip' frame...")
77  T_B_Wr = velma.getTf("B", "Wr")
78  T_Wr_Gr = velma.getTf("Wr", "Gr")
79  if not velma.moveCartImpRight([T_B_Wr*T_Wr_Gr], [0.5], [T_Wr_Gr], [0.5], None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
80  exitError(18)
81  if velma.waitForEffectorRight() != 0:
82  exitError(19)
83  print("The right tool is now in 'grip' pose")
84  elif (rORl == "left"):
85  print("Moving the left tool and equilibrium pose from 'wrist' to 'grip' frame...")
86  T_B_Wl = velma.getTf("B", "Wl")
87  T_Wl_Gl = velma.getTf("Wl", "Gl")
88  if not velma.moveCartImpLeft([T_B_Wl*T_Wl_Gl], [0.5], [T_Wl_Gl], [0.5], None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
89  exitError(20)
90  if velma.waitForEffectorLeft() != 0:
91  exitError(21)
92  print("The left tool is now in 'grip' pose")
93  rospy.sleep(0.1)
94 
95 def move_cart_imp(rORl, T_frame, imp_list, pt_val, time):
96  t0 = 0.5
97  max_wr = PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5))
98  p_tol = PyKDL.Twist(PyKDL.Vector(pt_val,pt_val,pt_val), PyKDL.Vector(pt_val,pt_val,pt_val)) # path_tolerance
99  if (rORl == "right"):
100  print("Moving right wrist to pose defined in world frame...")
101  if not velma.moveCartImpRight([T_frame], [time], None, None, [imp_list], [0.01], max_wrench = max_wr, start_time = t0, path_tol = p_tol):
102  exitError(22)
103  if velma.waitForEffectorRight() != 0:
104  exitError(23)
105  elif (rORl == "left"):
106  print("Moving left wrist to pose defined in world frame...")
107  if not velma.moveCartImpLeft([T_frame], [time], None, None, [imp_list], [0.01], max_wrench = max_wr, start_time = t0, path_tol = p_tol):
108  exitError(24)
109  if velma.waitForEffectorLeft() != 0:
110  exitError(25)
111  rospy.sleep(0.1)
112 
113 def identification_movements(rightORleft, imp_list, pt_val, dest_qGrasped, dest_qOpened, T_B_Trd, T_B_Trd_Identif1, T_B_Trd_Identif2):
114  imp_list_id = PyKDL.Wrench(PyKDL.Vector(1000, 1000, 1000), PyKDL.Vector(400, 400, 400))
115  # checking finger's configuration required to grasped the object
116  print("*** start of identification procedure ***")
117  move_cart_imp(rightORleft, T_B_Trd, imp_list_id, pt_val, 8.0)
119  closeORopen_gripper(rightORleft, dest_qGrasped)
120  isHandConfigClose_rORl(rightORleft)
121  q_hand = velma.getHandCurrentConfiguration(rightORleft)
122  dest_qChecked = [q_hand[1], q_hand[4], q_hand[6], 0]
123  print("[FingerOneKnuckleTwo, FingerTwoKnuckleTwo, FingerThreeKnuckleTwo, Spread]:", dest_qChecked)
124  rospy.sleep(0.5)
125  closeORopen_gripper(rightORleft, dest_qOpened)
126  print("Velma's", rightORleft, "gripper opened")
127 
128  # taking mesurements before grasping the object
129  switch2cart_imp_mode(rightORleft, 1.0)
130  #exit(2)
131  tool2grip_pose(rightORleft)
132 
133  print("Moving gripper to first given pose and take first identification measurement")
134  move_cart_imp(rightORleft, T_B_Trd_Identif1, imp_list_id, pt_val, 8.0)
135  closeORopen_gripper(rightORleft, dest_qChecked)
136  rospy.sleep(0.5)
137  velma.sendIdentificationMeasurementCommand(rightORleft, 1)
138  rospy.sleep(0.5)
139  print("Moving gripper to second given pose and take second identification measurement")
140  move_cart_imp(rightORleft, T_B_Trd_Identif2, imp_list_id, pt_val, 8.0)
141  rospy.sleep(0.5)
142  velma.sendIdentificationMeasurementCommand(rightORleft, 2)
143  rospy.sleep(0.5)
144  move_cart_imp(rightORleft, T_B_Trd_Identif1, imp_list_id, pt_val, 8.0)
145 
146  # opening gripper
148  closeORopen_gripper(rightORleft, dest_qOpened)
149  print("Velma's", rightORleft, "gripper opened")
150 
151  # grabbing the object
152  switch2cart_imp_mode(rightORleft, 1.0)
153  tool2grip_pose(rightORleft)
154  print("Moving gripper to pose before grasping object...")
155  move_cart_imp(rightORleft, T_B_Trd, imp_list_id, pt_val, 8.0)
157  closeORopen_gripper(rightORleft, dest_qGrasped)
158  isHandConfigClose_rORl(rightORleft)
159 
160  # taking mesurements after grasping the object
161  switch2cart_imp_mode(rightORleft, 1.0)
162  tool2grip_pose(rightORleft)
163  print("Moving gripper to first given pose and take third identification measurement")
164  move_cart_imp(rightORleft, T_B_Trd_Identif1, imp_list_id, pt_val, 8.0)
165  rospy.sleep(0.5)
166  velma.sendIdentificationMeasurementCommand(rightORleft, 3)
167  rospy.sleep(0.5)
168  print("Moving gripper to second given pose and take fourth identification measurement")
169  move_cart_imp(rightORleft, T_B_Trd_Identif2, imp_list_id, pt_val, 12.0)
170  rospy.sleep(0.5)
171  velma.sendIdentificationMeasurementCommand(rightORleft, 4)
172  rospy.sleep(0.5)
173  move_cart_imp(rightORleft, T_B_Trd_Identif1, imp_list, pt_val, 8.0)
174  print("*** end of identification procedure ***")
175 
176 def switch_weight_compensation(rightORleft, GRAV_OBJ_COMP, imp_list, pt_val):
177  if(rightORleft == 'right'):
178  T_B_Trd = velma.getTf("B", "Gr")
179  elif(rightORleft == 'left'):
180  T_B_Trd = velma.getTf("B", "Gl")
181  velma.setGraspedFlag(rightORleft, GRAV_OBJ_COMP)
182  move_cart_imp(rightORleft, T_B_Trd, imp_list, pt_val, 2.0)
183 
184 def diff_calc(rORl, T_frame):
185  print("Calculating difference between desiread and reached pose...")
186  if (rORl == "right"):
187  T_B_T_diff = PyKDL.diff(T_frame, velma.getTf("B", "Tr"), 1.0)
188  elif (rORl == "left"):
189  T_B_T_diff = PyKDL.diff(T_frame, velma.getTf("B", "Tl"), 1.0)
190  print(T_B_T_diff)
191 
192 def get_tf_rORl(rORl):
193  if (rORl == "right"):
194  T_Wo_grip = velma.getTf("Wo", "Gr") # right gripper
195  elif (rORl == "left"):
196  T_Wo_grip = velma.getTf("Wo", "Gl") # left gripper
197  return T_Wo_grip
198 
200  if (rORl == "right"):
201  if isHandConfigurationClose( velma.getHandRightCurrentConfiguration(), dest_qGrasped, tolerance=0.02):
202  print("Object not grabbed")
203  exitError(26)
204  else:
205  print("Right gripper grabbed the object")
206  elif (rORl == "left"):
207  if isHandConfigurationClose( velma.getHandLeftCurrentConfiguration(), dest_qGrasped, tolerance=0.02):
208  print("Object not grabbed")
209  exitError(27)
210  else:
211  print("Left gripper grabbed the object")
212 
213 def q_map_rORl0(rORl):
214  if (rORl == "right"):
215  q_mapR = {'torso_0_joint':0,
216  'right_arm_0_joint':-0.3, 'left_arm_0_joint':0.3,
217  'right_arm_1_joint':-1.8, 'left_arm_1_joint':1.8,
218  'right_arm_2_joint':1.25, 'left_arm_2_joint':-1.25,
219  'right_arm_3_joint':2.0, 'left_arm_3_joint':-0.85,
220  'right_arm_4_joint':0, 'left_arm_4_joint':0,
221  'right_arm_5_joint':-0.5, 'left_arm_5_joint':0.5,
222  'right_arm_6_joint':0, 'left_arm_6_joint':0 }
223  return q_mapR
224  elif (rORl == "left"):
225  q_mapL = {'torso_0_joint':0,
226  'right_arm_0_joint':-0.3, 'left_arm_0_joint':0.3,
227  'right_arm_1_joint':-1.8, 'left_arm_1_joint':1.8,
228  'right_arm_2_joint':1.25, 'left_arm_2_joint':-1.25,
229  'right_arm_3_joint':0.85, 'left_arm_3_joint':-2.0,
230  'right_arm_4_joint':0, 'left_arm_4_joint':0,
231  'right_arm_5_joint':-0.5, 'left_arm_5_joint':0.5,
232  'right_arm_6_joint':0, 'left_arm_6_joint':0 }
233  return q_mapL
234 
235 def q_map_rORl(rORl, torso_angle):
236  if (rORl == "right"):
237  q_mapR = {'torso_0_joint':torso_angle,
238  'right_arm_0_joint':0.6, 'left_arm_0_joint':0.3,
239  'right_arm_1_joint':-1.1, 'left_arm_1_joint':1.8,
240  'right_arm_2_joint':1.5, 'left_arm_2_joint':-1.25,
241  'right_arm_3_joint':1.8, 'left_arm_3_joint':-0.85,
242  'right_arm_4_joint':1.2, 'left_arm_4_joint':0,
243  'right_arm_5_joint':-1.05, 'left_arm_5_joint':0.5,
244  'right_arm_6_joint':0, 'left_arm_6_joint':0 }
245  return q_mapR
246  elif (rORl == "left"):
247  q_mapL = {'torso_0_joint':torso_angle,
248  'right_arm_0_joint':-0.3, 'left_arm_0_joint':-0.6,
249  'right_arm_1_joint':-1.8, 'left_arm_1_joint':1.1,
250  'right_arm_2_joint':1.25, 'left_arm_2_joint':-1.5,
251  'right_arm_3_joint':0.85, 'left_arm_3_joint':-1.8,
252  'right_arm_4_joint':0, 'left_arm_4_joint':-1.2,
253  'right_arm_5_joint':-0.5, 'left_arm_5_joint':1.05,
254  'right_arm_6_joint':0, 'left_arm_6_joint':0 }
255  return q_mapL
256 
257 
258 if __name__ == "__main__":
259 
260  # start position
261  q_map_starting = {'torso_0_joint':0,
262  'right_arm_0_joint':-0.3, 'left_arm_0_joint':0.3,
263  'right_arm_1_joint':-1.8, 'left_arm_1_joint':1.8,
264  'right_arm_2_joint':1.25, 'left_arm_2_joint':-1.25,
265  'right_arm_3_joint':0.85, 'left_arm_3_joint':-0.85,
266  'right_arm_4_joint':0, 'left_arm_4_joint':0,
267  'right_arm_5_joint':-0.5, 'left_arm_5_joint':0.5,
268  'right_arm_6_joint':0, 'left_arm_6_joint':0 }
269 
270  rospy.init_node('object_control_test')
271  rospy.sleep(0.5)
272 
273 
274  rightORleft = 'right'
275  #rightORleft = 'left'
276 
277  CART_TEST = True
278  #CART_TEST = False
279 
280  GRAV_OBJ_COMP = True
281  #GRAV_OBJ_COMP = False
282 
283 
284  print("Chosen gripper:", rightORleft)
285  print("CART_TEST:", CART_TEST)
286  print("GRAV_OBJ_COMP:", GRAV_OBJ_COMP)
287 
288  # defining the parametres
289  imp_list = PyKDL.Wrench(PyKDL.Vector(500, 500, 500), PyKDL.Vector(100, 100, 100)) # forces and torques
290  pt_val = 0.5
291 
292  dest_qOpened = [0, 0, 0, 0]
293  dest_qOpened2 = [0, 0, 0, math.pi]
294  dest_qClosed = [90.0/180.0*math.pi, 90.0/180.0*math.pi, 90.0/180.0*math.pi, 0]
295  dest_qGrasped = [85.0/180.0*math.pi, 85.0/180.0*math.pi, 85.0/180.0*math.pi, 0]
296 
297  # initializing
298  print("Running python interface for Velma...")
299  velma = VelmaInterface()
300  print("Waiting for VelmaInterface initialization...")
301  if not velma.waitForInit(timeout_s=5.0):
302  print("Could not initialize VelmaInterface")
303  exitError(1)
304  print("Initialization ok!")
305 
306  # rospy.sleep(10)
307  # T_B_Gr = velma.getTf("B", "Gr")
308  # print(T_B_Gr.p)
309  # exit(0)
310 
311  diag = velma.getCoreCsDiag()
312  if not diag.motorsReady():
313  print("Motors must be homed and ready to use for this test.")
314  exitError(2)
315 
316  if velma.enableMotors() != 0:
317  exitError(4)
318 
319  # nothing grasped
320  velma.setGraspedFlag('right', False)
321  velma.setGraspedFlag('left', False)
322 
323  # closing grippers
325  closeORopen_gripper("right", dest_qClosed)
326  print("Right gripper closed")
327  closeORopen_gripper("left", dest_qClosed)
328  print("Left gripper closed")
329 
330  #move_jnt_imp(q_map_starting, 15.0)
331  #exit(1)
332 
333  # moving to proper configuration & opening gripper
334  alfa = 0.0
335  q_map_0 = q_map_rORl0(rightORleft)
336  q_map_1 = q_map_rORl(rightORleft, alfa)
337  move_jnt_imp(q_map_0, 4.0)
338  move_jnt_imp(q_map_1, 8.0)
339  closeORopen_gripper(rightORleft, dest_qOpened)
340  print("Velma's", rightORleft, "gripper opened")
341  #exit(101)
342 
343  # cart_imp_mode initializing
344  switch2cart_imp_mode(rightORleft, 1.0)
345  print("Reset tools for both arms...")
346  T_B_Wr = velma.getTf("B", "Wr")
347  T_B_Wl = velma.getTf("B", "Wl")
348  if not velma.moveCartImpRight([T_B_Wr], [0.5], [PyKDL.Frame()], [0.5], None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
349  exitError(29)
350  if not velma.moveCartImpLeft([T_B_Wl], [0.5], [PyKDL.Frame()], [0.5], None, None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
351  exitError(30)
352  if velma.waitForEffectorRight() != 0:
353  exitError(31)
354  if velma.waitForEffectorLeft() != 0:
355  exitError(32)
356 
357  # preparing to move gripper to the object in cart_imp_mode
358  tool2grip_pose(rightORleft)
359  T_Wo_grip = get_tf_rORl(rightORleft)
360  # do odczytania object_frame --------------------------------------------------
361  # T_Wo_obj1_pos = PyKDL.Vector(0.621926, -0.260334, 0.851752)
362  if(rightORleft == 'right'):
363  T_Wo_obj1_pos = PyKDL.Vector(0.8, -0.17, 1.1) # object
364  elif(rightORleft == 'left'):
365  T_Wo_obj1_pos = PyKDL.Vector(0.8, 0.17, 1.1) # object
366 
367  T_B_Trd = PyKDL.Frame(T_Wo_grip.M, T_Wo_obj1_pos + PyKDL.Vector(0.0, 0.0, 0.0))
368 
369  dr = (T_Wo_obj1_pos - T_Wo_grip.p)
370  drL = math.sqrt(dr[0]**2 + dr[1]**2)
371  T_B_Trd_Identif1 = PyKDL.Frame(T_Wo_grip.M, T_Wo_obj1_pos + PyKDL.Vector(-0.15*dr[0]/drL, -0.15*dr[1]/drL, 0.15))
372  if (rightORleft == "right"):
373  R_z = PyKDL.Rotation.RotZ(-math.pi/2)
374  elif (rightORleft == "left"):
375  R_z = PyKDL.Rotation.RotZ(math.pi/2)
376  T_B_Trd_Identif2 = PyKDL.Frame(T_Wo_grip.M*R_z, T_Wo_obj1_pos + PyKDL.Vector(-0.15*dr[0]/drL, -0.15*dr[1]/drL, 0.15))
377 
378  # identification procedure
379  identification_movements(rightORleft, imp_list, pt_val, dest_qGrasped, dest_qOpened, T_B_Trd, T_B_Trd_Identif1, T_B_Trd_Identif2)
380 
381  # use identified params or not
382  switch_weight_compensation(rightORleft, GRAV_OBJ_COMP, imp_list, pt_val)
383 
384  # moving gripper up
385  print("Moving gripper up...")
386  T_B_Trd = PyKDL.Frame(T_Wo_grip.M, T_Wo_obj1_pos + PyKDL.Vector(0, 0, 0.4))
387  move_cart_imp(rightORleft, T_B_Trd, imp_list, pt_val, 3.0)
388 
389  if(CART_TEST == True):
390  q_map_2 = q_map_rORl(rightORleft, 0.0)
392  move_jnt_imp(q_map_2, 4.0)
393 
394  if(rightORleft == 'right'):
395  pm = 1.0
396  quat_z = 0.0
397  quat_w = 1.0
398  elif(rightORleft == 'left'):
399  pm = -1.0
400  quat_z = math.sin(math.pi/2) # 1.0 -> sin(theta/2)
401  quat_w = math.cos(math.pi/2) # 0.0 -> cos(theta/2)
402  else:
403  print("rightORleft and pm problem...")
404  exitError(34)
405 
406  T_B_Trd2 = PyKDL.Frame(PyKDL.Rotation.Quaternion( 0.0 , 0.0 , quat_z , quat_w ), PyKDL.Vector( 0.7, -0.2*pm, 1.45))
407  T_B_Trd3 = PyKDL.Frame(PyKDL.Rotation.Quaternion( 0.0 , 0.0 , quat_z , quat_w ), PyKDL.Vector( 0.7, -0.2*pm, 1.35))
408  T_B_Trd4 = PyKDL.Frame(PyKDL.Rotation.Quaternion( 0.0 , 0.0 , quat_z , quat_w ), PyKDL.Vector( 0.7, -0.1*pm, 1.35))
409  T_B_Trd5 = PyKDL.Frame(PyKDL.Rotation.Quaternion( 0.0 , 0.0 , quat_z , quat_w ), PyKDL.Vector( 0.7, -0.1*pm, 1.45))
410 
411  switch2cart_imp_mode(rightORleft, 1.0) # optional
412  move_cart_imp(rightORleft, T_B_Trd2, imp_list, pt_val, 3.0)
413  diff_calc(rightORleft, T_B_Trd2)
414 
415  i = 0
416  while i < 2:
417  move_cart_imp(rightORleft, T_B_Trd3, imp_list, pt_val, 3.0)
418  diff_calc(rightORleft, T_B_Trd3)
419  move_cart_imp(rightORleft, T_B_Trd4, imp_list, pt_val, 3.0)
420  diff_calc(rightORleft, T_B_Trd4)
421  move_cart_imp(rightORleft, T_B_Trd5, imp_list, pt_val, 3.0)
422  diff_calc(rightORleft, T_B_Trd5)
423  move_cart_imp(rightORleft, T_B_Trd2, imp_list, pt_val, 3.0)
424  diff_calc(rightORleft, T_B_Trd2)
425  rospy.sleep(1.0)
426  i += 1
427 
428  # calculating the angle and moving to proper configuration
430  q_map_end = q_map_rORl(rightORleft, alfa)
431  move_jnt_imp(q_map_end, 8.0)
432 
433  # procedure of putting down the object
434  switch2cart_imp_mode(rightORleft, 1.0)
435  tool2grip_pose(rightORleft)
436  T_Wo_grip = get_tf_rORl(rightORleft)
437 
438  print("Moving gripper to object's destination")
439  # do wpisania --------------------------------------------------------
440  T_B_Trd = PyKDL.Frame(T_Wo_grip.M, T_Wo_obj1_pos + PyKDL.Vector(0.0, 0.0, 0.01))
441  move_cart_imp(rightORleft, T_B_Trd, imp_list, pt_val, 12.0)
442  #switch_weight_compensation(rightORleft, False, imp_list, pt_val)
443 
444  # opening gripper
446  [time, q_actual] = velma.getLastJointState()
447  velma.setGraspedFlag(rightORleft, False)
448  move_jnt_imp(q_actual, 2.0)
449  closeORopen_gripper(rightORleft, dest_qOpened)
450  print("Velma's", rightORleft, "gripper opened")
451 
452  # moving gripper up
453  switch2cart_imp_mode(rightORleft, 1.0)
454  tool2grip_pose(rightORleft)
455  print("Moving", rightORleft, "gripper up...")
456 
457  # do wpisania --------------------------------------------------------
458  T_B_Trd = PyKDL.Frame(T_Wo_grip.M, T_Wo_obj1_pos + PyKDL.Vector(0.0, 0.0, 0.4))
459  move_cart_imp(rightORleft, T_B_Trd, imp_list, pt_val, 8.0)
460 
461  # closing gripper
463  closeORopen_gripper(rightORleft, dest_qClosed)
464  print("Velma's", rightORleft, "gripper closed")
465 
466  # moving to start position
467  move_jnt_imp(q_map_1, 4.0)
468  move_jnt_imp(q_map_0, 8.0)
469  move_jnt_imp(q_map_starting, 4.0)
470 
471  # opening grippers
472  # closeORopen_gripper("right", dest_qOpened)
473  # print("Right gripper opened")
474  # closeORopen_gripper("left", dest_qOpened)
475  # print("Left gripper opened")
476 
477  rospy.sleep(0.5)
478 
479  exitError(0)
def isHandConfigurationClose(current_q, dest_q, tolerance=0.1)
Check if two configurations of robot hand are close within tolerance.
def switch_weight_compensation(rightORleft, GRAV_OBJ_COMP, imp_list, pt_val)
def move_cart_imp(rORl, T_frame, imp_list, pt_val, time)
def identification_movements(rightORleft, imp_list, pt_val, dest_qGrasped, dest_qOpened, T_B_Trd, T_B_Trd_Identif1, T_B_Trd_Identif2)