-
Notifications
You must be signed in to change notification settings - Fork 241
/
Copy pathur_common.xacro
216 lines (194 loc) · 18.4 KB
/
ur_common.xacro
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
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<!--
NOTE the macros defined in this file are NOT part of the public API of this
package. Users CANNOT rely on this file being available, or stored in
this location. Nor can they rely on the existence of the two macros.
The macros store the defined properties in the scope of the caller.
However, users MUST NOT rely on these properties, their contents or their
names.
Author: Ludovic Delval
Contributor: Felix Messmer
-->
<xacro:macro name="cylinder_inertial" params="radius length mass *origin">
<inertial>
<mass value="${mass}" />
<xacro:insert_block name="origin" />
<inertia ixx="${0.0833333 * mass * (3 * radius * radius + length * length)}" ixy="0.0" ixz="0.0"
iyy="${0.0833333 * mass * (3 * radius * radius + length * length)}" iyz="0.0"
izz="${0.5 * mass * radius * radius}" />
</inertial>
</xacro:macro>
<xacro:macro name="read_model_data" params="joint_limits_parameters_file kinematics_parameters_file physical_parameters_file visual_parameters_file">
<!-- Read .yaml files from disk, load content into properties -->
<xacro:property name="config_joint_limit_parameters" value="${load_yaml(joint_limits_parameters_file)}"/>
<xacro:property name="config_kinematics_parameters" value="${load_yaml(kinematics_parameters_file)}"/>
<xacro:property name="config_physical_parameters" value="${load_yaml(physical_parameters_file)}"/>
<xacro:property name="config_visual_parameters" value="${load_yaml(visual_parameters_file)}"/>
<!-- Extract subsections from yaml dictionaries -->
<xacro:property name="sec_limits" value="${config_joint_limit_parameters['joint_limits']}"/>
<xacro:property name="sec_dh_parameters" value="${config_physical_parameters['dh_parameters']}"/>
<xacro:property name="sec_offsets" value="${config_physical_parameters['offsets']}"/>
<xacro:property name="sec_inertia_parameters" value="${config_physical_parameters['inertia_parameters']}" />
<xacro:property name="sec_mesh_files" value="${config_visual_parameters['mesh_files']}" />
<xacro:property name="sec_kinematics" value="${config_kinematics_parameters['kinematics']}" />
<!-- JOINTS LIMIT PARAMETERS -->
<xacro:property name="shoulder_pan_lower_limit" value="${sec_limits['shoulder_pan']['min_position']}" scope="parent"/>
<xacro:property name="shoulder_pan_upper_limit" value="${sec_limits['shoulder_pan']['max_position']}" scope="parent"/>
<xacro:property name="shoulder_pan_velocity_limit" value="${sec_limits['shoulder_pan']['max_velocity']}" scope="parent"/>
<xacro:property name="shoulder_pan_effort_limit" value="${sec_limits['shoulder_pan']['max_effort']}" scope="parent"/>
<xacro:property name="shoulder_lift_lower_limit" value="${sec_limits['shoulder_lift']['min_position']}" scope="parent"/>
<xacro:property name="shoulder_lift_upper_limit" value="${sec_limits['shoulder_lift']['max_position']}" scope="parent"/>
<xacro:property name="shoulder_lift_velocity_limit" value="${sec_limits['shoulder_lift']['max_velocity']}" scope="parent"/>
<xacro:property name="shoulder_lift_effort_limit" value="${sec_limits['shoulder_lift']['max_effort']}" scope="parent"/>
<xacro:property name="elbow_joint_lower_limit" value="${sec_limits['elbow_joint']['min_position']}" scope="parent"/>
<xacro:property name="elbow_joint_upper_limit" value="${sec_limits['elbow_joint']['max_position']}" scope="parent"/>
<xacro:property name="elbow_joint_velocity_limit" value="${sec_limits['elbow_joint']['max_velocity']}" scope="parent"/>
<xacro:property name="elbow_joint_effort_limit" value="${sec_limits['elbow_joint']['max_effort']}" scope="parent"/>
<xacro:property name="wrist_1_lower_limit" value="${sec_limits['wrist_1']['min_position']}" scope="parent"/>
<xacro:property name="wrist_1_upper_limit" value="${sec_limits['wrist_1']['max_position']}" scope="parent"/>
<xacro:property name="wrist_1_velocity_limit" value="${sec_limits['wrist_1']['max_velocity']}" scope="parent"/>
<xacro:property name="wrist_1_effort_limit" value="${sec_limits['wrist_1']['max_effort']}" scope="parent"/>
<xacro:property name="wrist_2_lower_limit" value="${sec_limits['wrist_2']['min_position']}" scope="parent"/>
<xacro:property name="wrist_2_upper_limit" value="${sec_limits['wrist_2']['max_position']}" scope="parent"/>
<xacro:property name="wrist_2_velocity_limit" value="${sec_limits['wrist_2']['max_velocity']}" scope="parent"/>
<xacro:property name="wrist_2_effort_limit" value="${sec_limits['wrist_2']['max_effort']}" scope="parent"/>
<xacro:property name="wrist_3_lower_limit" value="${sec_limits['wrist_3']['min_position']}" scope="parent"/>
<xacro:property name="wrist_3_upper_limit" value="${sec_limits['wrist_3']['max_position']}" scope="parent"/>
<xacro:property name="wrist_3_velocity_limit" value="${sec_limits['wrist_3']['max_velocity']}" scope="parent"/>
<xacro:property name="wrist_3_effort_limit" value="${sec_limits['wrist_3']['max_effort']}" scope="parent"/>
<!-- DH PARAMETERS -->
<xacro:property name="d1" value="${sec_dh_parameters['d1']}" scope="parent"/>
<xacro:property name="a2" value="${sec_dh_parameters['a2']}" scope="parent"/>
<xacro:property name="a3" value="${sec_dh_parameters['a3']}" scope="parent"/>
<xacro:property name="d4" value="${sec_dh_parameters['d4']}" scope="parent"/>
<xacro:property name="d5" value="${sec_dh_parameters['d5']}" scope="parent"/>
<xacro:property name="d6" value="${sec_dh_parameters['d6']}" scope="parent"/>
<!-- kinematics -->
<xacro:property name="shoulder_x" value="${sec_kinematics['shoulder']['x']}" scope="parent"/>
<xacro:property name="shoulder_y" value="${sec_kinematics['shoulder']['y']}" scope="parent"/>
<xacro:property name="shoulder_z" value="${sec_kinematics['shoulder']['z']}" scope="parent"/>
<xacro:property name="shoulder_roll" value="${sec_kinematics['shoulder']['roll']}" scope="parent"/>
<xacro:property name="shoulder_pitch" value="${sec_kinematics['shoulder']['pitch']}" scope="parent"/>
<xacro:property name="shoulder_yaw" value="${sec_kinematics['shoulder']['yaw']}" scope="parent"/>
<xacro:property name="upper_arm_x" value="${sec_kinematics['upper_arm']['x']}" scope="parent"/>
<xacro:property name="upper_arm_y" value="${sec_kinematics['upper_arm']['y']}" scope="parent"/>
<xacro:property name="upper_arm_z" value="${sec_kinematics['upper_arm']['z']}" scope="parent"/>
<xacro:property name="upper_arm_roll" value="${sec_kinematics['upper_arm']['roll']}" scope="parent"/>
<xacro:property name="upper_arm_pitch" value="${sec_kinematics['upper_arm']['pitch']}" scope="parent"/>
<xacro:property name="upper_arm_yaw" value="${sec_kinematics['upper_arm']['yaw']}" scope="parent"/>
<xacro:property name="forearm_x" value="${sec_kinematics['forearm']['x']}" scope="parent"/>
<xacro:property name="forearm_y" value="${sec_kinematics['forearm']['y']}" scope="parent"/>
<xacro:property name="forearm_z" value="${sec_kinematics['forearm']['z']}" scope="parent"/>
<xacro:property name="forearm_roll" value="${sec_kinematics['forearm']['roll']}" scope="parent"/>
<xacro:property name="forearm_pitch" value="${sec_kinematics['forearm']['pitch']}" scope="parent"/>
<xacro:property name="forearm_yaw" value="${sec_kinematics['forearm']['yaw']}" scope="parent"/>
<xacro:property name="wrist_1_x" value="${sec_kinematics['wrist_1']['x']}" scope="parent"/>
<xacro:property name="wrist_1_y" value="${sec_kinematics['wrist_1']['y']}" scope="parent"/>
<xacro:property name="wrist_1_z" value="${sec_kinematics['wrist_1']['z']}" scope="parent"/>
<xacro:property name="wrist_1_roll" value="${sec_kinematics['wrist_1']['roll']}" scope="parent"/>
<xacro:property name="wrist_1_pitch" value="${sec_kinematics['wrist_1']['pitch']}" scope="parent"/>
<xacro:property name="wrist_1_yaw" value="${sec_kinematics['wrist_1']['yaw']}" scope="parent"/>
<xacro:property name="wrist_2_x" value="${sec_kinematics['wrist_2']['x']}" scope="parent"/>
<xacro:property name="wrist_2_y" value="${sec_kinematics['wrist_2']['y']}" scope="parent"/>
<xacro:property name="wrist_2_z" value="${sec_kinematics['wrist_2']['z']}" scope="parent"/>
<xacro:property name="wrist_2_roll" value="${sec_kinematics['wrist_2']['roll']}" scope="parent"/>
<xacro:property name="wrist_2_pitch" value="${sec_kinematics['wrist_2']['pitch']}" scope="parent"/>
<xacro:property name="wrist_2_yaw" value="${sec_kinematics['wrist_2']['yaw']}" scope="parent"/>
<xacro:property name="wrist_3_x" value="${sec_kinematics['wrist_3']['x']}" scope="parent"/>
<xacro:property name="wrist_3_y" value="${sec_kinematics['wrist_3']['y']}" scope="parent"/>
<xacro:property name="wrist_3_z" value="${sec_kinematics['wrist_3']['z']}" scope="parent"/>
<xacro:property name="wrist_3_roll" value="${sec_kinematics['wrist_3']['roll']}" scope="parent"/>
<xacro:property name="wrist_3_pitch" value="${sec_kinematics['wrist_3']['pitch']}" scope="parent"/>
<xacro:property name="wrist_3_yaw" value="${sec_kinematics['wrist_3']['yaw']}" scope="parent"/>
<!-- OFFSETS -->
<xacro:property name="shoulder_offset" value="${sec_offsets['shoulder_offset']}" scope="parent"/>
<xacro:property name="elbow_offset" value="${sec_offsets['elbow_offset']}" scope="parent"/>
<!-- INERTIA PARAMETERS -->
<!-- mass -->
<xacro:property name="base_mass" value="${sec_inertia_parameters['base_mass']}" scope="parent"/>
<xacro:property name="shoulder_mass" value="${sec_inertia_parameters['shoulder_mass']}" scope="parent"/>
<xacro:property name="upper_arm_mass" value="${sec_inertia_parameters['upper_arm_mass']}" scope="parent"/>
<xacro:property name="upper_arm_inertia_offset" value="${sec_inertia_parameters['upper_arm_inertia_offset']}" scope="parent"/>
<xacro:property name="forearm_mass" value="${sec_inertia_parameters['forearm_mass']}" scope="parent"/>
<xacro:property name="wrist_1_mass" value="${sec_inertia_parameters['wrist_1_mass']}" scope="parent"/>
<xacro:property name="wrist_2_mass" value="${sec_inertia_parameters['wrist_2_mass']}" scope="parent"/>
<xacro:property name="wrist_3_mass" value="${sec_inertia_parameters['wrist_3_mass']}" scope="parent"/>
<!-- link inertia parameter -->
<xacro:property name="intertia_links" value="${sec_inertia_parameters['links']}" scope="parent"/>
<xacro:property name="base_inertia_radius" value="${intertia_links['base']['radius']}" scope="parent"/>
<xacro:property name="base_inertia_length" value="${intertia_links['base']['length']}" scope="parent"/>
<xacro:property name="shoulder_inertia_radius" value="${intertia_links['shoulder']['radius']}" scope="parent"/>
<xacro:property name="shoulder_inertia_length" value="${intertia_links['shoulder']['length']}" scope="parent"/>
<xacro:property name="upperarm_inertia_radius" value="${intertia_links['upperarm']['radius']}" scope="parent"/>
<xacro:property name="upperarm_inertia_length" value="${intertia_links['upperarm']['length']}" scope="parent"/>
<xacro:property name="forearm_inertia_radius" value="${intertia_links['forearm']['radius']}" scope="parent"/>
<xacro:property name="forearm_inertia_length" value="${intertia_links['forearm']['length']}" scope="parent"/>
<xacro:property name="wrist_1_inertia_radius" value="${intertia_links['wrist_1']['radius']}" scope="parent"/>
<xacro:property name="wrist_1_inertia_length" value="${intertia_links['wrist_1']['length']}" scope="parent"/>
<xacro:property name="wrist_2_inertia_radius" value="${intertia_links['wrist_2']['radius']}" scope="parent"/>
<xacro:property name="wrist_2_inertia_length" value="${intertia_links['wrist_2']['length']}" scope="parent"/>
<xacro:property name="wrist_3_inertia_radius" value="${intertia_links['wrist_3']['radius']}" scope="parent"/>
<xacro:property name="wrist_3_inertia_length" value="${intertia_links['wrist_3']['length']}" scope="parent"/>
<!-- center of mass -->
<xacro:property name="prop_shoulder_cog" value="${sec_inertia_parameters['center_of_mass']['shoulder_cog']}" scope="parent"/>
<xacro:property name="prop_upper_arm_cog" value="${sec_inertia_parameters['center_of_mass']['upper_arm_cog']}" scope="parent"/>
<xacro:property name="prop_forearm_cog" value="${sec_inertia_parameters['center_of_mass']['forearm_cog']}" scope="parent"/>
<xacro:property name="prop_wrist_1_cog" value="${sec_inertia_parameters['center_of_mass']['wrist_1_cog']}" scope="parent"/>
<xacro:property name="prop__wrist_2_cog" value="${sec_inertia_parameters['center_of_mass']['wrist_2_cog']}" scope="parent"/>
<xacro:property name="prop_wrist_3_cog" value="${sec_inertia_parameters['center_of_mass']['wrist_3_cog']}" scope="parent"/>
<xacro:property name="shoulder_cog" value="${prop_shoulder_cog['x']} ${prop_shoulder_cog['y']} ${prop_shoulder_cog['z']}" scope="parent"/>
<xacro:property name="upper_arm_cog" value="${prop_upper_arm_cog['x']} ${prop_upper_arm_cog['y']} ${prop_upper_arm_cog['z']}" scope="parent"/>
<xacro:property name="forearm_cog" value="${prop_forearm_cog['x']} ${prop_forearm_cog['y']} ${prop_forearm_cog['z']}" scope="parent"/>
<xacro:property name="wrist_1_cog" value="${prop_wrist_1_cog['x']} ${prop_wrist_1_cog['y']} ${prop_wrist_1_cog['z']}" scope="parent"/>
<xacro:property name="wrist_2_cog" value="${prop__wrist_2_cog['x']} ${prop__wrist_2_cog['y']} ${prop__wrist_2_cog['z']}" scope="parent"/>
<xacro:property name="wrist_3_cog" value="${prop_wrist_3_cog['x']} ${prop_wrist_3_cog['y']} ${prop_wrist_3_cog['z']}" scope="parent"/>
<!-- cylinder radius -->
<xacro:property name="shoulder_radius" value="${sec_inertia_parameters['shoulder_radius']}" scope="parent"/>
<xacro:property name="upper_arm_radius" value="${sec_inertia_parameters['upper_arm_radius']}" scope="parent"/>
<xacro:property name="elbow_radius" value="${sec_inertia_parameters['elbow_radius']}" scope="parent"/>
<xacro:property name="forearm_radius" value="${sec_inertia_parameters['forearm_radius']}" scope="parent"/>
<xacro:property name="wrist_radius" value="${sec_inertia_parameters['wrist_radius']}" scope="parent"/>
<!-- Mesh files -->
<xacro:property name="base_mesh" value="${sec_mesh_files['base']}"/>
<xacro:property name="base_visual_mesh" value="${base_mesh['visual']['mesh']}" scope="parent"/>
<xacro:property name="base_visual_material_name" value="${base_mesh['visual']['material']['name']}" scope="parent"/>
<xacro:property name="base_visual_material_color" value="${base_mesh['visual']['material']['color']}" scope="parent"/>
<xacro:property name="base_collision_mesh" value="${base_mesh['collision']['mesh']}" scope="parent"/>
<xacro:property name="shoulder_mesh" value="${sec_mesh_files['shoulder']}"/>
<xacro:property name="shoulder_visual_mesh" value="${shoulder_mesh['visual']['mesh']}" scope="parent"/>
<xacro:property name="shoulder_visual_material_name" value="${shoulder_mesh['visual']['material']['name']}" scope="parent"/>
<xacro:property name="shoulder_visual_material_color" value="${shoulder_mesh['visual']['material']['color']}" scope="parent"/>
<xacro:property name="shoulder_collision_mesh" value="${shoulder_mesh['collision']['mesh']}" scope="parent"/>
<xacro:property name="upper_arm_mesh" value="${sec_mesh_files['upper_arm']}"/>
<xacro:property name="upper_arm_visual_mesh" value="${upper_arm_mesh['visual']['mesh']}" scope="parent"/>
<xacro:property name="upper_arm_visual_material_name" value="${upper_arm_mesh['visual']['material']['name']}" scope="parent"/>
<xacro:property name="upper_arm_visual_material_color" value="${upper_arm_mesh['visual']['material']['color']}" scope="parent"/>
<xacro:property name="upper_arm_collision_mesh" value="${upper_arm_mesh['collision']['mesh']}" scope="parent"/>
<xacro:property name="forearm_mesh" value="${sec_mesh_files['forearm']}"/>
<xacro:property name="forearm_visual_mesh" value="${forearm_mesh['visual']['mesh']}" scope="parent"/>
<xacro:property name="forearm_visual_material_name" value="${forearm_mesh['visual']['material']['name']}" scope="parent"/>
<xacro:property name="forearm_visual_material_color" value="${forearm_mesh['visual']['material']['color']}" scope="parent"/>
<xacro:property name="forearm_collision_mesh" value="${forearm_mesh['collision']['mesh']}" scope="parent"/>
<xacro:property name="wrist_1_mesh" value="${sec_mesh_files['wrist_1']}"/>
<xacro:property name="wrist_1_visual_mesh" value="${wrist_1_mesh['visual']['mesh']}" scope="parent"/>
<xacro:property name="wrist_1_visual_material_name" value="${wrist_1_mesh['visual']['material']['name']}" scope="parent"/>
<xacro:property name="wrist_1_visual_material_color" value="${wrist_1_mesh['visual']['material']['color']}" scope="parent"/>
<xacro:property name="wrist_1_collision_mesh" value="${wrist_1_mesh['collision']['mesh']}" scope="parent"/>
<xacro:property name="wrist_1_visual_offset" value="${wrist_1_mesh['visual_offset']}" scope="parent"/>
<xacro:property name="wrist_2_mesh" value="${sec_mesh_files['wrist_2']}"/>
<xacro:property name="wrist_2_visual_mesh" value="${wrist_2_mesh['visual']['mesh']}" scope="parent"/>
<xacro:property name="wrist_2_visual_material_name" value="${wrist_2_mesh['visual']['material']['name']}" scope="parent"/>
<xacro:property name="wrist_2_visual_material_color" value="${wrist_2_mesh['visual']['material']['color']}" scope="parent"/>
<xacro:property name="wrist_2_collision_mesh" value="${wrist_2_mesh['collision']['mesh']}" scope="parent"/>
<xacro:property name="wrist_2_visual_offset" value="${wrist_2_mesh['visual_offset']}" scope="parent"/>
<xacro:property name="wrist_3_mesh" value="${sec_mesh_files['wrist_3']}"/>
<xacro:property name="wrist_3_visual_mesh" value="${wrist_3_mesh['visual']['mesh']}" scope="parent"/>
<xacro:property name="wrist_3_visual_material_name" value="${wrist_3_mesh['visual']['material']['name']}" scope="parent"/>
<xacro:property name="wrist_3_visual_material_color" value="${wrist_3_mesh['visual']['material']['color']}" scope="parent"/>
<xacro:property name="wrist_3_collision_mesh" value="${wrist_3_mesh['collision']['mesh']}" scope="parent"/>
<xacro:property name="wrist_3_visual_offset" value="${wrist_3_mesh['visual_offset']}" scope="parent"/>
<!--KINEMATICS HASH-->
<xacro:property name="kinematics_hash" value="${sec_kinematics['hash']}" scope="parent"/>
</xacro:macro>
</robot>