Skip to content

Commit

Permalink
Merge pull request #329 from tecnalia-medical-robotics/joint_limits
Browse files Browse the repository at this point in the history
Homogenize xacro macro arguments.
  • Loading branch information
fmessmer authored Jan 6, 2018
2 parents 7568098 + a2d01d4 commit 0a35a5a
Show file tree
Hide file tree
Showing 4 changed files with 42 additions and 16 deletions.
20 changes: 13 additions & 7 deletions ur_description/urdf/ur3.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,13 @@
</xacro:macro>


<xacro:macro name="ur3_robot" params="prefix joint_limited">
<xacro:macro name="ur3_robot" params="prefix joint_limited
shoulder_pan_lower_limit:=${-pi} shoulder_pan_upper_limit:=${pi}
shoulder_lift_lower_limit:=${-pi} shoulder_lift_upper_limit:=${pi}
elbow_joint_lower_limit:=${-pi} elbow_joint_upper_limit:=${pi}
wrist_1_lower_limit:=${-pi} wrist_1_upper_limit:=${pi}
wrist_2_lower_limit:=${-pi} wrist_2_upper_limit:=${pi}
wrist_3_lower_limit:=${-pi} wrist_3_upper_limit:=${pi}">

<link name="${prefix}base_link" >
<visual>
Expand Down Expand Up @@ -90,7 +96,7 @@
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="330.0" velocity="2.16"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${-pi}" upper="${pi}" effort="330.0" velocity="2.16"/>
<limit lower="${shoulder_pan_lower_limit}" upper="${shoulder_pan_upper_limit}" effort="330.0" velocity="2.16"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
Expand Down Expand Up @@ -123,7 +129,7 @@
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="330.0" velocity="2.16"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${-pi}" upper="${pi}" effort="330.0" velocity="2.16"/>
<limit lower="${shoulder_lift_lower_limit}" upper="${shoulder_lift_upper_limit}" effort="330.0" velocity="2.16"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
Expand Down Expand Up @@ -156,7 +162,7 @@
<limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="3.15"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="3.15"/>
<limit lower="${elbow_joint_lower_limit}" upper="${elbow_joint_upper_limit}" effort="150.0" velocity="3.15"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
Expand Down Expand Up @@ -189,7 +195,7 @@
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="3.2"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${-pi}" upper="${pi}" effort="54.0" velocity="3.2"/>
<limit lower="${wrist_1_lower_limit}" upper="${wrist_1_upper_limit}" effort="54.0" velocity="3.2"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
Expand Down Expand Up @@ -222,7 +228,7 @@
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="3.2"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${-pi}" upper="${pi}" effort="54.0" velocity="3.2"/>
<limit lower="${wrist_2_lower_limit}" upper="${wrist_2_upper_limit}" effort="54.0" velocity="3.2"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
Expand Down Expand Up @@ -255,7 +261,7 @@
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="54.0" velocity="3.2"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${-pi}" upper="${pi}" effort="54.0" velocity="3.2"/>
<limit lower="${wrist_3_lower_limit}" upper="${wrist_3_upper_limit}" effort="54.0" velocity="3.2"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
Expand Down
9 changes: 8 additions & 1 deletion ur_description/urdf/ur3_joint_limited_robot.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,14 @@
<xacro:include filename="$(find ur_description)/urdf/ur3.urdf.xacro" />

<!-- arm -->
<xacro:ur3_robot prefix="" joint_limited="true"/>
<xacro:ur3_robot prefix="" joint_limited="true"
shoulder_pan_lower_limit="${-pi}" shoulder_pan_upper_limit="${pi}"
shoulder_lift_lower_limit="${-pi}" shoulder_lift_upper_limit="${pi}"
elbow_joint_lower_limit="${-pi}" elbow_joint_upper_limit="${pi}"
wrist_1_lower_limit="${-pi}" wrist_1_upper_limit="${pi}"
wrist_2_lower_limit="${-pi}" wrist_2_upper_limit="${pi}"
wrist_3_lower_limit="${-pi}" wrist_3_upper_limit="${pi}"
/>

<link name="world" />

Expand Down
20 changes: 13 additions & 7 deletions ur_description/urdf/ur5.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,13 @@
</xacro:macro>


<xacro:macro name="ur5_robot" params="prefix joint_limited">
<xacro:macro name="ur5_robot" params="prefix joint_limited
shoulder_pan_lower_limit:=${-pi} shoulder_pan_upper_limit:=${pi}
shoulder_lift_lower_limit:=${-pi} shoulder_lift_upper_limit:=${pi}
elbow_joint_lower_limit:=${-pi} elbow_joint_upper_limit:=${pi}
wrist_1_lower_limit:=${-pi} wrist_1_upper_limit:=${pi}
wrist_2_lower_limit:=${-pi} wrist_2_upper_limit:=${pi}
wrist_3_lower_limit:=${-pi} wrist_3_upper_limit:=${pi}">

<link name="${prefix}base_link" >
<visual>
Expand Down Expand Up @@ -106,7 +112,7 @@
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="150.0" velocity="3.15"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="3.15"/>
<limit lower="${shoulder_pan_lower_limit}" upper="${shoulder_pan_upper_limit}" effort="150.0" velocity="3.15"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
Expand Down Expand Up @@ -139,7 +145,7 @@
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="150.0" velocity="3.15"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="3.15"/>
<limit lower="${shoulder_lift_lower_limit}" upper="${shoulder_lift_upper_limit}" effort="150.0" velocity="3.15"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
Expand Down Expand Up @@ -172,7 +178,7 @@
<limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="3.15"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="3.15"/>
<limit lower="${elbow_joint_lower_limit}" upper="${elbow_joint_upper_limit}" effort="150.0" velocity="3.15"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
Expand Down Expand Up @@ -205,7 +211,7 @@
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="28.0" velocity="3.2"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${-pi}" upper="${pi}" effort="28.0" velocity="3.2"/>
<limit lower="${wrist_1_lower_limit}" upper="${wrist_1_upper_limit}" effort="28.0" velocity="3.2"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
Expand Down Expand Up @@ -238,7 +244,7 @@
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="28.0" velocity="3.2"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${-pi}" upper="${pi}" effort="28.0" velocity="3.2"/>
<limit lower="${wrist_2_lower_limit}" upper="${wrist_2_upper_limit}" effort="28.0" velocity="3.2"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
Expand Down Expand Up @@ -271,7 +277,7 @@
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="28.0" velocity="3.2"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${-pi}" upper="${pi}" effort="28.0" velocity="3.2"/>
<limit lower="${wrist_3_lower_limit}" upper="${wrist_3_upper_limit}" effort="28.0" velocity="3.2"/>
</xacro:if>
<dynamics damping="0.0" friction="0.0"/>
</joint>
Expand Down
9 changes: 8 additions & 1 deletion ur_description/urdf/ur5_joint_limited_robot.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,14 @@
<xacro:include filename="$(find ur_description)/urdf/ur5.urdf.xacro" />

<!-- arm -->
<xacro:ur5_robot prefix="" joint_limited="true"/>
<xacro:ur5_robot prefix="" joint_limited="true"
shoulder_pan_lower_limit="${-pi}" shoulder_pan_upper_limit="${pi}"
shoulder_lift_lower_limit="${-pi}" shoulder_lift_upper_limit="${pi}"
elbow_joint_lower_limit="${-pi}" elbow_joint_upper_limit="${pi}"
wrist_1_lower_limit="${-pi}" wrist_1_upper_limit="${pi}"
wrist_2_lower_limit="${-pi}" wrist_2_upper_limit="${pi}"
wrist_3_lower_limit="${-pi}" wrist_3_upper_limit="${pi}"
/>

<link name="world" />

Expand Down

0 comments on commit 0a35a5a

Please sign in to comment.