From c3652a10ee26b1ad9d45afd68f29b1b8fc60a554 Mon Sep 17 00:00:00 2001 From: Robert Haschke <rhaschke@techfak.uni-bielefeld.de> Date: Thu, 1 Sep 2022 13:35:16 +0200 Subject: [PATCH] Drop link8 from ACM as this link doesn't have any collision model anymore --- config/arm.xacro | 7 ++----- config/hand.xacro | 4 ++-- 2 files changed, 4 insertions(+), 7 deletions(-) diff --git a/config/arm.xacro b/config/arm.xacro index ea345aa..fef366a 100644 --- a/config/arm.xacro +++ b/config/arm.xacro @@ -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> @@ -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> diff --git a/config/hand.xacro b/config/hand.xacro index 8c78a14..47a06b6 100644 --- a/config/hand.xacro +++ b/config/hand.xacro @@ -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" /> -- GitLab