Skip to content

Commit 66d2c54

Browse files
committed
Fix weird bugs when update ubuntu
1 parent 185c176 commit 66d2c54

File tree

3 files changed

+39
-39
lines changed

3 files changed

+39
-39
lines changed

iai_ur_description/urdf/ur10.urdf.xacro

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@
3131
safety_k_position:=20
3232
kinematics_file">
3333

34-
<xacro:property name="__kinematics" value="${kinematics_file['kinematics']}"/>
34+
<xacro:property name="kinematics" value="${kinematics_file['kinematics']}"/>
3535

3636
<!-- Inertia parameters -->
3737
<xacro:property name="base_mass" value="4.0" /> <!-- This mass might be incorrect -->
@@ -85,7 +85,7 @@
8585
<joint name="${prefix}shoulder_pan_joint" type="revolute">
8686
<parent link="${prefix}base_link" />
8787
<child link = "${prefix}shoulder_link" />
88-
<origin xyz="${__kinematics['shoulder']['x']} ${__kinematics['shoulder']['y']} ${__kinematics['shoulder']['z']}" rpy="${__kinematics['shoulder']['roll']} ${__kinematics['shoulder']['pitch']} ${__kinematics['shoulder']['yaw'] + base_correction}" />
88+
<origin xyz="${kinematics['shoulder']['x']} ${kinematics['shoulder']['y']} ${kinematics['shoulder']['z']}" rpy="${kinematics['shoulder']['roll']} ${kinematics['shoulder']['pitch']} ${kinematics['shoulder']['yaw'] + base_correction}" />
8989
<axis xyz="0 0 1" />
9090
<xacro:unless value="${joint_limited}">
9191
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="330.0" velocity="2.16"/>
@@ -126,7 +126,7 @@
126126
<joint name="${prefix}shoulder_lift_joint" type="revolute">
127127
<parent link="${prefix}shoulder_link" />
128128
<child link = "${prefix}upper_arm_link" />
129-
<origin xyz="${__kinematics['upper_arm']['x']} ${__kinematics['upper_arm']['y']} ${__kinematics['upper_arm']['z']}" rpy="${__kinematics['upper_arm']['roll']} ${__kinematics['upper_arm']['pitch']} ${__kinematics['upper_arm']['yaw']}" />
129+
<origin xyz="${kinematics['upper_arm']['x']} ${kinematics['upper_arm']['y']} ${kinematics['upper_arm']['z']}" rpy="${kinematics['upper_arm']['roll']} ${kinematics['upper_arm']['pitch']} ${kinematics['upper_arm']['yaw']}" />
130130
<axis xyz="0 0 1" />
131131
<xacro:unless value="${joint_limited}">
132132
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="330.0" velocity="2.16"/>
@@ -159,15 +159,15 @@
159159
<mesh filename="package://iai_ur_description/meshes/ur10/collision/upperarm.stl"/>
160160
</geometry>
161161
</collision>
162-
<xacro:cylinder_inertial radius="0.075" length="${-1*__kinematics['forearm']['x']}" mass="${upper_arm_mass}">
163-
<origin xyz="${0.5*__kinematics['forearm']['x']} 0.0 ${upper_arm_inertia_offset}" rpy="0 ${pi/2} 0" />
162+
<xacro:cylinder_inertial radius="0.075" length="${-1*kinematics['forearm']['x']}" mass="${upper_arm_mass}">
163+
<origin xyz="${0.5*kinematics['forearm']['x']} 0.0 ${upper_arm_inertia_offset}" rpy="0 ${pi/2} 0" />
164164
</xacro:cylinder_inertial>
165165
</link>
166166

167167
<joint name="${prefix}elbow_joint" type="revolute">
168168
<parent link="${prefix}upper_arm_link" />
169169
<child link = "${prefix}forearm_link" />
170-
<origin xyz="${__kinematics['forearm']['x']} ${__kinematics['forearm']['y']} ${__kinematics['forearm']['z']}" rpy="${__kinematics['forearm']['roll']} ${__kinematics['forearm']['pitch']} ${__kinematics['forearm']['yaw']}" />
170+
<origin xyz="${kinematics['forearm']['x']} ${kinematics['forearm']['y']} ${kinematics['forearm']['z']}" rpy="${kinematics['forearm']['roll']} ${kinematics['forearm']['pitch']} ${kinematics['forearm']['yaw']}" />
171171
<axis xyz="0 0 1" />
172172
<xacro:unless value="${joint_limited}">
173173
<limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="3.15"/>
@@ -200,15 +200,15 @@
200200
<mesh filename="package://iai_ur_description/meshes/ur10/collision/forearm.stl"/>
201201
</geometry>
202202
</collision>
203-
<xacro:cylinder_inertial radius="0.075" length="${-1*__kinematics['wrist_1']['x']}" mass="${forearm_mass}">
204-
<origin xyz="${0.5*__kinematics['forearm']['x']} 0.0 ${elbow_offset}" rpy="0 ${pi/2} 0" />
203+
<xacro:cylinder_inertial radius="0.075" length="${-1*kinematics['wrist_1']['x']}" mass="${forearm_mass}">
204+
<origin xyz="${0.5*kinematics['forearm']['x']} 0.0 ${elbow_offset}" rpy="0 ${pi/2} 0" />
205205
</xacro:cylinder_inertial>
206206
</link>
207207

208208
<joint name="${prefix}wrist_1_joint" type="revolute">
209209
<parent link="${prefix}forearm_link" />
210210
<child link = "${prefix}wrist_1_link" />
211-
<origin xyz="${__kinematics['wrist_1']['x']} ${__kinematics['wrist_1']['y']} ${__kinematics['wrist_1']['z']}" rpy="${__kinematics['wrist_1']['roll']} ${__kinematics['wrist_1']['pitch']} ${__kinematics['wrist_1']['yaw']}" />
211+
<origin xyz="${kinematics['wrist_1']['x']} ${kinematics['wrist_1']['y']} ${kinematics['wrist_1']['z']}" rpy="${kinematics['wrist_1']['roll']} ${kinematics['wrist_1']['pitch']} ${kinematics['wrist_1']['yaw']}" />
212212
<axis xyz="0 0 1" />
213213
<xacro:unless value="${joint_limited}">
214214
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="3.2"/>
@@ -241,15 +241,15 @@
241241
<mesh filename="package://iai_ur_description/meshes/ur10/collision/wrist1.stl"/>
242242
</geometry>
243243
</collision>
244-
<xacro:cylinder_inertial radius="0.075" length="${-1*__kinematics['wrist_2']['y']}" mass="${wrist_1_mass}">
244+
<xacro:cylinder_inertial radius="0.075" length="${-1*kinematics['wrist_2']['y']}" mass="${wrist_1_mass}">
245245
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
246246
</xacro:cylinder_inertial>
247247
</link>
248248

249249
<joint name="${prefix}wrist_2_joint" type="revolute">
250250
<parent link="${prefix}wrist_1_link" />
251251
<child link = "${prefix}wrist_2_link" />
252-
<origin xyz="${__kinematics['wrist_2']['x']} ${__kinematics['wrist_2']['y']} ${__kinematics['wrist_2']['z']}" rpy="${__kinematics['wrist_2']['roll']} ${__kinematics['wrist_2']['pitch']} ${__kinematics['wrist_2']['yaw']}" />
252+
<origin xyz="${kinematics['wrist_2']['x']} ${kinematics['wrist_2']['y']} ${kinematics['wrist_2']['z']}" rpy="${kinematics['wrist_2']['roll']} ${kinematics['wrist_2']['pitch']} ${kinematics['wrist_2']['yaw']}" />
253253
<axis xyz="0 0 1" />
254254
<xacro:unless value="${joint_limited}">
255255
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="3.2"/>
@@ -282,15 +282,15 @@
282282
<mesh filename="package://iai_ur_description/meshes/ur10/collision/wrist2.stl"/>
283283
</geometry>
284284
</collision>
285-
<xacro:cylinder_inertial radius="0.075" length="${__kinematics['wrist_3']['y']}" mass="${wrist_2_mass}">
285+
<xacro:cylinder_inertial radius="0.075" length="${kinematics['wrist_3']['y']}" mass="${wrist_2_mass}">
286286
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
287287
</xacro:cylinder_inertial>
288288
</link>
289289

290290
<joint name="${prefix}wrist_3_joint" type="revolute">
291291
<parent link="${prefix}wrist_2_link" />
292292
<child link = "${prefix}wrist_3_link" />
293-
<origin xyz="${__kinematics['wrist_3']['x']} ${__kinematics['wrist_3']['y']} ${__kinematics['wrist_3']['z']}" rpy="${__kinematics['wrist_3']['roll']} ${__kinematics['wrist_3']['pitch']} ${__kinematics['wrist_3']['yaw']}" />
293+
<origin xyz="${kinematics['wrist_3']['x']} ${kinematics['wrist_3']['y']} ${kinematics['wrist_3']['z']}" rpy="${kinematics['wrist_3']['roll']} ${kinematics['wrist_3']['pitch']} ${kinematics['wrist_3']['yaw']}" />
294294
<axis xyz="0 0 1" />
295295
<xacro:unless value="${joint_limited}">
296296
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="3.2"/>

iai_ur_description/urdf/ur3.urdf.xacro

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@
3030
safety_k_position:=20
3131
kinematics_file">
3232

33-
<xacro:property name="__kinematics" value="${kinematics_file['kinematics']}"/>
33+
<xacro:property name="kinematics" value="${kinematics_file['kinematics']}"/>
3434

3535
<!-- Inertia parameters -->
3636
<xacro:property name="base_mass" value="2.0" /> <!-- This mass might be incorrect -->
@@ -84,7 +84,7 @@
8484
<joint name="${prefix}shoulder_pan_joint" type="revolute">
8585
<parent link="${prefix}base_link" />
8686
<child link = "${prefix}shoulder_link" />
87-
<origin xyz="${__kinematics['shoulder']['x']} ${__kinematics['shoulder']['y']} ${__kinematics['shoulder']['z']}" rpy="${__kinematics['shoulder']['roll']} ${__kinematics['shoulder']['pitch']} ${__kinematics['shoulder']['yaw'] + base_correction}" />
87+
<origin xyz="${kinematics['shoulder']['x']} ${kinematics['shoulder']['y']} ${kinematics['shoulder']['z']}" rpy="${kinematics['shoulder']['roll']} ${kinematics['shoulder']['pitch']} ${kinematics['shoulder']['yaw'] + base_correction}" />
8888
<axis xyz="0 0 1" />
8989
<xacro:unless value="${joint_limited}">
9090
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="330.0" velocity="2.16"/>
@@ -125,7 +125,7 @@
125125
<joint name="${prefix}shoulder_lift_joint" type="revolute">
126126
<parent link="${prefix}shoulder_link" />
127127
<child link = "${prefix}upper_arm_link" />
128-
<origin xyz="${__kinematics['upper_arm']['x']} ${__kinematics['upper_arm']['y']} ${__kinematics['upper_arm']['z']}" rpy="${__kinematics['upper_arm']['roll']} ${__kinematics['upper_arm']['pitch']} ${__kinematics['upper_arm']['yaw']}" />
128+
<origin xyz="${kinematics['upper_arm']['x']} ${kinematics['upper_arm']['y']} ${kinematics['upper_arm']['z']}" rpy="${kinematics['upper_arm']['roll']} ${kinematics['upper_arm']['pitch']} ${kinematics['upper_arm']['yaw']}" />
129129
<axis xyz="0 0 1" />
130130
<xacro:unless value="${joint_limited}">
131131
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="330.0" velocity="2.16"/>
@@ -158,15 +158,15 @@
158158
<mesh filename="package://iai_ur_description/meshes/ur3/collision/upperarm.stl"/>
159159
</geometry>
160160
</collision>
161-
<xacro:cylinder_inertial radius="0.075" length="${-1*__kinematics['forearm']['x']}" mass="${upper_arm_mass}">
162-
<origin xyz="${0.5*__kinematics['forearm']['x']} 0.0 ${upper_arm_inertia_offset}" rpy="0 ${pi/2} 0" />
161+
<xacro:cylinder_inertial radius="0.075" length="${-1*kinematics['forearm']['x']}" mass="${upper_arm_mass}">
162+
<origin xyz="${0.5*kinematics['forearm']['x']} 0.0 ${upper_arm_inertia_offset}" rpy="0 ${pi/2} 0" />
163163
</xacro:cylinder_inertial>
164164
</link>
165165

166166
<joint name="${prefix}elbow_joint" type="revolute">
167167
<parent link="${prefix}upper_arm_link" />
168168
<child link = "${prefix}forearm_link" />
169-
<origin xyz="${__kinematics['forearm']['x']} ${__kinematics['forearm']['y']} ${__kinematics['forearm']['z']}" rpy="${__kinematics['forearm']['roll']} ${__kinematics['forearm']['pitch']} ${__kinematics['forearm']['yaw']}" />
169+
<origin xyz="${kinematics['forearm']['x']} ${kinematics['forearm']['y']} ${kinematics['forearm']['z']}" rpy="${kinematics['forearm']['roll']} ${kinematics['forearm']['pitch']} ${kinematics['forearm']['yaw']}" />
170170
<axis xyz="0 0 1" />
171171
<xacro:unless value="${joint_limited}">
172172
<limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="3.15"/>
@@ -199,15 +199,15 @@
199199
<mesh filename="package://iai_ur_description/meshes/ur3/collision/forearm.stl"/>
200200
</geometry>
201201
</collision>
202-
<xacro:cylinder_inertial radius="0.075" length="${-1*__kinematics['wrist_1']['x']}" mass="${forearm_mass}">
203-
<origin xyz="${0.5*__kinematics['forearm']['x']} 0.0 ${elbow_offset}" rpy="0 ${pi/2} 0" />
202+
<xacro:cylinder_inertial radius="0.075" length="${-1*kinematics['wrist_1']['x']}" mass="${forearm_mass}">
203+
<origin xyz="${0.5*kinematics['forearm']['x']} 0.0 ${elbow_offset}" rpy="0 ${pi/2} 0" />
204204
</xacro:cylinder_inertial>
205205
</link>
206206

207207
<joint name="${prefix}wrist_1_joint" type="revolute">
208208
<parent link="${prefix}forearm_link" />
209209
<child link = "${prefix}wrist_1_link" />
210-
<origin xyz="${__kinematics['wrist_1']['x']} ${__kinematics['wrist_1']['y']} ${__kinematics['wrist_1']['z']}" rpy="${__kinematics['wrist_1']['roll']} ${__kinematics['wrist_1']['pitch']} ${__kinematics['wrist_1']['yaw']}" />
210+
<origin xyz="${kinematics['wrist_1']['x']} ${kinematics['wrist_1']['y']} ${kinematics['wrist_1']['z']}" rpy="${kinematics['wrist_1']['roll']} ${kinematics['wrist_1']['pitch']} ${kinematics['wrist_1']['yaw']}" />
211211
<axis xyz="0 0 1" />
212212
<xacro:unless value="${joint_limited}">
213213
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="3.2"/>
@@ -240,15 +240,15 @@
240240
<mesh filename="package://iai_ur_description/meshes/ur3/collision/wrist1.stl"/>
241241
</geometry>
242242
</collision>
243-
<xacro:cylinder_inertial radius="0.075" length="${-1*__kinematics['wrist_2']['y']}" mass="${wrist_1_mass}">
243+
<xacro:cylinder_inertial radius="0.075" length="${-1*kinematics['wrist_2']['y']}" mass="${wrist_1_mass}">
244244
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
245245
</xacro:cylinder_inertial>
246246
</link>
247247

248248
<joint name="${prefix}wrist_2_joint" type="revolute">
249249
<parent link="${prefix}wrist_1_link" />
250250
<child link = "${prefix}wrist_2_link" />
251-
<origin xyz="${__kinematics['wrist_2']['x']} ${__kinematics['wrist_2']['y']} ${__kinematics['wrist_2']['z']}" rpy="${__kinematics['wrist_2']['roll']} ${__kinematics['wrist_2']['pitch']} ${__kinematics['wrist_2']['yaw']}" />
251+
<origin xyz="${kinematics['wrist_2']['x']} ${kinematics['wrist_2']['y']} ${kinematics['wrist_2']['z']}" rpy="${kinematics['wrist_2']['roll']} ${kinematics['wrist_2']['pitch']} ${kinematics['wrist_2']['yaw']}" />
252252
<axis xyz="0 0 1" />
253253
<xacro:unless value="${joint_limited}">
254254
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="3.2"/>
@@ -281,15 +281,15 @@
281281
<mesh filename="package://iai_ur_description/meshes/ur3/collision/wrist2.stl"/>
282282
</geometry>
283283
</collision>
284-
<xacro:cylinder_inertial radius="0.075" length="${__kinematics['wrist_3']['y']}" mass="${wrist_2_mass}">
284+
<xacro:cylinder_inertial radius="0.075" length="${kinematics['wrist_3']['y']}" mass="${wrist_2_mass}">
285285
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
286286
</xacro:cylinder_inertial>
287287
</link>
288288

289289
<joint name="${prefix}wrist_3_joint" type="revolute">
290290
<parent link="${prefix}wrist_2_link" />
291291
<child link = "${prefix}wrist_3_link" />
292-
<origin xyz="${__kinematics['wrist_3']['x']} ${__kinematics['wrist_3']['y']} ${__kinematics['wrist_3']['z']}" rpy="${__kinematics['wrist_3']['roll']} ${__kinematics['wrist_3']['pitch']} ${__kinematics['wrist_3']['yaw']}" />
292+
<origin xyz="${kinematics['wrist_3']['x']} ${kinematics['wrist_3']['y']} ${kinematics['wrist_3']['z']}" rpy="${kinematics['wrist_3']['roll']} ${kinematics['wrist_3']['pitch']} ${kinematics['wrist_3']['yaw']}" />
293293
<axis xyz="0 0 1" />
294294
<xacro:unless value="${joint_limited}">
295295
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="3.2"/>

0 commit comments

Comments
 (0)