Skip to content

Commit

Permalink
プランニングできるように可動範囲を微調整
Browse files Browse the repository at this point in the history
  • Loading branch information
chama1176 committed Jul 9, 2024
1 parent b9329bd commit 27f0d43
Showing 1 changed file with 4 additions and 2 deletions.
6 changes: 4 additions & 2 deletions urdf/sciurus17.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,8 @@

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

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

0 comments on commit 27f0d43

Please sign in to comment.