Skip to content

Commit 3d29907

Browse files
committed
円周率の定数を削除してradians()に置き換える
1 parent cc925fc commit 3d29907

File tree

4 files changed

+34
-36
lines changed

4 files changed

+34
-36
lines changed

urdf/crane_x7.urdf.xacro

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -47,8 +47,6 @@
4747
<color rgba="0.3 0.3 1.0 1.0"/>
4848
</material>
4949

50-
<xacro:property name="M_PI" value="3.14159"/>
51-
5250
<xacro:property name="NAME_LINK_MOUNTING_PLATE" value="crane_x7_mounting_plate_link"/>
5351
<xacro:property name="NAME_LINK_BASE" value="crane_x7_shoulder_fixed_part_link"/>
5452
<xacro:property name="NAME_LINK_1" value="crane_x7_shoulder_revolute_part_link"/>

urdf/crane_x7_arm.xacro

Lines changed: 20 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@
5858
<!-- crane_x7_link_1 -->
5959
<link name="${NAME_LINK_1}">
6060
<visual>
61-
<origin xyz="0 0 0" rpy="0 0 ${M_PI}"/>
61+
<origin xyz="0 0 0" rpy="0 0 ${radians(180)}"/>
6262
<geometry>
6363
<mesh filename="package://crane_x7_description/meshes/visual/base_revolute_part.stl"
6464
scale="1 1 1"/>
@@ -67,7 +67,7 @@
6767
</visual>
6868

6969
<collision>
70-
<!--<origin xyz="0 0 0" rpy="0 0 ${M_PI}"/>-->
70+
<!--<origin xyz="0 0 0" rpy="0 0 ${radians(180)}"/>-->
7171
<!--<geometry>-->
7272
<!--<mesh filename="package://crane_x7_description/meshes/collision/base_revolute_part.stl"-->
7373
<!--scale="1 1 1"/>-->
@@ -78,7 +78,7 @@
7878
</geometry>
7979
</collision>
8080
<collision>
81-
<origin xyz="0 0 0.064" rpy="${M_PI/2} 0 0"/>
81+
<origin xyz="0 0 0.064" rpy="${radians(90)} 0 0"/>
8282
<geometry>
8383
<cylinder radius="0.034" length="0.0491"/>
8484
</geometry>
@@ -111,7 +111,7 @@
111111
<!-- crane_x7_link_2 -->
112112
<link name="${NAME_LINK_2}">
113113
<visual>
114-
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
114+
<origin xyz="0 0 0" rpy="${radians(90)} 0 0"/>
115115
<geometry>
116116
<mesh filename="package://crane_x7_description/meshes/visual/rotating_link_type_1_fixed_part.stl"
117117
scale="1 1 1"/>
@@ -120,7 +120,7 @@
120120
</visual>
121121

122122
<collision>
123-
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
123+
<origin xyz="0 0 0" rpy="${radians(90)} 0 0"/>
124124
<geometry>
125125
<mesh filename="package://crane_x7_description/meshes/collision/rotating_link_type_1_fixed_part.stl"
126126
scale="1 1 1"/>
@@ -129,7 +129,7 @@
129129

130130
<inertial>
131131
<mass value="0.136"/>
132-
<origin xyz="3.10E-05 1.90E-05 3.42E-02" rpy="${M_PI/2} 0 0"/>
132+
<origin xyz="3.10E-05 1.90E-05 3.42E-02" rpy="${radians(90)} 0 0"/>
133133
<inertia ixx="1.68E-04" ixy="2.05E-08" ixz="-4.00E-07"
134134
iyy="9.62E-05" iyz="6.24E-08"
135135
izz="1.34E-04"/>
@@ -146,7 +146,7 @@
146146
<!-- crane_x7_link_cover_2_l -->
147147
<link name="${NAME_LINK_COVER_2_L}">
148148
<visual>
149-
<origin xyz="0 0 0" rpy="-${M_PI/2} 0 0"/>
149+
<origin xyz="0 0 0" rpy="${radians(-90)} 0 0"/>
150150
<geometry>
151151
<mesh filename="package://crane_x7_description/meshes/visual/joint_cover.stl"
152152
scale="1 1 1"/>
@@ -155,7 +155,7 @@
155155
</visual>
156156

157157
<collision>
158-
<origin xyz="0 0 0" rpy="-${M_PI/2} 0 0"/>
158+
<origin xyz="0 0 0" rpy="${radians(-90)} 0 0"/>
159159
<geometry>
160160
<mesh filename="package://crane_x7_description/meshes/visual/joint_cover.stl"
161161
scale="1 1 1"/>
@@ -173,7 +173,7 @@
173173
<!-- crane_x7_link_cover_2_r -->
174174
<link name="${NAME_LINK_COVER_2_R}">
175175
<visual>
176-
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
176+
<origin xyz="0 0 0" rpy="${radians(90)} 0 0"/>
177177
<geometry>
178178
<mesh filename="package://crane_x7_description/meshes/visual/joint_cover.stl"
179179
scale="1 1 1"/>
@@ -182,7 +182,7 @@
182182
</visual>
183183

184184
<collision>
185-
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
185+
<origin xyz="0 0 0" rpy="${radians(90)} 0 0"/>
186186
<geometry>
187187
<mesh filename="package://crane_x7_description/meshes/visual/joint_cover.stl"
188188
scale="1 1 1"/>
@@ -250,7 +250,7 @@
250250
<!-- crane_x7_link_4 -->
251251
<link name="${NAME_LINK_4}">
252252
<visual>
253-
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
253+
<origin xyz="0 0 0" rpy="${radians(90)} 0 0"/>
254254
<geometry>
255255
<mesh filename="package://crane_x7_description/meshes/visual/rotating_link_type_2_fixed_part.stl"
256256
scale="1 1 1"/>
@@ -259,7 +259,7 @@
259259
</visual>
260260

261261
<collision>
262-
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
262+
<origin xyz="0 0 0" rpy="${radians(90)} 0 0"/>
263263
<geometry>
264264
<mesh filename="package://crane_x7_description/meshes/collision/rotating_link_type_2_fixed_part.stl"
265265
scale="1 1 1"/>
@@ -268,7 +268,7 @@
268268

269269
<inertial>
270270
<mass value="0.222"/>
271-
<origin xyz="-9.39E-03 6.40E-05 8.04E-02" rpy="${M_PI/2} 0 0"/>
271+
<origin xyz="-9.39E-03 6.40E-05 8.04E-02" rpy="${radians(90)} 0 0"/>
272272
<inertia ixx="4.89E-04" ixy="-3.90E-06" ixz="8.29E-08"
273273
iyy="1.14E-04" iyz="2.82E-06"
274274
izz="5.03E-04"/>
@@ -285,7 +285,7 @@
285285
<!-- crane_x7_link_cover_4_l -->
286286
<link name="${NAME_LINK_COVER_4_L}">
287287
<visual>
288-
<origin xyz="0 0 0" rpy="-${M_PI/2} 0 0"/>
288+
<origin xyz="0 0 0" rpy="${radians(-90)} 0 0"/>
289289
<geometry>
290290
<mesh filename="package://crane_x7_description/meshes/visual/joint_cover.stl"
291291
scale="1 1 1"/>
@@ -294,7 +294,7 @@
294294
</visual>
295295

296296
<collision>
297-
<origin xyz="0 0 0" rpy="-${M_PI/2} 0 0"/>
297+
<origin xyz="0 0 0" rpy="${radians(-90)} 0 0"/>
298298
<geometry>
299299
<mesh filename="package://crane_x7_description/meshes/visual/joint_cover.stl"
300300
scale="1 1 1"/>
@@ -312,7 +312,7 @@
312312
<!-- crane_x7_link_cover_4_r -->
313313
<link name="${NAME_LINK_COVER_4_R}">
314314
<visual>
315-
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
315+
<origin xyz="0 0 0" rpy="${radians(90)} 0 0"/>
316316
<geometry>
317317
<mesh filename="package://crane_x7_description/meshes/visual/joint_cover.stl"
318318
scale="1 1 1"/>
@@ -321,7 +321,7 @@
321321
</visual>
322322

323323
<collision>
324-
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
324+
<origin xyz="0 0 0" rpy="${radians(90)} 0 0"/>
325325
<geometry>
326326
<mesh filename="package://crane_x7_description/meshes/visual/joint_cover.stl"
327327
scale="1 1 1"/>
@@ -393,7 +393,7 @@
393393
<!-- crane_x7_link_6 -->
394394
<link name="${NAME_LINK_6}">
395395
<visual>
396-
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
396+
<origin xyz="0 0 0" rpy="${radians(90)} 0 0"/>
397397
<geometry>
398398
<mesh filename="package://crane_x7_description/meshes/visual/wrist.stl"
399399
scale="1 1 1"/>
@@ -402,7 +402,7 @@
402402
</visual>
403403

404404
<collision>
405-
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
405+
<origin xyz="0 0 0" rpy="${radians(90)} 0 0"/>
406406
<geometry>
407407
<mesh filename="package://crane_x7_description/meshes/collision/wrist.stl"
408408
scale="1 1 1"/>
@@ -411,7 +411,7 @@
411411

412412
<inertial>
413413
<mass value="0.14"/>
414-
<origin xyz="6.10E-03 8.26E-04 -3.55E-03" rpy="${M_PI/2} 0 0"/>
414+
<origin xyz="6.10E-03 8.26E-04 -3.55E-03" rpy="${radians(90)} 0 0"/>
415415
<inertia ixx="4.01E-05" ixy="-2.91E-06" ixz="6.39E-07"
416416
iyy="6.13E-05" iyz="-4.90E-07"
417417
izz="7.35E-05"/>

urdf/crane_x7_rt_logos.xacro

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
<!-- Left side logo text -->
77
<link name="${NAME_LINK_LOGO_TEXT_L}">
88
<visual>
9-
<origin xyz="0 0 0" rpy="-${M_PI/2} ${M_PI/2} 0"/>
9+
<origin xyz="0 0 0" rpy="${radians(-90)} ${radians(90)} 0"/>
1010
<geometry>
1111
<mesh filename="package://crane_x7_description/meshes/visual/rtcorp_logo_name.stl"
1212
scale="1 1 1"/>
@@ -15,7 +15,7 @@
1515
</visual>
1616

1717
<collision>
18-
<origin xyz="0 0 0" rpy="-${M_PI/2} ${M_PI/2} 0"/>
18+
<origin xyz="0 0 0" rpy="${radians(-90)} ${radians(90)} 0"/>
1919
<geometry>
2020
<mesh filename="package://crane_x7_description/meshes/visual/rtcorp_logo_name.stl"
2121
scale="1 1 1"/>
@@ -31,7 +31,7 @@
3131
<!-- Left side logo symbol -->
3232
<link name="${NAME_LINK_LOGO_SYMBOL_L}">
3333
<visual>
34-
<origin xyz="0 0 0" rpy="-${M_PI/2} ${M_PI/2} 0"/>
34+
<origin xyz="0 0 0" rpy="${radians(-90)} ${radians(90)} 0"/>
3535
<geometry>
3636
<mesh filename="package://crane_x7_description/meshes/visual/rtcorp_logo_rabbit.stl"
3737
scale="1 1 1"/>
@@ -40,7 +40,7 @@
4040
</visual>
4141

4242
<collision>
43-
<origin xyz="0 0 0" rpy="-${M_PI/2} ${M_PI/2} 0"/>
43+
<origin xyz="0 0 0" rpy="${radians(-90)} ${radians(90)} 0"/>
4444
<geometry>
4545
<mesh filename="package://crane_x7_description/meshes/visual/rtcorp_logo_rabbit.stl"
4646
scale="1 1 1"/>
@@ -56,7 +56,7 @@
5656
<!-- Right side logo text -->
5757
<link name="${NAME_LINK_LOGO_TEXT_R}">
5858
<visual>
59-
<origin xyz="0 0 0" rpy="${M_PI/2} -${M_PI/2} 0"/>
59+
<origin xyz="0 0 0" rpy="${radians(90)} ${radians(-90)} 0"/>
6060
<geometry>
6161
<mesh filename="package://crane_x7_description/meshes/visual/rtcorp_logo_name.stl"
6262
scale="1 1 1"/>
@@ -65,7 +65,7 @@
6565
</visual>
6666

6767
<collision>
68-
<origin xyz="0 0 0" rpy="${M_PI/2} -${M_PI/2} 0"/>
68+
<origin xyz="0 0 0" rpy="${radians(90)} ${radians(-90)} 0"/>
6969
<geometry>
7070
<mesh filename="package://crane_x7_description/meshes/visual/rtcorp_logo_name.stl"
7171
scale="1 1 1"/>
@@ -81,7 +81,7 @@
8181
<!-- Right side logo symbol -->
8282
<link name="${NAME_LINK_LOGO_SYMBOL_R}">
8383
<visual>
84-
<origin xyz="0 0 0" rpy="${M_PI/2} -${M_PI/2} 0"/>
84+
<origin xyz="0 0 0" rpy="${radians(90)} ${radians(-90)} 0"/>
8585
<geometry>
8686
<mesh filename="package://crane_x7_description/meshes/visual/rtcorp_logo_rabbit.stl"
8787
scale="1 1 1"/>
@@ -90,7 +90,7 @@
9090
</visual>
9191

9292
<collision>
93-
<origin xyz="0 0 0" rpy="${M_PI/2} -${M_PI/2} 0"/>
93+
<origin xyz="0 0 0" rpy="${radians(90)} ${radians(-90)} 0"/>
9494
<geometry>
9595
<mesh filename="package://crane_x7_description/meshes/visual/rtcorp_logo_rabbit.stl"
9696
scale="1 1 1"/>

urdf/crane_x7_wide_two_finger_gripper.xacro

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@
4545

4646
<link name="${NAME_LINK_GRIPPER_FINGER_A}">
4747
<visual>
48-
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
48+
<origin xyz="0 0 0" rpy="${radians(90)} 0 0"/>
4949
<geometry>
5050
<mesh filename="package://crane_x7_description/meshes/visual/wide_two_finger_gripper_finger_a.stl"
5151
scale="1 1 1"/>
@@ -54,7 +54,7 @@
5454
</visual>
5555

5656
<collision>
57-
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
57+
<origin xyz="0 0 0" rpy="${radians(90)} 0 0"/>
5858
<geometry>
5959
<mesh filename="package://crane_x7_description/meshes/collision/wide_two_finger_gripper_finger_a.stl"
6060
scale="1 1 1"/>
@@ -63,7 +63,7 @@
6363

6464
<inertial>
6565
<mass value="0.0158"/>
66-
<origin xyz="-2.65E-03 3.54E-03 2.69E-02" rpy="${M_PI/2} 0 0"/>
66+
<origin xyz="-2.65E-03 3.54E-03 2.69E-02" rpy="${radians(90)} 0 0"/>
6767
<inertia ixx="1.01E-05" ixy="-1.97E-07" ixz="-9.89E-08"
6868
iyy="4.95E-06" iyz="5.37E-07"
6969
izz="6.24E-06"/>
@@ -96,7 +96,7 @@
9696

9797
<link name="${NAME_LINK_GRIPPER_FINGER_B}">
9898
<visual>
99-
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
99+
<origin xyz="0 0 0" rpy="${radians(90)} 0 0"/>
100100
<geometry>
101101
<mesh filename="package://crane_x7_description/meshes/visual/wide_two_finger_gripper_finger_b.stl"
102102
scale="1 1 1"/>
@@ -105,7 +105,7 @@
105105
</visual>
106106

107107
<collision>
108-
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
108+
<origin xyz="0 0 0" rpy="${radians(90)} 0 0"/>
109109
<geometry>
110110
<mesh filename="package://crane_x7_description/meshes/collision/wide_two_finger_gripper_finger_b.stl"
111111
scale="1 1 1"/>
@@ -114,7 +114,7 @@
114114

115115
<inertial>
116116
<mass value="0.0139"/>
117-
<origin xyz="3.01E-03 2.85E-03 3.09E-02" rpy="${M_PI/2} 0 0"/>
117+
<origin xyz="3.01E-03 2.85E-03 3.09E-02" rpy="${radians(90)} 0 0"/>
118118
<inertia ixx="7.48E-06" ixy="3.61E-07" ixz="6.34E-08"
119119
iyy="4.09E-06" iyz="2.28E-07"
120120
izz="4.37E-06"/>

0 commit comments

Comments
 (0)