2
2
3
3
import numpy as np
4
4
from roboticstoolbox .robot .ERobot import ERobot
5
+ from spatialmath import SE3
5
6
6
7
7
8
class Frankie (ERobot ):
@@ -28,31 +29,43 @@ class Frankie(ERobot):
28
29
.. codeauthor:: Jesse Haviland
29
30
.. sectionauthor:: Peter Corke
30
31
"""
32
+
31
33
def __init__ (self ):
32
34
33
35
links , name = self .URDF_read (
34
- "franka_description/robots/frankie_arm_hand.urdf.xacro" )
36
+ "franka_description/robots/frankie_arm_hand.urdf.xacro"
37
+ )
35
38
36
39
super ().__init__ (
37
- links ,
38
- name = name ,
39
- manufacturer = 'Franka Emika' ,
40
- gripper_links = links [11 ]
40
+ links , name = name , manufacturer = "Franka Emika" , gripper_links = links [11 ]
41
41
)
42
42
43
- self .qdlim = np .array ([
44
- 4.0 , 4.0 ,
45
- 2.1750 , 2.1750 , 2.1750 , 2.1750 , 2.6100 , 2.6100 , 2.6100 ,
46
- 3.0 , 3.0 ])
43
+ self .grippers [0 ].tool = SE3 (0 , 0 , 0.1034 )
44
+
45
+ self .qdlim = np .array (
46
+ [4.0 , 4.0 , 2.1750 , 2.1750 , 2.1750 , 2.1750 , 2.6100 , 2.6100 , 2.6100 , 3.0 , 3.0 ]
47
+ )
47
48
48
- self .addconfiguration ("qz" , np .array (
49
- [0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 ]))
49
+ self .addconfiguration ("qz" , np .array ([0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 ]))
50
50
51
- self .addconfiguration ("qr" , np .array (
52
- [0 , 0 , 0 , - 0.3 , 0 , - 2.2 , 0 , 2.0 , np .pi / 4 ]))
51
+ self .addconfiguration (
52
+ "qr" , np .array ([0 , 0 , 0 , - 0.3 , 0 , - 2.2 , 0 , 2.0 , np .pi / 4 ])
53
+ )
53
54
54
55
55
- if __name__ == ' __main__' : # pragma nocover
56
+ if __name__ == " __main__" : # pragma nocover
56
57
57
58
robot = Frankie ()
58
59
print (robot )
60
+
61
+ for link in robot .links :
62
+ print (link .name )
63
+ print (link .isjoint )
64
+ print (len (link .collision ))
65
+
66
+ print ()
67
+
68
+ for link in robot .grippers [0 ].links :
69
+ print (link .name )
70
+ print (link .isjoint )
71
+ print (len (link .collision ))
0 commit comments