Skip to content

Commit

Permalink
Ur3 infinite wrist (backport of #196)
Browse files Browse the repository at this point in the history
  • Loading branch information
mergify[bot] authored Sep 26, 2024
1 parent b915c2a commit 7f06077
Show file tree
Hide file tree
Showing 4 changed files with 23 additions and 13 deletions.
4 changes: 1 addition & 3 deletions config/ur3/joint_limits.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -72,9 +72,7 @@ joint_limits:
# acceleration limits are not publicly available
has_acceleration_limits: false
has_effort_limits: true
has_position_limits: true
has_position_limits: false
has_velocity_limits: true
max_effort: 12.0
max_position: !degrees 360.0
max_velocity: !degrees 360.0
min_position: !degrees -360.0
4 changes: 1 addition & 3 deletions config/ur3e/joint_limits.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -72,9 +72,7 @@ joint_limits:
# acceleration limits are not publicly available
has_acceleration_limits: false
has_effort_limits: true
has_position_limits: true
has_position_limits: false
has_velocity_limits: true
max_effort: 9.0
max_position: !degrees 360.0
max_velocity: !degrees 360.0
min_position: !degrees -360.0
10 changes: 8 additions & 2 deletions urdf/inc/ur_common.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -78,8 +78,14 @@
<xacro:property name="wrist_2_upper_limit" value="${sec_limits['wrist_2_joint']['max_position']}" scope="parent"/>
<xacro:property name="wrist_2_velocity_limit" value="${sec_limits['wrist_2_joint']['max_velocity']}" scope="parent"/>
<xacro:property name="wrist_2_effort_limit" value="${sec_limits['wrist_2_joint']['max_effort']}" scope="parent"/>
<xacro:property name="wrist_3_lower_limit" value="${sec_limits['wrist_3_joint']['min_position']}" scope="parent"/>
<xacro:property name="wrist_3_upper_limit" value="${sec_limits['wrist_3_joint']['max_position']}" scope="parent"/>
<xacro:if value="${sec_limits['wrist_3_joint']['has_position_limits']}">
<xacro:property name="wrist_3_joint_type" value="revolute" scope="parent"/>
<xacro:property name="wrist_3_lower_limit" value="${sec_limits['wrist_3_joint']['min_position']}" scope="parent"/>
<xacro:property name="wrist_3_upper_limit" value="${sec_limits['wrist_3_joint']['max_position']}" scope="parent"/>
</xacro:if>
<xacro:unless value="${sec_limits['wrist_3_joint']['has_position_limits']}">
<xacro:property name="wrist_3_joint_type" value="continuous" scope="parent"/>
</xacro:unless>
<xacro:property name="wrist_3_velocity_limit" value="${sec_limits['wrist_3_joint']['max_velocity']}" scope="parent"/>
<xacro:property name="wrist_3_effort_limit" value="${sec_limits['wrist_3_joint']['max_effort']}" scope="parent"/>

Expand Down
18 changes: 13 additions & 5 deletions urdf/ur_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -402,16 +402,24 @@
</xacro:if>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="${tf_prefix}wrist_3_joint" type="revolute">
<joint name="${tf_prefix}wrist_3_joint" type="${wrist_3_joint_type}">
<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 value="${wrist_3_joint_type != 'continuous'}">
<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>
</xacro:if>
<xacro:unless value="${wrist_3_joint_type != 'continuous'}">
<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>
</xacro:unless>
<dynamics damping="0" friction="0"/>
</joint>

Expand Down

0 comments on commit 7f06077

Please sign in to comment.