Update
This commit is contained in:
parent
31cce6dcf5
commit
4e434b5845
@ -5,7 +5,7 @@
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''> 0 0 0.0 -0 0</pose>
|
||||
<mass>0.1</mass>
|
||||
<mass>0.001</mass>
|
||||
<inertia>
|
||||
<ixx>0.000002</ixx>
|
||||
<ixy>0</ixy>
|
||||
|
||||
18
new_main.py
18
new_main.py
@ -171,59 +171,77 @@ def H_Routine():
|
||||
|
||||
V_Routine()
|
||||
left_pnp.send(ta.B_1_A)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.send(ta.B_1_P)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.gripper_open()
|
||||
left_pnp.send(ta.B_1_A)
|
||||
|
||||
V_Routine()
|
||||
left_pnp.send(ta.B_2_A)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.send(ta.B_2_P)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.gripper_open()
|
||||
left_pnp.send(ta.B_2_A)
|
||||
|
||||
V_Routine()
|
||||
left_pnp.send(ta.B_3_A)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.send(ta.B_3_P)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.gripper_open()
|
||||
left_pnp.send(ta.B_3_A)
|
||||
|
||||
|
||||
H_Routine()
|
||||
left_pnp.send(ta.B_4_A)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.send(ta.B_4_P)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.gripper_open()
|
||||
left_pnp.send(ta.B_4_A)
|
||||
|
||||
H_Routine()
|
||||
left_pnp.send(ta.B_5_A)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.send(ta.B_5_P)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.gripper_open()
|
||||
left_pnp.send(ta.B_5_A)
|
||||
|
||||
|
||||
V_Routine()
|
||||
left_pnp.send(ta.B_6_A)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.send(ta.B_6_P)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.gripper_open()
|
||||
left_pnp.send(ta.B_6_A)
|
||||
|
||||
V_Routine()
|
||||
left_pnp.send(ta.B_7_A)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.send(ta.B_7_P)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.gripper_open()
|
||||
left_pnp.send(ta.B_7_A)
|
||||
|
||||
|
||||
H_Routine()
|
||||
left_pnp.send(ta.B_8_A)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.send(ta.B_8_P)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.gripper_open()
|
||||
left_pnp.send(ta.B_8_A)
|
||||
|
||||
|
||||
V_Routine()
|
||||
left_pnp.send(ta.B_9_A)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.send(ta.B_9_P)
|
||||
x = raw_input('Continue?: ')
|
||||
left_pnp.gripper_open()
|
||||
left_pnp.send(ta.B_9_A)
|
||||
|
||||
|
||||
Loading…
Reference in New Issue
Block a user