From d97b987a7bfc4ec0d10fa01d1ae518a67daf31d4 Mon Sep 17 00:00:00 2001
From: Mike Lautman <mikeblautman@gmail.com>
Date: Sat, 9 Feb 2019 19:46:00 -0700
Subject: [PATCH] changing the end effector parent group (#20)

* changing the end effector parent group

* changing virtual joint to floating for use with moveit_visual_tools
---
 config/panda_arm.xacro           | 2 +-
 config/panda_arm_hand.srdf.xacro | 2 +-
 2 files changed, 2 insertions(+), 2 deletions(-)

diff --git a/config/panda_arm.xacro b/config/panda_arm.xacro
index 53ddcdf..092b68f 100644
--- a/config/panda_arm.xacro
+++ b/config/panda_arm.xacro
@@ -21,7 +21,7 @@
     </group_state>
     <!--END EFFECTOR: Purpose: Represent information about an end effector.-->
     <!--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)-->
-    <virtual_joint name="virtual_joint" type="fixed" parent_frame="world" child_link="panda_link0" />
+    <virtual_joint name="virtual_joint" type="floating" parent_frame="world" child_link="panda_link0" />
     <!--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. -->
     <disable_collisions link1="panda_link0" link2="panda_link1" reason="Adjacent" />
     <disable_collisions link1="panda_link0" link2="panda_link2" reason="Never" />
diff --git a/config/panda_arm_hand.srdf.xacro b/config/panda_arm_hand.srdf.xacro
index 39de54f..39f7db9 100644
--- a/config/panda_arm_hand.srdf.xacro
+++ b/config/panda_arm_hand.srdf.xacro
@@ -28,7 +28,7 @@
     <joint name="panda_joint7" value="0.785" />
   </group_state>
   <!--END EFFECTOR: Purpose: Represent information about an end effector.-->
-  <end_effector name="hand" parent_link="panda_link8" group="hand" parent_group="panda_arm_hand" />
+  <end_effector name="hand" parent_link="panda_link8" group="hand" parent_group="panda_arm" />
   <!--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. -->
   <disable_collisions link1="panda_hand" link2="panda_link3" reason="Never" />
   <disable_collisions link1="panda_hand" link2="panda_link4" reason="Never" />
-- 
GitLab