This commit is contained in:
Max Hunt 2020-02-13 10:04:55 +00:00
parent 53277e5e9c
commit 609b5aada2
2 changed files with 4 additions and 4 deletions

View File

@ -269,12 +269,12 @@ if __name__ == "__main__":
print(left_pick) print(left_pick)
print() print()
print() print()
left_pick.position.z+=0.5 # left_pick.position.z+=0.5
left_pnp.pick(left_pick) left_pnp.pick(left_pick)
left_place = otc.tf_lookup('f2') left_place = otc.tf_lookup('f2')
left_pick.position.z+=0.5 # left_pick.position.z+=0.5
left_pnp.place(left_place) left_pnp.place(left_place)

View File

@ -19,9 +19,9 @@ def tf_lookup(object_name):
continue continue
object_angles = tf.transformations.euler_from_quaternion([rot[0] , rot[1] , rot[2], rot[3]]) object_angles = tf.transformations.euler_from_quaternion([rot[0] , rot[1] , rot[2], rot[3]])
xangle = object_angles[0] + radians(-90) xangle = object_angles[0]# + radians(-90)
xangle1 = object_angles[1]# + radians(-90) xangle1 = object_angles[1]# + radians(-90)
xangle2 = object_angles[2] + radians(-180) xangle2 = object_angles[2]# + radians(-180)
object_angles = (xangle, xangle1, xangle2) object_angles = (xangle, xangle1, xangle2)
target_quat = tf.transformations.quaternion_from_euler(xangle, xangle1, xangle2) target_quat = tf.transformations.quaternion_from_euler(xangle, xangle1, xangle2)
target_pose = Pose() target_pose = Pose()