-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathfile.urdf
133 lines (133 loc) · 3.57 KB
/
file.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="origins">
<link name="base_link">
<visual>
<geometry>
<cylinder length="0.01" radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.01"/>
</visual>
</link>
<link name="link1">
<visual>
<geometry>
<cylinder length="0.095" radius="0.03"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.045"/>
</visual>
</link>
<joint name="base_link_link1" type="revolute">
<parent link="base_link"/>
<child link="link1"/>
<axis xyz="0 0 1"/>
<limit effort="1000.0" lower="-1.57" upper="1.57" velocity="0.5"/>
<origin rpy="0 0 0" xyz="0 0 0.01"/>
</joint>
<link name="link2">
<visual>
<geometry>
<cylinder length="0.12" radius="0.015"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.075"/>
</visual>
</link>
<joint name="link1_link2" type="revolute">
<parent link="link1"/>
<child link="link2"/>
<origin rpy="0 0 0" xyz="0 0.033 0.095"/>
<limit effort="1000.0" lower="-1" upper="0.785" velocity="0.5"/>
<axis xyz="1 0 0"/>
</joint>
<link name="link3">
<visual>
<geometry>
<box size="0.04 0.06 0.04"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.02"/>
</visual>
</link>
<joint name="link2_link3" type="revolute">
<parent link="link2"/>
<child link="link3"/>
<origin rpy="0 0 0" xyz="0 0 0.12"/>
<limit effort="1000.0" lower="-0.785" upper="0.785" velocity="0.5"/>
<axis xyz="1 0 0"/>
</joint>
<link name="link4">
<visual>
<geometry>
<cylinder length="0.133" radius="0.01"/>
</geometry>
<origin rpy="-1.57 0 0" xyz="0 0.0665 0"/>
</visual>
</link>
<joint name="link3_link4" type="revolute">
<parent link="link3"/>
<child link="link4"/>
<origin rpy="0 0 0" xyz="0 0 0.02"/>
<limit effort="1000.0" lower="-1.57" upper="1.57" velocity="0.5"/>
<axis xyz="0 1 0"/>
</joint>
<link name="link5">
<visual>
<geometry>
<box size="0.04 0.02 0.03"/>
</geometry>
<origin rpy="-1.57 0 0" xyz="0 -0.015 0"/>
</visual>
</link>
<joint name="link4_link5" type="revolute">
<parent link="link4"/>
<child link="link5"/>
<origin rpy="0 0 0" xyz="0 0.133 0"/>
<limit effort="1000.0" lower="-1.57" upper="1.57" velocity="0.5"/>
<axis xyz="0 0 1"/>
</joint>
<link name="link6">
<visual>
<geometry>
<cylinder length="0.005" radius="0.015"/>
</geometry>
<origin rpy="-1.57 0 0" xyz="0 -0.0025 0"/>
</visual>
</link>
<joint name="link5_link6" type="revolute">
<parent link="link5"/>
<child link="link6"/>
<origin rpy="0 0 0" xyz="0 0.03 0"/>
<limit effort="1000.0" lower="-1.57777777" upper="-1.57" velocity="0.5"/>
<axis xyz="0 1 0"/>
</joint>
<!--
<link name="link3">
<visual>
<geometry>
<cylinder length="0.15" radius="0.01"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.075"/>
</visual>
</link>
<joint name="link2_link3" type="revolute">
<parent link="link2"/>
<child link="link3"/>
<origin rpy="0 0 0" xyz="0 0 0.2"/>
<limit effort="1000.0" lower="-2.53" upper="0" velocity="0.5"/>
<axis xyz="1 0 0"/>
<origin rpy="0 0 0" xyz="0 0 0.02"/>
</joint>
<link name="link4">
<visual>
<geometry>
<cylinder length="0.015" radius="0.02"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</visual>
</link>
<joint name="link3_link4" type="fixed">
<parent link="link3"/>
<child link="link4"/>
<origin rpy="0 0 0" xyz="0 0 0.15"/>
<axis xyz="0 0 0"/>
</joint>
-->
</robot>