Skip to content

Conversation

URJala
Copy link
Collaborator

@URJala URJala commented Sep 18, 2024

This is related to #174.
The URDF now reflects the possibility of using the infinite wrist on the UR3(e), but can also still be configured to have limits via the limits file.

Comment on lines 78 to 79
<xacro:property name="config_joint_limit_parameters" value="${xacro.load_yaml(joint_limits_parameters_file)}"/>
<xacro:property name="sec_limits" value="${config_joint_limit_parameters['joint_limits']}"/>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We can probably get around this by putting the parsed values into the parent scope in ur_common.xacro

Comment on lines 284 to 310
<xacro:if value="${sec_limits['wrist_3_joint']['has_position_limits']}">
<joint name="${tf_prefix}wrist_3_joint" type="revolute">
<parent link="${tf_prefix}wrist_2_link" />
<child link="${tf_prefix}wrist_3_link" />
<origin xyz="${wrist_3_x} ${wrist_3_y} ${wrist_3_z}" rpy="${wrist_3_roll} ${wrist_3_pitch} ${wrist_3_yaw}" />
<axis xyz="0 0 1" />
<limit lower="${wrist_3_lower_limit}" upper="${wrist_3_upper_limit}"
effort="${wrist_3_effort_limit}" velocity="${wrist_3_velocity_limit}"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${wrist_3_lower_limit + safety_pos_margin}" soft_upper_limit="${wrist_3_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
</joint>
</xacro:if>
<xacro:unless value="${sec_limits['wrist_3_joint']['has_position_limits']}">
<joint name="${tf_prefix}wrist_3_joint" type="continuous">
<parent link="${tf_prefix}wrist_2_link" />
<child link="${tf_prefix}wrist_3_link" />
<origin xyz="${wrist_3_x} ${wrist_3_y} ${wrist_3_z}" rpy="${wrist_3_roll} ${wrist_3_pitch} ${wrist_3_yaw}" />
<axis xyz="0 0 1" />
<limit effort="${wrist_3_effort_limit}" velocity="${wrist_3_velocity_limit}"/>
<xacro:if value="${safety_limits}">
<safety_controller k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
</joint>
</xacro:unless>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think, this can be written a bit neater:

  • We could specify the joint_type, e.g. in ur_common as wrist_3_joint_type
  • We could put a <xacro:if value="${wrist_3_joint_type} != continuous"> around the limit tag only.

IMHO this would reduce code duplication while also improving readability.

Copy link
Contributor

@fmauch fmauch left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is looking good, thank you very much!

@fmauch fmauch merged commit 352a35c into UniversalRobots:rolling Sep 25, 2024
8 checks passed
mergify bot pushed a commit that referenced this pull request Sep 25, 2024
Change URDF to reflect ur3(e)'s infinite wrist 3 joint

(cherry picked from commit 352a35c)
mergify bot pushed a commit that referenced this pull request Sep 25, 2024
Change URDF to reflect ur3(e)'s infinite wrist 3 joint

(cherry picked from commit 352a35c)
fmauch pushed a commit that referenced this pull request Sep 26, 2024
fmauch pushed a commit that referenced this pull request Sep 26, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants