Update
This commit is contained in:
parent
717417aa5c
commit
816d7cd442
@ -292,7 +292,7 @@ bricks_start_v1 =[{
|
|||||||
bricks_start_v2 =[{
|
bricks_start_v2 =[{
|
||||||
'id':'a1',
|
'id':'a1',
|
||||||
'rframe':'t1',
|
'rframe':'t1',
|
||||||
'x':-0.159,
|
'x':-0.059,
|
||||||
'y':0.134,
|
'y':0.134,
|
||||||
'z':0.821,
|
'z':0.821,
|
||||||
'roll':radians(0),
|
'roll':radians(0),
|
||||||
|
|||||||
@ -19,9 +19,9 @@ def tf_lookup(object_name):
|
|||||||
continue
|
continue
|
||||||
|
|
||||||
object_angles = tf.transformations.euler_from_quaternion([rot[3] , rot[0], rot[1], rot[2]], axes='sxyz')
|
object_angles = tf.transformations.euler_from_quaternion([rot[3] , rot[0], rot[1], rot[2]], axes='sxyz')
|
||||||
xangle = object_angles[0] + radians(286)
|
xangle = object_angles[0] + radians(196)
|
||||||
xangle1 = object_angles[1] + radians(90)
|
xangle1 = object_angles[1] + radians(90)
|
||||||
xangle2 = object_angles[2] + radians(-106)
|
xangle2 = object_angles[2] + radians(-196)
|
||||||
object_angles = (xangle, xangle1, xangle2)
|
object_angles = (xangle, xangle1, xangle2)
|
||||||
print("Angles:")
|
print("Angles:")
|
||||||
print(xangle)
|
print(xangle)
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user