-
Notifications
You must be signed in to change notification settings - Fork 23
/
mecharm_270_pi.urdf
175 lines (153 loc) · 5.31 KB
/
mecharm_270_pi.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
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="firefighter" >
<xacro:property name="width" value=".2" />
<link name="base">
<visual>
<geometry>
<!--- 0.0 0 -0.04 1.5708 3.14159-->
<mesh filename="package://mycobot_description/urdf/mecharm_270_pi/base.dae"/>
</geometry>
<origin xyz = " 0 0 0 " rpy = " 0 0 -3.1415926"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 1.5708 3.14159-->
<mesh filename="package://mycobot_description/urdf/mecharm_270_pi/base.dae"/>
</geometry>
<origin xyz = " 0 0 0 " rpy = " 0 0 -3.1415926"/>
</collision>
</link>
<link name="link1">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mecharm_270_pi/link1.dae"/>
</geometry>
<origin xyz = "0 0 -0.132 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mecharm_270_pi/link1.dae"/>
</geometry>
<origin xyz = "0 0 -0.132 " rpy = " 0 0 0"/>
</collision>
</link>
<link name="link2">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mecharm_270_pi/link2.dae"/>
</geometry>
<origin xyz = "-0.005 0.21 0.002 " rpy = " 1.5708 -3.1415926 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mecharm_270_pi/link2.dae"/>
</geometry>
<origin xyz = "-0.005 -0.21 0.002 " rpy = " 1.5708 -3.1415926 0"/>
</collision>
</link>
<link name="link3">
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mecharm_270_pi/link3.dae"/>
</geometry>
<origin xyz = "-0.09 0.306 0.005 " rpy = "1.5708 3.1415926 0"/>
<!-- <origin xyz = "-0.0 0.0 0.000 " rpy = "0 0 0"/> -->
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mecharm_270_pi/link3.dae"/>
</geometry>
<origin xyz = "-0.09 0.306 0.005" rpy = "1.5708 3.1415926 0"/>
</collision>
</link>
<link name="link4">
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mecharm_270_pi/link4.dae"/>
</geometry>
<origin xyz = "0.009 -0.311 -0.228" rpy = " 0 1.5708 1.5708"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mecharm_270_pi/link4.dae"/>
</geometry>
<origin xyz = "0.009 -0.311 -0.228" rpy = " 0 1.5708 1.5708"/>
</collision>
</link>
<link name="link5">
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mecharm_270_pi/link5.dae"/>
</geometry>
<origin xyz = "-0.292 -0.318 -0.007" rpy = " 1.5708 0 3.1415926"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mecharm_270_pi/link5.dae"/>
</geometry>
<origin xyz = "-0.292 -0.318 -0.007 " rpy = " 1.5708 0 3.1415926"/>
</collision>
</link>
<link name="link6">
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mecharm_270_pi/link6.dae"/>
</geometry>
<origin xyz = "-0.1645 0.0536 -0.211 " rpy = " 0 1.5708 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mecharm_270_pi/link6.dae"/>
</geometry>
<origin xyz = "-0.1645 0.0536 -0.211 " rpy = " 0 1.5708 0"/>
</collision>
</link>
<joint name="joint1_to_base" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-2.792527" upper = "2.792527" velocity = "0"/>
<parent link="base"/>
<child link="link1"/>
<origin xyz= "0 0 0.1" rpy = "0 0 0"/>
</joint>
<joint name="joint2_to_joint1" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-1.48353" upper = "1.570796" velocity = "0"/>
<parent link="link1"/>
<child link="link2"/>
<origin xyz= "0 0 0.038" rpy = " -1.5708 0 0 "/>
</joint>
<joint name="joint3_to_joint2" type="revolute">
<axis xyz=" 0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "0.785398" velocity = "0"/>
<parent link="link2"/>
<child link="link3"/>
<origin xyz= "0.0 -0.1 0 " rpy = "0 0 0 "/>
</joint>
<joint name="joint4_to_joint3" type="revolute">
<axis xyz=" 0 0 1"/>
<limit effort = "1000.0" lower = "-2.792527" upper = "2.792527" velocity = "0"/>
<parent link="link3"/>
<child link="link4"/>
<origin xyz= "0.108 -0.005 -0.001" rpy = "0 1.5708 0 "/>
</joint>
<joint name="joint5_to_joint4" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-1.745329" upper = "1.745329" velocity = "0"/>
<parent link="link4"/>
<child link="link5"/>
<origin xyz= " -0.001 0 0.0" rpy = " 0 -1.5708 0"/>
</joint>
<joint name="joint6_to_joint5" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14" velocity = "0"/>
<parent link="link5"/>
<child link="link6"/>
<origin xyz= " 0.06 0.00 -0.0" rpy = " 0 1.5708 0 "/>
</joint>
</robot>