Update
This commit is contained in:
parent
a4442fe6b1
commit
a958cb374d
12
main.py
12
main.py
@ -266,9 +266,9 @@ if __name__ == "__main__":
|
||||
left_pick = otc.tf_lookup('a1')
|
||||
|
||||
left_pick_angles = euler_from_quaternion([left_pick.orientation.x , left_pick.orientation.y , left_pick.orientation.z, left_pick.orientation.w])
|
||||
xangle = left_pick_angles[0] + radians(180)
|
||||
xangle1 = left_pick_angles[1] + radians(-90)
|
||||
xangle2 = left_pick_angles[2]
|
||||
xangle = left_pick_angles[0]
|
||||
xangle1 = left_pick_angles[1]
|
||||
xangle2 = left_pick_angles[2] + radians(-90)
|
||||
left_pick_angles = (xangle, left_pick_angles[1], left_pick_angles[2])
|
||||
target_quat = quaternion_from_euler(left_pick_angles[0], left_pick_angles[1], left_pick_angles[2])
|
||||
left_pick_proc = Pose()
|
||||
@ -286,9 +286,9 @@ if __name__ == "__main__":
|
||||
left_place = otc.tf_lookup('f2')
|
||||
|
||||
left_place_angles = euler_from_quaternion([left_place.orientation.x , left_place.orientation.y , left_place.orientation.z, left_place.orientation.w])
|
||||
xangle = left_place_angles[0] + radians(180)
|
||||
xangle1 = left_place_angles[1] + radians(-90)
|
||||
xangle2 = left_place_angles[2] + radians(0)
|
||||
xangle = left_place_angles[0]
|
||||
xangle1 = left_place_angles[1]
|
||||
xangle2 = left_place_angles[2] + radians(90)
|
||||
left_place_angles = (xangle, left_place_angles[1], left_place_angles[2])
|
||||
target_quat = quaternion_from_euler(left_place_angles[0], left_place_angles[1], left_pick_angles[2])
|
||||
left_place_pos = Pose()
|
||||
|
||||
Loading…
Reference in New Issue
Block a user