-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathm710ic45m.urdf
192 lines (191 loc) · 6.44 KB
/
m710ic45m.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
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from urdf/m710ic45m.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="fanuc_m710ic45m">
<!-- links: main serial chain -->
<link name="base_link">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m710ic_support/meshes/m710ic50/visual/base_link.stl"/>
</geometry>
<material name="">
<color rgba="0.15 0.15 0.15 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m710ic_support/meshes/m710ic50/collision/base_link.stl"/>
</geometry>
</collision>
</link>
<link name="link_1">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m710ic_support/meshes/m710ic50/visual/link_1.stl"/>
</geometry>
<material name="">
<color rgba="0.96 0.76 0.13 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m710ic_support/meshes/m710ic50/collision/link_1.stl"/>
</geometry>
</collision>
</link>
<link name="link_2">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m710ic_support/meshes/m710ic45m/visual/link_2.stl"/>
</geometry>
<material name="">
<color rgba="0.96 0.76 0.13 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m710ic_support/meshes/m710ic45m/collision/link_2.stl"/>
</geometry>
</collision>
</link>
<link name="link_3">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m710ic_support/meshes/m710ic50/visual/link_3.stl"/>
</geometry>
<material name="">
<color rgba="0.96 0.76 0.13 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m710ic_support/meshes/m710ic50/collision/link_3.stl"/>
</geometry>
</collision>
</link>
<link name="link_4">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m710ic_support/meshes/m710ic45m/visual/link_4.stl"/>
</geometry>
<material name="">
<color rgba="0.96 0.76 0.13 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m710ic_support/meshes/m710ic45m/collision/link_4.stl"/>
</geometry>
</collision>
</link>
<link name="link_5">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m710ic_support/meshes/m710ic50/visual/link_5.stl"/>
</geometry>
<material name="">
<color rgba="0.96 0.76 0.13 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m710ic_support/meshes/m710ic50/collision/link_5.stl"/>
</geometry>
</collision>
</link>
<link name="link_6">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m710ic_support/meshes/m710ic50/visual/link_6.stl"/>
</geometry>
<material name="">
<color rgba="0.15 0.15 0.15 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m710ic_support/meshes/m710ic50/collision/link_6.stl"/>
</geometry>
</collision>
</link>
<!-- joints: main serial chain -->
<joint name="joint_1" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.565"/>
<parent link="base_link"/>
<child link="link_1"/>
<axis xyz="0 0 1"/>
<limit effort="0" lower="-3.141592653589793" upper="3.141592653589793" velocity="3.141592653589793"/>
</joint>
<joint name="joint_2" type="revolute">
<origin rpy="0 0 0" xyz="0.150 0 0"/>
<parent link="link_1"/>
<child link="link_2"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="-1.5707963267948966" upper="2.356194490192345" velocity="3.141592653589793"/>
</joint>
<joint name="joint_3" type="revolute">
<origin rpy="0 0 0" xyz="0 0 1.150"/>
<parent link="link_2"/>
<child link="link_3"/>
<axis xyz="0 -1 0"/>
<limit effort="0" lower="-2.792526803190927" upper="4.886921905584122" velocity="3.141592653589793"/>
</joint>
<joint name="joint_4" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.170"/>
<parent link="link_3"/>
<child link="link_4"/>
<axis xyz="-1 0 0"/>
<limit effort="0" lower="-6.981317007977318" upper="6.981317007977318" velocity="4.363323129985824"/>
</joint>
<joint name="joint_5" type="revolute">
<origin rpy="0 0 0" xyz="1.295 0 0"/>
<parent link="link_4"/>
<child link="link_5"/>
<axis xyz="0 -1 0"/>
<limit effort="0" lower="-2.181661564992912" upper="2.181661564992912" velocity="4.363323129985824"/>
</joint>
<joint name="joint_6" type="revolute">
<origin rpy="0 0 0" xyz="0.175 0 0"/>
<parent link="link_5"/>
<child link="link_6"/>
<axis xyz="-1 0 0"/>
<limit effort="0" lower="-6.981317007977318" upper="6.981317007977318" velocity="6.283185307179586"/>
</joint>
<!-- ROS-Industrial 'base' frame: base_link to Fanuc World Coordinates transform -->
<link name="base"/>
<joint name="base_link-base" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.565"/>
<parent link="base_link"/>
<child link="base"/>
</joint>
<!-- ROS-Industrial 'flange' frame: attachment point for EEF models -->
<link name="flange"/>
<joint name="joint_6-flange" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="link_6"/>
<child link="flange"/>
</joint>
<!-- ROS-Industrial 'tool0' frame: all-zeros tool frame -->
<link name="tool0"/>
<joint name="link_6-tool0" type="fixed">
<origin rpy="3.141592653589793 -1.5707963267948966 0" xyz="0 0 0"/>
<parent link="flange"/>
<child link="tool0"/>
</joint>
</robot>