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 Panda (ERobot ):
@@ -28,29 +29,31 @@ class Panda(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/panda_arm_hand.urdf.xacro" )
36
+ "franka_description/robots/panda_arm_hand.urdf.xacro"
37
+ )
35
38
36
39
super ().__init__ (
37
<
F192
/td>- links ,
38
- name = name ,
39
- manufacturer = 'Franka Emika' ,
40
- gripper_links = links [9 ]
40
+ links , name = name , manufacturer = "Franka Emika" , gripper_links = links [9 ]
41
+ )
42
+
43
+ self .grippers [0 ].tool = SE3 (0 , 0 , 0.1034 )
44
+
45
+ self .qdlim = np .array (
46
+ [2.1750 , 2.1750 , 2.1750 , 2.1750 , 2.6100 , 2.6100 , 2.6100 , 3.0 , 3.0 ]
41
47
)
42
48
43
- self .qdlim = np .array ([
44
- 2.1750 , 2.1750 , 2.1750 , 2.1750 , 2.6100 , 2.6100 , 2.6100 , 3.0 , 3.0 ])
49
+ self .addconfiguration ("qz" , np .array ([0 , 0 , 0 , 0 , 0 , 0 , 0 ]))
45
50
46
- self .addconfiguration ("qz" , np .array (
47
- [0 , 0 , 0 , 0 , 0 , 0 , 0 ]))
51
+ self .addconfiguration ("qr" , np .array ([0 , - 0.3 , 0 , - 2.2 , 0 , 2.0 , np .pi / 4 ]))
48
52
49
- self .addconfiguration ("qr" , np .array (
50
- [0 , - 0.3 , 0 , - 2.2 , 0 , 2.0 , np .pi / 4 ]))
51
53
54
+ if __name__ == "__main__" : # pragma nocover
52
55
53
- if __name__ == '__main__' : # pragma nocover
56
+ r = Panda ()
54
57
55
- robot = Panda ()
56
- print (robot )
58
+ for link in r . grippers [ 0 ]. links :
59
+ print (link )
0 commit comments