-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathfaze4.urdf
More file actions
65 lines (58 loc) · 1.89 KB
/
faze4.urdf
File metadata and controls
65 lines (58 loc) · 1.89 KB
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
<?xml version="1.0" ?>
<robot name="faze4">
<link name="base_link" />
<link name="link_1" />
<joint name="joint_1" type="revolute">
<parent link="base_link"/>
<child link="link_1"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="-3.1415" upper="3.1415" effort="100" velocity="3"/>
</joint>
<link name="link_2" />
<joint name="joint_2" type="revolute">
<parent link="link_1"/>
<child link="link_2"/>
<origin xyz="0 0 0.2358" rpy="-1.5707963 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="-3.1415" upper="3.1415" effort="100" velocity="3"/>
</joint>
<link name="link_3" />
<joint name="joint_3" type="revolute">
<parent link="link_2"/>
<child link="link_3"/>
<origin xyz="0.32 0 0" rpy="-3.1415926 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="-3.1415" upper="3.1415" effort="100" velocity="3"/>
</joint>
<link name="link_4" />
<joint name="joint_4" type="revolute">
<parent link="link_3"/>
<child link="link_4"/>
<origin xyz="0.0735 0 0" rpy="-1.5707963 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="-3.1415" upper="3.1415" effort="100" velocity="3"/>
</joint>
<link name="link_5" />
<joint name="joint_5" type="revolute">
<parent link="link_4"/>
<child link="link_5"/>
<origin xyz="0 0 -0.2507" rpy="1.5707963 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="-3.1415" upper="3.1415" effort="100" velocity="3"/>
</joint>
<link name="link_6" />
<joint name="joint_6" type="revolute">
<parent link="link_5"/>
<child link="link_6"/>
<origin xyz="0 0 0" rpy="-1.5707963 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="-3.1415" upper="3.1415" effort="100" velocity="3"/>
</joint>
<link name="end_effector" />
<joint name="joint_ee" type="fixed">
<parent link="link_6"/>
<child link="end_effector"/>
<origin xyz="0 0 0.056" rpy="3.1415926 0 0"/>
</joint>
</robot>