-
Notifications
You must be signed in to change notification settings - Fork 1
/
spatial_3R_robot.urdf
135 lines (110 loc) · 2.8 KB
/
spatial_3R_robot.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
<?xml version="1.0"?>
<robot name="spatial_3R_robot">
<!-- Simple three-axis serial robot -->
<material name="blue">
<color rgba="0 0 0.4 1"/>
</material>
<material name="light_blue">
<color rgba="0.0 0.0 0.9 1"/>
</material>
<material name="red">
<color rgba="0.8 0 0 1"/>
</material>
<!-- world link -->
<link name="world"/>
<!-- base_link and its fixed joint -->
<joint name="rotation0" type="revolute">
<parent link="world"/>
<child link="base_link"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="100" velocity="10" lower="-3.14" upper="3.14"/>
</joint>
<link name="base_link">
<collision>
<origin xyz="0 0 0.2" rpy="0 0 0"/>
<geometry>
<cylinder length="1.0" radius="0.1"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<geometry>
<cylinder length="1.0" radius="0.1"/>
</geometry>
<material name="red" />
</visual>
<inertial>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<mass value="1"/>
<inertia
ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0"/>
</inertial>
</link>
<!-- the first arm of the scara, with revolute joint rotating along z axis -->
<!-- arm length between two rotation axis is 1 -->
<joint name="rotation1" type="revolute">
<parent link="base_link"/>
<child link="arm1"/>
<origin xyz="0 0 1.0" rpy="0 1.57075 0"/>
<axis xyz="0 0 1"/>
<limit effort="100" velocity="10" lower="-3.14" upper="3.14"/>
</joint>
<link name="arm1">
<collision>
<origin xyz="0 -0.5 0.0" rpy="0 0 0"/>
<geometry>
<box size="0.1 1.1 0.1"/>
</geometry>
</collision>
<visual>
<origin xyz="0 -0.5 0.0" rpy="0 0 0"/>
<geometry>
<box size="0.1 1.1 0.1"/>
</geometry>
<material name="blue" />
</visual>
<inertial>
<origin xyz="0 0 0.0" rpy="0 0 0"/>
<mass value="1"/>
<inertia
ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.001"/>
</inertial>
</link>
<!-- the second arm and its rotation joint -->
<!-- arm length between two rotation axis is 0.8 -->
<joint name="rotation2" type="revolute">
<parent link="arm1"/>
<child link="arm2"/>
<origin xyz="0 -1 0.1" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="1000" velocity="1000" lower="-3.00" upper="3.00"/>
</joint>
<link name="arm2">
<collision>
<origin xyz="0 -0.4 0.05" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.9 0.1"/>
</geometry>
</collision>
<visual>
<origin xyz="0 -0.4 0.05" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.9 0.1"/>
</geometry>
<material name="light_blue" />
</visual>
<inertial>
<origin xyz="0 0 0.05" rpy="0 0 0"/>
<mass value="1"/>
<inertia
ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.001"/>
</inertial>
</link>
</robot>