This commit is contained in:
Max Hunt 2020-02-12 23:48:05 +00:00
parent d1c78d2e3a
commit e49f035927

View File

@ -266,9 +266,9 @@ if __name__ == "__main__":
left_pick = otc.tf_lookup('a1') 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]) 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(-90) xangle = left_pick_angles[0]# + radians(-90)
xangle1 = left_pick_angles[1] + radians(-90) xangle1 = left_pick_angles[1] + radians(-90)
xangle2 = left_pick_angles[2] + radians(-180) xangle2 = left_pick_angles[2]# + radians(-180)
left_pick_angles = (xangle, left_pick_angles[1], left_pick_angles[2]) 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]) target_quat = quaternion_from_euler(left_pick_angles[0], left_pick_angles[1], left_pick_angles[2])
left_pick_proc = Pose() left_pick_proc = Pose()
@ -286,8 +286,8 @@ if __name__ == "__main__":
left_place = otc.tf_lookup('f2') 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]) 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] xangle = left_place_angles[0]+ radians(90)
xangle1 = left_place_angles[1]+ radians(90) xangle1 = left_place_angles[1]
xangle2 = left_place_angles[2] xangle2 = left_place_angles[2]
left_place_angles = (xangle, left_place_angles[1], left_place_angles[2]) 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]) target_quat = quaternion_from_euler(left_place_angles[0], left_place_angles[1], left_pick_angles[2])