Skip to content

Commit 352a35c

Browse files
authored
Ur3 infinite wrist (#196)
Change URDF to reflect ur3(e)'s infinite wrist 3 joint
1 parent 60e6974 commit 352a35c

File tree

4 files changed

+23
-13
lines changed

4 files changed

+23
-13
lines changed

config/ur3/joint_limits.yaml

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -72,9 +72,7 @@ joint_limits:
7272
# acceleration limits are not publicly available
7373
has_acceleration_limits: false
7474
has_effort_limits: true
75-
has_position_limits: true
75+
has_position_limits: false
7676
has_velocity_limits: true
7777
max_effort: 12.0
78-
max_position: !degrees 360.0
7978
max_velocity: !degrees 360.0
80-
min_position: !degrees -360.0

config/ur3e/joint_limits.yaml

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -72,9 +72,7 @@ joint_limits:
7272
# acceleration limits are not publicly available
7373
has_acceleration_limits: false
7474
has_effort_limits: true
75-
has_position_limits: true
75+
has_position_limits: false
7676
has_velocity_limits: true
7777
max_effort: 9.0
78-
max_position: !degrees 360.0
7978
max_velocity: !degrees 360.0
80-
min_position: !degrees -360.0

urdf/inc/ur_common.xacro

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -78,8 +78,14 @@
7878
<xacro:property name="wrist_2_upper_limit" value="${sec_limits['wrist_2_joint']['max_position']}" scope="parent"/>
7979
<xacro:property name="wrist_2_velocity_limit" value="${sec_limits['wrist_2_joint']['max_velocity']}" scope="parent"/>
8080
<xacro:property name="wrist_2_effort_limit" value="${sec_limits['wrist_2_joint']['max_effort']}" scope="parent"/>
81-
<xacro:property name="wrist_3_lower_limit" value="${sec_limits['wrist_3_joint']['min_position']}" scope="parent"/>
82-
<xacro:property name="wrist_3_upper_limit" value="${sec_limits['wrist_3_joint']['max_position']}" scope="parent"/>
81+
<xacro:if value="${sec_limits['wrist_3_joint']['has_position_limits']}">
82+
<xacro:property name="wrist_3_joint_type" value="revolute" scope="parent"/>
83+
<xacro:property name="wrist_3_lower_limit" value="${sec_limits['wrist_3_joint']['min_position']}" scope="parent"/>
84+
<xacro:property name="wrist_3_upper_limit" value="${sec_limits['wrist_3_joint']['max_position']}" scope="parent"/>
85+
</xacro:if>
86+
<xacro:unless value="${sec_limits['wrist_3_joint']['has_position_limits']}">
87+
<xacro:property name="wrist_3_joint_type" value="continuous" scope="parent"/>
88+
</xacro:unless>
8389
<xacro:property name="wrist_3_velocity_limit" value="${sec_limits['wrist_3_joint']['max_velocity']}" scope="parent"/>
8490
<xacro:property name="wrist_3_effort_limit" value="${sec_limits['wrist_3_joint']['max_effort']}" scope="parent"/>
8591

urdf/ur_macro.xacro

Lines changed: 13 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -331,16 +331,24 @@
331331
</xacro:if>
332332
<dynamics damping="0" friction="0"/>
333333
</joint>
334-
<joint name="${tf_prefix}wrist_3_joint" type="revolute">
334+
<joint name="${tf_prefix}wrist_3_joint" type="${wrist_3_joint_type}">
335335
<parent link="${tf_prefix}wrist_2_link" />
336336
<child link="${tf_prefix}wrist_3_link" />
337337
<origin xyz="${wrist_3_x} ${wrist_3_y} ${wrist_3_z}" rpy="${wrist_3_roll} ${wrist_3_pitch} ${wrist_3_yaw}" />
338338
<axis xyz="0 0 1" />
339-
<limit lower="${wrist_3_lower_limit}" upper="${wrist_3_upper_limit}"
340-
effort="${wrist_3_effort_limit}" velocity="${wrist_3_velocity_limit}"/>
341-
<xacro:if value="${safety_limits}">
342-
<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"/>
339+
<xacro:if value="${wrist_3_joint_type != 'continuous'}">
340+
<limit lower="${wrist_3_lower_limit}" upper="${wrist_3_upper_limit}"
341+
effort="${wrist_3_effort_limit}" velocity="${wrist_3_velocity_limit}"/>
342+
<xacro:if value="${safety_limits}">
343+
<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"/>
344+
</xacro:if>
343345
</xacro:if>
346+
<xacro:unless value="${wrist_3_joint_type != 'continuous'}">
347+
<limit effort="${wrist_3_effort_limit}" velocity="${wrist_3_velocity_limit}"/>
348+
<xacro:if value="${safety_limits}">
349+
<safety_controller k_position="${safety_k_position}" k_velocity="0.0"/>
350+
</xacro:if>
351+
</xacro:unless>
344352
<dynamics damping="0" friction="0"/>
345353
</joint>
346354

0 commit comments

Comments
 (0)