From b0b70632bebe79fee15861af1a6b6f20884b49db Mon Sep 17 00:00:00 2001
From: Johannes Mey <johannes.mey@tu-dresden.de>
Date: Sun, 23 Aug 2020 22:55:02 +0200
Subject: [PATCH] switch fingers to effort controller

---
 robots/panda.transmission.xacro | 12 ++++++++----
 1 file changed, 8 insertions(+), 4 deletions(-)

diff --git a/robots/panda.transmission.xacro b/robots/panda.transmission.xacro
index f293138..32dee85 100644
--- a/robots/panda.transmission.xacro
+++ b/robots/panda.transmission.xacro
@@ -91,21 +91,25 @@
             <transmission name="${robot_name}_leftfinger">
                 <type>transmission_interface/SimpleTransmission</type>
                 <joint name="${robot_name}_finger_joint1">
-                    <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+<!--                    <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>-->
+                    <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
                 </joint>
                 <actuator name="${robot_name}_finger_joint1">
                     <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
-                    <mechanicalReduction>1</mechanicalReduction>
+                    <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+<!--                    <mechanicalReduction>1</mechanicalReduction>-->
                 </actuator>
             </transmission>
 
             <transmission name="${robot_name}_rightfinger">
                 <type>transmission_interface/SimpleTransmission</type>
                 <joint name="${robot_name}_finger_joint2">
-                    <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+<!--                    <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>-->
+                    <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
                 </joint>
                 <actuator name="${robot_name}_finger_joint2">
-                    <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+<!--                    <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>-->
+                    <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
                     <mechanicalReduction>1</mechanicalReduction>
                 </actuator>
             </transmission>
-- 
GitLab