-
Notifications
You must be signed in to change notification settings - Fork 85
/
ultraArm_p340.urdf
100 lines (85 loc) · 2.92 KB
/
ultraArm_p340.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
<?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/ultraArm_p340/ultraArm-base.dae"/>
</geometry>
<origin xyz = " 0 0 0.0 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 1.5708 3.14159-->
<mesh filename="package://mycobot_description/urdf/ultraArm_p340/ultraArm-base.dae"/>
</geometry>
<origin xyz = " 0 0 0.0 " rpy = " 0 0 0"/>
</collision>
</link>
<link name="link1">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/ultraArm_p340/ultraArm-1.dae"/>
</geometry>
<origin xyz = "0 0 0.122 " rpy = " 3.1415926 0 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/ultraArm_p340/ultraArm-1.dae"/>
</geometry>
<origin xyz = "0 0 0.122 " rpy = " 3.1415926 0 0"/>
</collision>
</link>
<link name="link2">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/ultraArm_p340/ultraArm-2.dae"/>
</geometry>
<origin xyz = "-0.03 0.112 0.0 " rpy = " 1.5708 0 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/ultraArm_p340/ultraArm-2.dae"/>
</geometry>
<origin xyz = "-0.03 0.112 0.0 " rpy = " 1.5708 0 0"/>
</collision>
</link>
<link name="link3">
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/ultraArm_p340/ultraArm-3.dae"/>
</geometry>
<origin xyz = "-0.03 0.23 0.0 " rpy = "1.5708 0 0"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/ultraArm_p340/ultraArm-3.dae"/>
</geometry>
<origin xyz = "-0.03 0.23 0.0 " rpy = "1.5708 0 0"/>
</collision>
</link>
<joint name="joint1_to_base" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-2.36" upper = "2.967" velocity = "0"/>
<parent link="base"/>
<child link="link1"/>
<origin xyz= "0 0 0.12" rpy = "3.1415926 0 0"/>
</joint>
<joint name="joint2_to_joint1" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-0.31" upper = "1.57" velocity = "0"/>
<parent link="link1"/>
<child link="link2"/>
<origin xyz= "0.03 0 0.01" rpy = " -1.5707963 3.1415926 3.1415926 "/>
</joint>
<joint name="joint3_to_joint2" type="revolute">
<axis xyz=" 0 0 1"/>
<limit effort = "1000.0" lower = "-0.087" upper = "1.0472" velocity = "0"/>
<parent link="link2"/>
<child link="link3"/>
<origin xyz= "0.00 -0.12 0 " rpy = "0 0 0 "/>
</joint>
</robot>