Skip to content

Commit

Permalink
Merge pull request #320 from gavanderhoorn/bp_268_indigo-devel
Browse files Browse the repository at this point in the history
Backport #268 to Indigo
  • Loading branch information
gavanderhoorn authored Sep 12, 2017
2 parents 68d76b2 + eb12019 commit 2e078f5
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 3 deletions.
2 changes: 1 addition & 1 deletion ur_description/urdf/ur10.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,7 @@
<origin xyz="0.0 ${elbow_offset} ${upper_arm_length}" rpy="0.0 0.0 0.0" />
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="150.0" velocity="3.15"/>
<limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="3.15"/>
</xacro:unless>
<xacro:if value="${joint_limited}">
<limit lower="${elbow_joint_lower_limit}" upper="${elbow_joint_upper_limit}" effort="150.0" velocity="3.15"/>
Expand Down
2 changes: 1 addition & 1 deletion ur_description/urdf/ur3.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -155,7 +155,7 @@
<origin xyz="0.0 ${elbow_offset} ${upper_arm_length}" rpy="0.0 0.0 0.0" />
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="150.0" velocity="3.15"/>
<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"/>
Expand Down
2 changes: 1 addition & 1 deletion ur_description/urdf/ur5.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,7 @@
<origin xyz="0.0 ${elbow_offset} ${upper_arm_length}" rpy="0.0 0.0 0.0" />
<axis xyz="0 1 0" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="150.0" velocity="3.15"/>
<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"/>
Expand Down

0 comments on commit 2e078f5

Please sign in to comment.