-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathKR480R3330MT.urdf
133 lines (130 loc) · 4.04 KB
/
KR480R3330MT.urdf
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
<?xml version="1.0" ?>
<robot name="KUKA KR480 R3330 MT">
<!-- Properties -->
<material name="kuka_gray">
<color rgba="0.4 0.4 0.4 1" />
</material>
<material name="kuka_organge">
<color rgba="0.96 0.65 0.14 1" />
</material>
<!-- link list -->
<link name="base_link">
<visual>
<geometry>
<mesh filename="visual/base_link.stl" material_name="kuka_gray"/>
</geometry>
</visual>
</link>
<link name="link1">
<visual>
<geometry>
<mesh filename="visual/link_1.stl" material_name="kuka_organge"/>
</geometry>
</visual>
</link>
<link name="link2">
<visual>
<geometry>
<mesh filename="visual/link_2.stl" material_name="kuka_organge"/>
</geometry>
</visual>
</link>
<link name="link3">
<visual>
<geometry>
<mesh filename="visual/link_3.stl" material_name="kuka_organge"/>
</geometry>
</visual>
</link>
<link name="link4">
<visual>
<geometry>
<mesh filename="visual/link_4.stl" material_name="kuka_organge"/>
</geometry>
</visual>
</link>
<link name="link5">
<visual>
<geometry>
<mesh filename="visual/link_5.stl" material_name="kuka_organge"/>
</geometry>
</visual>
</link>
<link name="link6">
<visual>
<geometry>
<mesh filename="visual/link_6.stl" material_name="kuka_organge"/>
</geometry>
</visual>
</link>
<link name="ee_link"/>
<!-- end of link list -->
<!-- joint list -->
<joint name="joint1" type="revolute">
<parent link="base_link"/>
<child link="link1"/>
<origin xyz="0 0 0" rpy="0 0 0" />
<axis xyz="0 0 -1" />
<limit lower="-185" upper="185" velocity="45"/>
</joint>
<joint name="joint2" type="revolute">
<parent link="link1"/>
<child link="link2"/>
<origin xyz="0.5 0 1.045" rpy="0 90 0" />
<axis xyz="0 1 0" />
<limit lower="-130" upper="20" velocity="45"/>
</joint>
<joint name="joint3" type="revolute">
<parent link="link2"/>
<child link="link3"/>
<origin xyz="0 0 1.3" rpy="0 -90 0" />
<axis xyz="0 1 0" />
<limit lower="-100" upper="144" velocity="45"/>
</joint>
<joint name="joint4" type="revolute">
<parent link="link3"/>
<child link="link4"/>
<origin xyz="1.525 0 -0.055" rpy="0 0 0" />
<axis xyz="-1 0 0" />
<limit lower="-350" upper="350" velocity="90"/>
</joint>
<joint name="joint5" type="revolute">
<parent link="link4"/>
<child link="link5"/>
<origin xyz="0 0 0" rpy="0 0 0" />
<axis xyz="0 1 0" />
<limit lower="-120" upper="120" velocity="83"/>
</joint>
<joint name="joint6" type="revolute">
<parent link="link5"/>
<child link="link6"/>
<origin xyz="0 0 0" rpy="0 0 0" />
<axis xyz="-1 0 0" />
<limit lower="-350" upper="350" velocity="130"/>
</joint>
<joint name="joint_6_t-tool0" type="fixed">
<origin xyz="0.29 0 0" rpy="0 90 0"/>
<parent link="link6"/>
<child link="ee_link"/>
</joint>
<!-- end of joint list -->
<tcp xyz="0 0 0" rpy="0 0 0"/>
<!-- home positions -->
<home_positions joints="0 -90 90 0 90 0" />
<!-- Ortho-parallel Basis and a Spherical Wrist -->
<opw_parameters>
<c1>1.045</c1>
<c2>1.3</c2>
<c3>1.525</c3>
<c4>0.29</c4>
<a1>0.5</a1>
<a2>0.055</a2>
<b>0</b>
<joint1 sign_correction="-1" offset="0"/>
<joint2 sign_correction="1" offset="-90"/>
<joint3 sign_correction="1" offset="0"/>
<joint4 sign_correction="-1" offset="0"/>
<joint5 sign_correction="1" offset="0"/>
<joint6 sign_correction="-1" offset="0"/>
</opw_parameters>
</robot>