This commit is contained in:
Max Hunt 2020-03-09 15:31:39 +00:00
parent 39c4054b39
commit 5e5590ce33
2 changed files with 70 additions and 46 deletions

View File

@ -141,7 +141,6 @@ def etq(roll, pitch, yaw): #Euler To Quaternian
qw = np.cos(roll/2) * np.cos(pitch/2) * np.cos(yaw/2) + np.sin(roll/2) * np.sin(pitch/2) * np.sin(yaw/2) qw = np.cos(roll/2) * np.cos(pitch/2) * np.cos(yaw/2) + np.sin(roll/2) * np.sin(pitch/2) * np.sin(yaw/2)
return [qx, qy, qz, qw] return [qx, qy, qz, qw]
def spawn_v_brick(): def spawn_v_brick():
'''Spawns Vertical brick in Gazebo simulation''' '''Spawns Vertical brick in Gazebo simulation'''
brick_pose = Pose() brick_pose = Pose()
@ -191,20 +190,6 @@ def spawn_tables():
spawn_sdf(table1_id, table_sdf, "/", table1, table_reference_frame) spawn_sdf(table1_id, table_sdf, "/", table1, table_reference_frame)
spawn_sdf(table2_id, table_sdf, "/", table2, table_reference_frame) spawn_sdf(table2_id, table_sdf, "/", table2, table_reference_frame)
rospy.init_node("MOTHER_CLUCKER") #Initializes rospy node
if simulation:
#Clean up any (known) preexisting objects in Gazebo and spawns the tables
cleanup()
spawn_tables()
tuck_arms.init_arms() #Makes sure the arms are in known starting place
hover_distance = 0.2 #Used for IK, not useful to us anymore
left_pnp = PickAndPlace('left', hover_distance) #Initializer
def open_and_wait(): def open_and_wait():
'''Opens gripper and waits for uer input to close''' '''Opens gripper and waits for uer input to close'''
left_pnp.gripper_open() left_pnp.gripper_open()
@ -224,7 +209,6 @@ def gripperBrickChecker():
print('Exiting') print('Exiting')
exit(0) exit(0)
def V_Routine(): def V_Routine():
'''Spawns vertical brick (if sim), sends gripper to brick position, asks if ready (if in debug), picks it up and checks that the brick is in the gripper''' '''Spawns vertical brick (if sim), sends gripper to brick position, asks if ready (if in debug), picks it up and checks that the brick is in the gripper'''
if simulation: spawn_v_brick() if simulation: spawn_v_brick()
@ -253,8 +237,21 @@ def H_Routine():
left_pnp.goto(ta.H_approach) left_pnp.goto(ta.H_approach)
rospy.init_node("MOTHER_CLUCKER") #Initializes rospy node
if simulation:
#Clean up any (known) preexisting objects in Gazebo and spawns the tables
cleanup()
spawn_tables()
tuck_arms.init_arms() #Makes sure the arms are in known starting place
left_pnp = PickAndPlace('left', hover_distance) #Limb initializer
left_pnp.gripper_open() #Ensures gripper is open before grabbing brick left_pnp.gripper_open() #Ensures gripper is open before grabbing brick
V_Routine() V_Routine()
left_pnp.goto(ta.B_1_A) left_pnp.goto(ta.B_1_A)

View File

@ -1,28 +1,3 @@
'''
Pickup Vertical Offset :: {'left_w0': 0.309347832698974, 'left_w1': 1.881132793719985, 'left_w2': 2.3018260606950194, 'left_e0': -0.6620952326288202, 'left_e1': 0.8506124094054622, 'left_s0': 0.4467327362087081, 'left_s1': -1.0924293648582206}
Pickup Vertical Pick :: {'left_w0': 0.32998286773274293, 'left_w1': 1.3930185907441222, 'left_w2': 2.2171019702140753, 'left_e0': -0.6821342836475758, 'left_e1': 1.3311146610544962, 'left_s0': 0.5323550070725158, 'left_s1': -1.0404847669613069}
Pickup Horizontal Offset : {'left_w0': 0.8139517749899786, 'left_w1': 1.7913332347783784, 'left_w2': 2.140253332470379, 'left_e0': -1.2881506550429311, 'left_e1': 0.9559160919794364, 'left_s0': 0.718405344706577, 'left_s1': -0.7389057972202023}
Pickup Horizontal Pick : {'left_w0': 0.9011295809085222, 'left_w1': 1.4021253667832847, 'left_w2': 2.0105076391011076, 'left_e0': -1.171667748823461, 'left_e1': 1.2991409722196496, 'left_s0': 0.7750446847107565, 'left_s1': -0.5757716624754514}
Place 1 Offset : {'left_w0': -0.24575885307317663, 'left_w1': 0.8749420307826046, 'left_w2': 1.6948949798814181, 'left_e0': 0.4583130030868797, 'left_e1': 1.8748037298799984, 'left_s0': -1.240546397484759, 'left_s1': -1.1229907414393936}
Place 1 Down : {'left_w0': -0.44706325183614026, 'left_w1': 0.5308931382072065, 'left_w2': 1.8176589482381398, 'left_e0': 0.2909093427758618, 'left_e1': 1.8092679400066711, 'left_s0': -1.1225317078625037, 'left_s1': -0.7034153618455765}
Place 2 Offset : {'left_w0': 1.0334701994763147, 'left_w1': 1.2668145176284678, 'left_w2': 0.9572318887458758, 'left_e0': -1.3409238316370244, 'left_e1': 1.7778524701894391, 'left_s0': 0.2271848446398137, 'left_s1': -0.573105088634528}
Place 2 Down : {'left_w0': 1.2915396241568844, 'left_w1': 0.964866770561432, 'left_w2': 0.8596545556176473, 'left_e0': -0.991322423912265, 'left_e1': 1.7633745271360939, 'left_s0': 0.07709549283393327, 'left_s1': -0.33774783820639565}
Place 3 Offset : {'left_w0': 0.803725300735474, 'left_w1': 1.194163188977739, 'left_w2': 1.4667013915694584, 'left_e0': -1.0771478530987262, 'left_e1': 1.58481527249928, 'left_s0': 0.3549391390860414, 'left_s1': -0.7083016536375286}
Place 3 Down : {'left_w0': 1.0094440753014968, 'left_w1': 0.8974942275422987, 'left_w2': 1.3801020782459945, 'left_e0': -0.8128594434709138, 'left_e1': 1.56853086901738, 'left_s0': 0.2186545601611162, 'left_s1': -0.4267459808731298}
Place 4 Offset : {'left_w0': 0.1671234856733194, 'left_w1': 0.8261944766180188, 'left_w2': 1.379487069256468, 'left_e0': -0.28247213805949767, 'left_e1': 1.8837252545953784, 'left_s0': -0.607713162458475, 'left_s1': -1.1163951963030918}
Place 4 Down : {'left_w0': 0.24419474317602866, 'left_w1': 0.6290231193065527, 'left_w2': 1.326407292573995, 'left_e0': -0.23303382594081024, 'left_e1': 1.8771117428607849, 'left_s0': -0.6460371665357855, 'left_s1': -0.9078139028116797}
Place 5 Offset : {'left_w0': 0.6984403275545308, 'left_w1': 1.2544926841081905, 'left_w2': 1.3544614580142273, 'left_e0': -1.1745832201258934, 'left_e1': 1.6458210205020332, 'left_s0': 0.31526732584172107, 'left_s1': -0.8464672073407838}
Place 5 Down : {'left_w0': 0.9437250579116295, 'left_w1': 0.9167077216413124, 'left_w2': 1.222379447910923, 'left_e0': -0.879490332019234, 'left_e1': 1.7294606327190576, 'left_s0': 0.15746537974463826, 'left_s1': -0.5907485424149368}
Place 6 Offset : {'left_w0': 0.13795791158290516, 'left_w1': 1.4976647271381562, 'left_w2': 1.3716861361389447, 'left_e0': -0.7668644025351493, 'left_e1': 1.5004594439971868, 'left_s0': -0.21720089382963984, 'left_s1': -1.3717982666530235}
Place 6 Down : {'left_w0': 0.30567556734697016, 'left_w1': 1.0253204952492578, 'left_w2': 1.2509852844361058, 'left_e0': -0.6998909977260979, 'left_e1': 1.8157485803507927, 'left_s0': -0.2856819912424196, 'left_s1': -1.1598950455287043}
Place 7 Offset : {'left_w0': 0.2880633344490283, 'left_w1': 1.586029171376809, 'left_w2': 1.618882284053745, 'left_e0': -0.9484107003286485, 'left_e1': 1.3454477156124263, 'left_s0': 0.1821213719091443, 'left_s1': -1.2157353154435486}
Place 7 Down : {'left_w0': 0.42723819133965163, 'left_w1': 1.1318459412158908, 'left_w2': 1.5190079397734162, 'left_e0': -0.8526717542593604, 'left_e1': 1.6855962489232676, 'left_s0': 0.13537792888171907, 'left_s1': -1.049425917711375}
Place 8 Offset : {'left_w0': 0.47397216515126994, 'left_w1': 1.8191693493757988, 'left_w2': 1.3505030133400355, 'left_e0': -1.2629306563238563, 'left_e1': 1.135600354775232, 'left_s0': 0.09497817386676323, 'left_s1': -1.0891358446984596}
Place 8 Down : {'left_w0': 0.47397216515126994, 'left_w1': 1.8191693493757988, 'left_w2': 1.3505030133400355, 'left_e0': -1.2629306563238563, 'left_e1': 1.135600354775232, 'left_s0': 0.09497817386676323, 'left_s1': -1.0891358446984596}
Place 9 Offset : {'left_w0': 0.35959165932558207, 'left_w1': 1.9280499585601125, 'left_w2': 1.4753075963656614, 'left_e0': -1.014625396487737, 'left_e1': 0.9725959751301161, 'left_s0': -0.03418343328074433, 'left_s1': -1.1722171342836722}
Place 9 Down : {'left_w0': 0.31592446450227823, 'left_w1': 1.7694573442805632, 'left_w2': 1.4526326487219683, 'left_e0': -1.0428825978748242, 'left_e1': 1.1732291351006587, 'left_s0': 0.05048765124424395, 'left_s1': -1.2037991885581427}
'''
V_approach = {'left_w0': 0.309347832698974, 'left_w1': 1.881132793719985, 'left_w2': 2.3018260606950194, 'left_e0': -0.6620952326288202, 'left_e1': 0.8506124094054622, 'left_s0': 0.4467327362087081, 'left_s1': -1.0924293648582206} V_approach = {'left_w0': 0.309347832698974, 'left_w1': 1.881132793719985, 'left_w2': 2.3018260606950194, 'left_e0': -0.6620952326288202, 'left_e1': 0.8506124094054622, 'left_s0': 0.4467327362087081, 'left_s1': -1.0924293648582206}
V_pickup = {'left_w0': 0.4649854934058153, 'left_w1': 1.4526645466391497, 'left_w2': 2.138194707013768, 'left_e0': -0.89929386139053, 'left_e1': 1.2965189348212542, 'left_s0': 0.6436312256143302, 'left_s1': -0.9657905946725601} V_pickup = {'left_w0': 0.4649854934058153, 'left_w1': 1.4526645466391497, 'left_w2': 2.138194707013768, 'left_e0': -0.89929386139053, 'left_e1': 1.2965189348212542, 'left_s0': 0.6436312256143302, 'left_s1': -0.9657905946725601}
H_approach = {'left_w0': 0.8139517749899786, 'left_w1': 1.7913332347783784, 'left_w2': 2.140253332470379, 'left_e0': -1.2881506550429311, 'left_e1': 0.9559160919794364, 'left_s0': 0.718405344706577, 'left_s1': -0.7389057972202023} H_approach = {'left_w0': 0.8139517749899786, 'left_w1': 1.7913332347783784, 'left_w2': 2.140253332470379, 'left_e0': -1.2881506550429311, 'left_e1': 0.9559160919794364, 'left_s0': 0.718405344706577, 'left_s1': -0.7389057972202023}
@ -47,8 +22,60 @@ B_9_A = {'left_w0': 0.35959165932558207, 'left_w1': 1.9280499585601125, 'left_w2
B_9_P = {'left_w0': 0.31592446450227823, 'left_w1': 1.7694573442805632, 'left_w2': 1.4526326487219683, 'left_e0': -1.0428825978748242, 'left_e1': 1.1732291351006587, 'left_s0': 0.05048765124424395, 'left_s1': -1.2037991885581427} B_9_P = {'left_w0': 0.31592446450227823, 'left_w1': 1.7694573442805632, 'left_w2': 1.4526326487219683, 'left_e0': -1.0428825978748242, 'left_e1': 1.1732291351006587, 'left_s0': 0.05048765124424395, 'left_s1': -1.2037991885581427}
B_9_za = {'left_w0': 0.4224716898888107, 'left_w1': 2.0940001010894775, 'left_w2': 1.5055377828561145, 'left_e0': -0.9718054278924021, 'left_e1': 0.7415823040245637, 'left_s0': -0.1466335135058824, 'left_s1': -1.1271627193043057} B_9_za = {'left_w0': 0.4224716898888107, 'left_w1': 2.0940001010894775, 'left_w2': 1.5055377828561145, 'left_e0': -0.9718054278924021, 'left_e1': 0.7415823040245637, 'left_s0': -0.1466335135058824, 'left_s1': -1.1271627193043057}
B_9_zb = {'left_w0': 0.4347300274764977, 'left_w1': 2.0940001010894775, 'left_w2': 1.6022059702674842, 'left_e0': -0.9568544450910222, 'left_e1': 0.7236685435274075, 'left_s0': -0.07853688979435548, 'left_s1': -1.1083415625783348} B_9_zb = {'left_w0': 0.4347300274764977, 'left_w1': 2.0940001010894775, 'left_w2': 1.6022059702674842, 'left_e0': -0.9568544450910222, 'left_e1': 0.7236685435274075, 'left_s0': -0.07853688979435548, 'left_s1': -1.1083415625783348}
# vpk = {'left_w0': 0.4649854934058153, 'left_w1': 1.4526645466391497, 'left_w2': 2.138194707013768, 'left_e0': -0.89929386139053, 'left_e1': 1.2965189348212542, 'left_s0': 0.6436312256143302, 'left_s1': -0.9657905946725601}
# hpk = {'left_w0': 0.3769936175655104, 'left_w1': 1.2305944969345881, 'left_w2': 2.2665093979599353, 'left_e0': -0.5773304857037607, 'left_e1': 1.340754726206522, 'left_s0': 0.5061440970662591, 'left_s1': -0.8921470049131158} instructions = [
# 1pl = {'left_w0': 1.2027300003884847, 'left_w1': 0.8795510297892881, 'left_w2': 0.5632980390463863, 'left_e0': -0.8960386873043342, 'left_e1': 1.7558376775390683, 'left_s0': -0.31400273801416234, 'left_s1': -0.4013131412149057} {
# 3pl = {'left_w0': 1.1424562096018538, 'left_w1': 0.995761483224297, 'left_w2': 1.3813210747199685, 'left_e0': -0.9434785814973881, 'left_e1': 1.5257241802006776, 'left_s0': 0.30682480243089416, 'left_s1': -0.3342487874061004} 'step':1,
# 8pl = {'left_w0': 0.8110423768060999, 'left_w1': 1.472609531372465, 'left_w2': 1.1138183782919966, 'left_e0': -1.4329588050987652, 'left_e1': 1.5676992726056054, 'left_s0': 0.23139732100304755, 'left_s1': -0.7547923372600823} 'hover':B_1_A,
'pick':B_1_P,
'vertical':True
},
{
'step':2,
'hover':B_2_A,
'pick':B_2_P,
'vertical':True
},
{
'step':3,
'hover':B_3_A,
'pick':B_3_P,
'vertical':True
},
{
'step':4,
'hover':B_4_A,
'pick':B_4_P,
'vertical':False
},
{
'step':5,
'hover':B_5_A,
'pick':B_5_P,
'vertical':False
},
{
'step':6,
'hover':B_6_A,
'pick':B_6_P,
'vertical':True
},
{
'step':7,
'hover':B_7_A,
'pick':B_7_P,
'vertical':True
},
{
'step':8,
'hover':B_8_A,
'pick':B_8_P,
'vertical':False
},
{
'step':9,
'hover':B_9_A,
'pick':B_9_P,
'vertical':True
}
]