Skip to content

Commit 27f0d43

Browse files
committed
プランニングできるように可動範囲を微調整
1 parent b9329bd commit 27f0d43

File tree

1 file changed

+4
-2
lines changed

1 file changed

+4
-2
lines changed

urdf/sciurus17.urdf.xacro

+4-2
Original file line numberDiff line numberDiff line change
@@ -121,7 +121,8 @@
121121

122122
<xacro:property name="JOINT_ARM_R_1_LOWER_LIMIT" value="${radians(-90)}"/>
123123
<xacro:property name="JOINT_ARM_R_1_UPPER_LIMIT" value="${radians(90)}"/>
124-
<xacro:property name="JOINT_ARM_R_2_LOWER_LIMIT" value="${radians(-90)}"/>
124+
<!-- 初期角度が範囲外だとプランニングで失敗するため範囲を広げる -->
125+
<xacro:property name="JOINT_ARM_R_2_LOWER_LIMIT" value="${radians(-92)}"/>
125126
<xacro:property name="JOINT_ARM_R_2_UPPER_LIMIT" value="${radians(0)}"/>
126127
<xacro:property name="JOINT_ARM_R_3_LOWER_LIMIT" value="${radians(-90)}"/>
127128
<xacro:property name="JOINT_ARM_R_3_UPPER_LIMIT" value="${radians(90)}"/>
@@ -142,8 +143,9 @@
142143

143144
<xacro:property name="JOINT_ARM_L_1_LOWER_LIMIT" value="${radians(-90)}"/>
144145
<xacro:property name="JOINT_ARM_L_1_UPPER_LIMIT" value="${radians(90)}"/>
146+
<!-- 初期角度が範囲外だとプランニングで失敗するため範囲を広げる -->
145147
<xacro:property name="JOINT_ARM_L_2_LOWER_LIMIT" value="${radians(0)}"/>
146-
<xacro:property name="JOINT_ARM_L_2_UPPER_LIMIT" value="${radians(90)}"/>
148+
<xacro:property name="JOINT_ARM_L_2_UPPER_LIMIT" value="${radians(92)}"/>
147149
<xacro:property name="JOINT_ARM_L_3_LOWER_LIMIT" value="${radians(-90)}"/>
148150
<xacro:property name="JOINT_ARM_L_3_UPPER_LIMIT" value="${radians(90)}"/>
149151
<xacro:property name="JOINT_ARM_L_4_LOWER_LIMIT" value="${radians(-157)}"/>

0 commit comments

Comments
 (0)