Skip to content

Commit

Permalink
Drop link8 from ACM
Browse files Browse the repository at this point in the history
as this link doesn't have any collision model anymore
  • Loading branch information
rhaschke committed Sep 1, 2022
1 parent adff2fd commit c3652a1
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 7 deletions.
7 changes: 2 additions & 5 deletions config/arm.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -52,13 +52,11 @@
<xacro:macro name="configure_collisions" params="link enabled:=${[]}">
<!-- Disable collision checking between normal links, as these are handled by "sc" links -->
<xacro:property name="link_fmt" value="$(arg arm_id)_link{}" />
<xacro:disable_collisions_for link="${link_fmt.format(link)}" others="${[link_fmt.format(i) for i in python.range(9)]}" />
<xacro:disable_collisions_for link="${link_fmt.format(link)}" others="${[link_fmt.format(i) for i in python.range(8)]}" />

<!-- Disable all collision checking for ${link}_sc -->
<xacro:property name="link_fmt" value="$(arg arm_id)_link{}_sc" />
<xacro:if value="${link != 8}">
<disable_default_collisions link="${link_fmt.format(link)}" />
</xacro:if>
<disable_default_collisions link="${link_fmt.format(link)}" />
<!-- Re-enable collisions checking for selected links -->
<xacro:enable_collisions_for link="${link_fmt.format(link)}" others="${[link_fmt.format(i) for i in enabled]}" />
</xacro:macro>
Expand All @@ -72,5 +70,4 @@
<xacro:configure_collisions link="5" />
<xacro:configure_collisions link="6" />
<xacro:configure_collisions link="7" />
<xacro:configure_collisions link="8" />
</robot>
4 changes: 2 additions & 2 deletions config/hand.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -31,9 +31,9 @@
<xacro:enable_collisions_for link="$(arg arm_id)_hand_sc" others="${[link_fmt.format(i) for i in [0,1,2,3]]}" />
<!-- Disable collision of hand link with all arm links. These are handled by the *_sc links -->
<xacro:property name="link_fmt" value="$(arg arm_id)_link{}" />
<xacro:disable_collisions_for link="$(arg arm_id)_hand" others="${[link_fmt.format(i) for i in python.range(9)]}" />
<xacro:disable_collisions_for link="$(arg arm_id)_hand" others="${[link_fmt.format(i) for i in python.range(8)]}" />
<!-- Disable collision of fingers with all arm links -->
<xacro:property name="others" value="${[link_fmt.format(i) for i in python.range(9)] + [xacro.arg('arm_id') + '_hand']}" />
<xacro:property name="others" value="${[link_fmt.format(i) for i in python.range(8)] + [xacro.arg('arm_id') + '_hand']}" />
<xacro:disable_collisions_for link="$(arg arm_id)_leftfinger" others="${list(others)}" />
<xacro:disable_collisions_for link="$(arg arm_id)_rightfinger" others="${list(others)}" />
<disable_collisions link1="$(arg arm_id)_leftfinger" link2="$(arg arm_id)_rightfinger" reason="Never" />
Expand Down

0 comments on commit c3652a1

Please sign in to comment.