diff --git a/robots/panda.transmission.xacro b/robots/panda.transmission.xacro
index f29313877d62e86a3f95779428c1c38783643a92..32dee85640530742c5bb605b560830be5981a86c 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>