Skip to content

Commit cfdf254

Browse files
committed
手首の可動範囲を広げる
1 parent 24845ae commit cfdf254

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
@@ -132,7 +132,8 @@
132132
<xacro:property name="JOINT_ARM_R_4_UPPER_LIMIT" value="${radians(157)}"/>
133133
<xacro:property name="JOINT_ARM_R_5_LOWER_LIMIT" value="${radians(-90)}"/>
134134
<xacro:property name="JOINT_ARM_R_5_UPPER_LIMIT" value="${radians(90)}"/>
135-
<xacro:property name="JOINT_ARM_R_6_LOWER_LIMIT" value="${radians(-120)}"/>
135+
<!-- 初期角度が範囲外だとプランニングで失敗するため範囲を広げる -->
136+
<xacro:property name="JOINT_ARM_R_6_LOWER_LIMIT" value="${radians(-123)}"/>
136137
<xacro:property name="JOINT_ARM_R_6_UPPER_LIMIT" value="${radians(60)}"/>
137138
<xacro:property name="JOINT_ARM_R_7_LOWER_LIMIT" value="${radians(-170)}"/>
138139
<xacro:property name="JOINT_ARM_R_7_UPPER_LIMIT" value="${radians(170)}"/>
@@ -155,7 +156,8 @@
155156
<xacro:property name="JOINT_ARM_L_5_LOWER_LIMIT" value="${radians(-90)}"/>
156157
<xacro:property name="JOINT_ARM_L_5_UPPER_LIMIT" value="${radians(90)}"/>
157158
<xacro:property name="JOINT_ARM_L_6_LOWER_LIMIT" value="${radians(-60)}"/>
158-
<xacro:property name="JOINT_ARM_L_6_UPPER_LIMIT" value="${radians(120)}"/>
159+
<!-- 初期角度が範囲外だとプランニングで失敗するため範囲を広げる -->
160+
<xacro:property name="JOINT_ARM_L_6_UPPER_LIMIT" value="${radians(123)}"/>
159161
<xacro:property name="JOINT_ARM_L_7_LOWER_LIMIT" value="${radians(-170)}"/>
160162
<xacro:property name="JOINT_ARM_L_7_UPPER_LIMIT" value="${radians(170)}"/>
161163
<xacro:property name="JOINT_GRIPPER_L_LOWER_LIMIT" value="${radians(-86)}"/>

0 commit comments

Comments
 (0)