From b645ff68d75e571be859721aa376930dac9821c7 Mon Sep 17 00:00:00 2001 From: Robert Haschke <rhaschke@techfak.uni-bielefeld.de> Date: Tue, 28 Dec 2021 18:49:08 +0100 Subject: [PATCH] Rename tag collision_default -> disable_default_collisions --- config/arm.xacro | 2 +- config/hand.xacro | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/config/arm.xacro b/config/arm.xacro index f6827f1..7a07faf 100644 --- a/config/arm.xacro +++ b/config/arm.xacro @@ -35,7 +35,7 @@ <xacro:macro name="collision" params="link"> <!-- Enable (environmental) collisions of ${link}_sc --> - <collision_default link="${link}_sc" allow="ALWAYS" /> + <disable_default_collisions link="${link}_sc" /> <!-- Disable collisions of link with any other arm link, as these are handled by the "sc" links --> <disable_collisions link1="${link}" link2="panda_link0" reason="Default" /> <disable_collisions link1="${link}" link2="panda_link1" reason="Default" /> diff --git a/config/hand.xacro b/config/hand.xacro index 3f1e608..cd85940 100644 --- a/config/hand.xacro +++ b/config/hand.xacro @@ -39,7 +39,7 @@ <!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)--> <!--PASSIVE JOINT: Purpose: this element is used to mark joints that are not actuated--> <!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. --> - <collision_default link="panda_hand_sc" allow="ALWAYS" /> + <disable_default_collisions link="panda_hand_sc" /> <enable_collisions link1="panda_hand_sc" link2="panda_link0" /> <enable_collisions link1="panda_hand_sc" link2="panda_link1" /> <enable_collisions link1="panda_hand_sc" link2="panda_link2" /> -- GitLab