2 from __future__
import print_function
3 from __future__
import division
5 import roslib; roslib.load_manifest(
'velma_task_cs_ros_interface')
10 from velma_common
import *
11 from rcprg_ros_utils
import exitError
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()
19 print(
"The action should have ended without error, but the error code is", error)
24 print(
"Switch to cart_imp mode (no trajectory)...")
26 if not velma.moveCartImpRightCurrentPos(start_time=0.5):
28 if velma.waitForEffectorRight(timeout_s=timeout) != 0:
30 elif (rORl ==
"left"):
31 if not velma.moveCartImpLeftCurrentPos(start_time=0.5):
33 if velma.waitForEffectorLeft(timeout_s=timeout) != 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")
43 print(
"Switch to jnt_imp mode (no trajectory)...")
44 velma.moveJointImpToCurrentPos(start_time=0.5)
45 error = velma.waitForJoint()
47 print(
"The action should have ended without error, but the error code is", error)
50 diag = velma.getCoreCsDiag()
51 if not diag.inStateJntImp():
52 print(
"The core_cs should be in jnt_imp state, but it is not")
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:
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:
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):
81 if velma.waitForEffectorRight() != 0:
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):
90 if velma.waitForEffectorLeft() != 0:
92 print(
"The left tool is now in 'grip' pose")
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))
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):
103 if velma.waitForEffectorRight() != 0:
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):
109 if velma.waitForEffectorLeft() != 0:
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))
116 print(
"*** start of identification procedure ***")
117 move_cart_imp(rightORleft, T_B_Trd, imp_list_id, pt_val, 8.0)
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)
126 print(
"Velma's", rightORleft,
"gripper opened")
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)
137 velma.sendIdentificationMeasurementCommand(rightORleft, 1)
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)
142 velma.sendIdentificationMeasurementCommand(rightORleft, 2)
144 move_cart_imp(rightORleft, T_B_Trd_Identif1, imp_list_id, pt_val, 8.0)
149 print(
"Velma's", rightORleft,
"gripper opened")
154 print(
"Moving gripper to pose before grasping object...")
155 move_cart_imp(rightORleft, T_B_Trd, imp_list_id, pt_val, 8.0)
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)
166 velma.sendIdentificationMeasurementCommand(rightORleft, 3)
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)
171 velma.sendIdentificationMeasurementCommand(rightORleft, 4)
173 move_cart_imp(rightORleft, T_B_Trd_Identif1, imp_list, pt_val, 8.0)
174 print(
"*** end of identification procedure ***")
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)
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)
193 if (rORl ==
"right"):
194 T_Wo_grip = velma.getTf(
"Wo",
"Gr")
195 elif (rORl ==
"left"):
196 T_Wo_grip = velma.getTf(
"Wo",
"Gl")
200 if (rORl ==
"right"):
202 print(
"Object not grabbed")
205 print(
"Right gripper grabbed the object")
206 elif (rORl ==
"left"):
208 print(
"Object not grabbed")
211 print(
"Left gripper grabbed the object")
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 }
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 }
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 }
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 }
258 if __name__ ==
"__main__":
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 }
270 rospy.init_node(
'object_control_test')
274 rightORleft =
'right' 284 print(
"Chosen gripper:", rightORleft)
285 print(
"CART_TEST:", CART_TEST)
286 print(
"GRAV_OBJ_COMP:", GRAV_OBJ_COMP)
289 imp_list = PyKDL.Wrench(PyKDL.Vector(500, 500, 500), PyKDL.Vector(100, 100, 100))
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]
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")
304 print(
"Initialization ok!")
311 diag = velma.getCoreCsDiag()
312 if not diag.motorsReady():
313 print(
"Motors must be homed and ready to use for this test.")
316 if velma.enableMotors() != 0:
320 velma.setGraspedFlag(
'right',
False)
321 velma.setGraspedFlag(
'left',
False)
326 print(
"Right gripper closed")
328 print(
"Left gripper closed")
340 print(
"Velma's", rightORleft,
"gripper opened")
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):
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):
352 if velma.waitForEffectorRight() != 0:
354 if velma.waitForEffectorLeft() != 0:
362 if(rightORleft ==
'right'):
363 T_Wo_obj1_pos = PyKDL.Vector(0.8, -0.17, 1.1)
364 elif(rightORleft ==
'left'):
365 T_Wo_obj1_pos = PyKDL.Vector(0.8, 0.17, 1.1)
367 T_B_Trd = PyKDL.Frame(T_Wo_grip.M, T_Wo_obj1_pos + PyKDL.Vector(0.0, 0.0, 0.0))
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))
379 identification_movements(rightORleft, imp_list, pt_val, dest_qGrasped, dest_qOpened, T_B_Trd, T_B_Trd_Identif1, T_B_Trd_Identif2)
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))
389 if(CART_TEST ==
True):
394 if(rightORleft ==
'right'):
398 elif(rightORleft ==
'left'):
400 quat_z = math.sin(math.pi/2)
401 quat_w = math.cos(math.pi/2)
403 print(
"rightORleft and pm problem...")
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))
438 print(
"Moving gripper to object's destination")
440 T_B_Trd = PyKDL.Frame(T_Wo_grip.M, T_Wo_obj1_pos + PyKDL.Vector(0.0, 0.0, 0.01))
446 [time, q_actual] = velma.getLastJointState()
447 velma.setGraspedFlag(rightORleft,
False)
450 print(
"Velma's", rightORleft,
"gripper opened")
455 print(
"Moving", rightORleft,
"gripper up...")
458 T_B_Trd = PyKDL.Frame(T_Wo_grip.M, T_Wo_obj1_pos + PyKDL.Vector(0.0, 0.0, 0.4))
464 print(
"Velma's", rightORleft,
"gripper closed")
def isHandConfigClose_rORl(rORl)
def switch2jnt_imp_mode()
def closeORopen_gripper(rORl, dest_q)
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)
def move_jnt_imp(q_dest, time)
def switch2cart_imp_mode(rORl, timeout)
def diff_calc(rORl, T_frame)
def q_map_rORl(rORl, torso_angle)