-
Notifications
You must be signed in to change notification settings - Fork 4
Expand file tree
/
Copy pathar4.urdf.xacro
More file actions
114 lines (107 loc) · 5.13 KB
/
ar4.urdf.xacro
File metadata and controls
114 lines (107 loc) · 5.13 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
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
<?xml version="1.0"?>
<robot name="ar4" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="package_name" value="ar4_description"/>
<xacro:include filename="$(find ${package_name})/urdf/include/common_macros.urdf.xacro" />
<xacro:property name="robot_properties_yaml_dir" value="$(find ${package_name})/config/link_properties.yaml" />
<xacro:property name="robot_properties" value="${xacro.load_yaml(robot_properties_yaml_dir)}"/>
<xacro:property name="robot_parameters_yaml_dir" value="$(find ${package_name})/config/ar4.yaml" />
<xacro:property name="robot_parameters" value="${xacro.load_yaml(robot_parameters_yaml_dir)}"/>
<xacro:link link_name="base_link"
inertial="${robot_properties['base_link']['inertial']}"
visual="${robot_properties['base_link']['visual']}"
collision="${robot_properties['base_link']['collision']}"
meshes="${['base_link', 'base_link_bottom', 'base_link_motor']}"
materials="${['grey', 'blue', 'black']}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:link>
<xacro:link link_name="link_1"
inertial="${robot_properties['link_1']['inertial']}"
visual="${robot_properties['link_1']['visual']}"
collision="${robot_properties['link_1']['collision']}"
meshes="${['link_1', 'link_1_motor']}"
materials="${['grey', 'black']}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:link>
<joint name="joint_1" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base_link"/>
<child link="link_1"/>
<axis xyz="0 0 1"/>
<limit lower="${-170.0 / 180.0 * pi}" upper="${170.0 / 180.0 * pi}" effort="100" velocity="0.5"/>
</joint>
<xacro:link link_name="link_2"
inertial="${robot_properties['link_2']['inertial']}"
visual="${robot_properties['link_2']['visual']}"
collision="${robot_properties['link_2']['collision']}"
meshes="${['link_2', 'link_2_motor', 'link_2_cover', 'link_2_cover_logo']}"
materials="${['grey', 'black', 'white', 'blue']}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:link>
<joint name="joint_2" type="revolute">
<origin rpy="-1.5708 0 0" xyz="0.0642 0 0.16977"/>
<parent link="link_1"/>
<child link="link_2"/>
<axis xyz="0 0 1"/>
<limit lower="${-42.0 / 180.0 * pi}" upper="${90.0 / 180.0 * pi}" effort="100" velocity="0.5"/>
</joint>
<xacro:link link_name="link_3"
inertial="${robot_properties['link_3']['inertial']}"
visual="${robot_properties['link_3']['visual']}"
collision="${robot_properties['link_3']['collision']}"
meshes="${['link_3', 'link_3_motor', 'link_3_misc']}"
materials="${['grey', 'black', 'black']}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:link>
<joint name="joint_3" type="revolute">
<origin rpy="0 0 -1.5708" xyz="0 -0.305 0"/>
<parent link="link_2"/>
<child link="link_3"/>
<axis xyz="0 0 1"/>
<limit lower="${-89.0 / 180.0 * pi}" upper="${52.0 / 180.0 * pi}" effort="100" velocity="0.5"/>
</joint>
<xacro:link link_name="link_4"
inertial="${robot_properties['link_4']['inertial']}"
visual="${robot_properties['link_4']['visual']}"
collision="${robot_properties['link_4']['collision']}"
meshes="${['link_4', 'link_4_motor']}"
materials="${['grey', 'black']}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:link>
<joint name="joint_4" type="revolute">
<origin rpy="-1.5708 0 0" xyz="0 0 0.0"/>
<parent link="link_3"/>
<child link="link_4"/>
<axis xyz="0 0 1"/>
<limit lower="${-1 * robot_parameters['j4_limit']}" upper="${robot_parameters['j4_limit']}" effort="100" velocity="0.5"/>
</joint>
<xacro:link link_name="link_5"
inertial="${robot_properties['link_5']['inertial']}"
visual="${robot_properties['link_5']['visual']}"
collision="${robot_properties['link_5']['collision']}"
meshes="${['link_5', 'link_5_motor']}"
materials="${['grey', 'black']}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:link>
<joint name="joint_5" type="revolute">
<origin rpy="1.5708 0 0" xyz="0 0 0.22263"/>
<parent link="link_4"/>
<child link="link_5"/>
<axis xyz="0 0 1"/>
<limit lower="${-105.0 / 180.0 * pi}" upper="${105.0 / 180.0 * pi}" effort="100" velocity="1.0"/>
</joint>
<xacro:link link_name="link_6"
inertial="${robot_properties['link_6']['inertial']}"
visual="${robot_properties['link_6']['visual']}"
collision="${robot_properties['link_6']['collision']}"
meshes="${['link_6']}"
materials="${['grey']}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:link>
<joint name="joint_6" type="revolute">
<origin rpy="0 -1.5708 0" xyz="-${robot_parameters['l6_length']} 0 0"/>
<parent link="link_5"/>
<child link="link_6"/>
<axis xyz="0 0 1"/>
<limit lower="${-1.0 * robot_parameters['j6_limit']}" upper="${robot_parameters['j6_limit']}" effort="100" velocity="1.0"/>
</joint>
</robot>