-
Notifications
You must be signed in to change notification settings - Fork 3
/
test_abb_4600_voxel1.urdf
169 lines (169 loc) · 5.91 KB
/
test_abb_4600_voxel1.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
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from urdf/irb4600_60_205.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="abb_irb4600_60_205">
<link name="base_link">
<collision name="collision">
<geometry>
<mesh filename="package://abb_irb4600_support/meshes/irb4600_60_205/collision/base_link.stl"/>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box size="0.7 0.7 0.2"/>
<!-- <mesh filename="package://abb_irb4600_support/meshes/irb4600_60_205/visual/base_link.stl"/> -->
</geometry>
<material name="yellow">
<color rgba="1 1 0 1"/>
</material>
</visual>
</link>
<link name="link_1">
<collision name="collision">
<geometry>
<mesh filename="package://abb_irb4600_support/meshes/irb4600_60_205/collision/link_1.stl"/>
</geometry>
</collision>
<visual name="visual">
<geometry>
<!-- <cylinder length="0.25" radius="0.08"/> -->
<!-- <box size="0.3 0.3 0.4"/> -->
<mesh filename="package://abb_irb4600_support/meshes/irb4600_60_205/visual/link_1.stl"/>
</geometry>
<origin xyz="0 0 -0.25" rpy="0 0 0"/>
<material name="yellow"/>
</visual>
</link>
<link name="link_2">
<collision name="collision">
<geometry>
<mesh filename="package://abb_irb4600_support/meshes/irb4600_60_205/collision/link_2.stl"/>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder length="1" radius="0.1"/>
<!-- <mesh filename="package://abb_irb4600_support/meshes/irb4600_60_205/visual/link_2.stl"/> -->
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="yellow"/>
</visual>
</link>
<link name="link_3">
<collision name="collision">
<geometry>
<mesh filename="package://abb_irb4600_support/meshes/irb4600_60_205/collision/link_3.stl"/>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder length="0.4" radius="0.08"/>
<!-- <mesh filename="package://abb_irb4600_support/meshes/irb4600_60_205/visual/link_3.stl"/> -->
</geometry>
<origin xyz="0 0 -0.2" rpy="0 0 0"/>
<material name="yellow"/>
</visual>
</link>
<link name="link_4">
<collision name="collision">
<geometry>
<mesh filename="package://abb_irb4600_support/meshes/irb4600_60_205/collision/link_4.stl"/>
</geometry>
</collision>
<visual name="visual">
<geometry>
<!-- <cylinder length="0.7" radius="0.08"/> -->
<box size="1.05 0.2 0.35"/>
<!-- <mesh filename="package://abb_irb4600_support/meshes/irb4600_60_205/visual/link_4.stl"/> -->
</geometry>
<origin xyz="0.4 0 0" rpy="0 0 0"/>
<material name="yellow"/>
</visual>
</link>
<link name="link_5">
<collision name="collision">
<geometry>
<mesh filename="package://abb_irb4600_support/meshes/irb4600_60_205/collision/link_5.stl"/>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder length="0.15" radius="0.08"/>
<!-- <mesh filename="package://abb_irb4600_support/meshes/irb4600_60_205/visual/link_5.stl"/> -->
</geometry>
<material name="yellow"/>
</visual>
</link>
<link name="link_6">
<collision name="collision">
<geometry>
<mesh filename="package://abb_irb4600_support/meshes/irb4600_60_205/collision/link_6.stl"/>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder length="0.12" radius="0.08"/>
<!-- <mesh filename="package://abb_irb4600_support/meshes/irb4600_60_205/visual/link_6.stl"/> -->
</geometry>
<material name="yellow"/>
</visual>
</link>
<link name="tool0"/>
<joint type="revolute" name="joint_1">
<origin xyz="0 0 0.495" rpy="0 0 0"/>
<!-- <origin xyz="0 0 0.595" rpy="0 0 0"/> -->
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="link_1"/>
<limit effort="0" lower="-3.141" upper="3.141" velocity="3.054"/>
</joint>
<joint type="revolute" name="joint_2">
<origin xyz="0.175 0 0" rpy="0 0 0"/>
<!-- <origin xyz="0.275 0 0" rpy="0 0 0"/> -->
<axis xyz="0 1 0"/>
<parent link="link_1"/>
<child link="link_2"/>
<limit effort="0" lower="-1.570" upper="2.617" velocity="3.054"/>
</joint>
<joint type="revolute" name="joint_3">
<origin xyz="0 0 0.9" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<parent link="link_2"/>
<child link="link_3"/>
<limit effort="0" lower="-3.141" upper="1.308" velocity="3.054"/>
</joint>
<joint type="revolute" name="joint_4">
<origin xyz="0 0 0.175" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
<parent link="link_3"/>
<child link="link_4"/>
<limit effort="0" lower="-6.981" upper="6.981" velocity="4.363"/>
</joint>
<joint type="revolute" name="joint_5">
<origin xyz="0.960 0 0 " rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<parent link="link_4"/>
<child link="link_5"/>
<limit effort="0" lower="-2.181" upper="2.094" velocity="4.363"/>
</joint>
<joint type="revolute" name="joint_6">
<origin xyz="0.135 0 0 " rpy="0 0 0"/>
<axis xyz="1 0 0"/>
<parent link="link_5"/>
<child link="link_6"/>
<limit effort="0" lower="-6.981" upper="6.981" velocity="6.283"/>
</joint>
<joint type="fixed" name="joint_6-tool0">
<parent link="link_6"/>
<child link="tool0"/>
<origin xyz="0 0 0" rpy="0 1.57079632679 0"/>
</joint>
<link name="base"/>
<joint name="base_link-base" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="base"/>
</joint>
</robot>