diff --git a/config/panda_control.yaml b/config/panda_control.yaml
index 65fcaf7fd3133a7aa88e41a322718ec51db7ecd0..b8370646d14c5ee907633d820e2d9c6ae8d9aeed 100644
--- a/config/panda_control.yaml
+++ b/config/panda_control.yaml
@@ -5,6 +5,7 @@
 
     position_joint_trajectory_controller:
         type: position_controllers/JointTrajectoryController
+#        type: effort_controllers/JointTrajectoryController
         joints:
             - panda_joint1
             - panda_joint2
@@ -17,14 +18,28 @@
         constraints:
             goal_time: 2.0
 
+        gains:
+          panda_joint1: { p: 12000, d: 50, i: 0.0, i_clamp: 10000 }
+          panda_joint2: { p: 30000, d: 100, i: 0.02, i_clamp: 10000 }
+          panda_joint3: { p: 18000, d: 50, i: 0.01, i_clamp: 1 }
+          panda_joint4: { p: 18000, d: 70, i: 0.01, i_clamp: 10000 }
+          panda_joint5: { p: 12000, d: 70, i: 0.01, i_clamp: 1 }
+          panda_joint6: { p: 7000, d: 50, i: 0.01, i_clamp: 1 }
+          panda_joint7: { p: 2000, d: 20, i: 0.0, i_clamp: 1 }
+
         state_publish_rate: 100
 
     panda_hand_controller:
-        type: position_controllers/JointTrajectoryController
+#        type: position_controllers/JointTrajectoryController
+        type: effort_controllers/JointTrajectoryController
         joints:
             - panda_finger_joint1
             - panda_finger_joint2
 
+        gains:
+            panda_finger_joint1: { p: 5, d: 3.0, i: 0, i_clamp: 1 }
+            panda_finger_joint2: { p: 5, d: 1.0, i: 0, i_clamp: 1 }
+
         state_publish_rate: 25
 
     joint_position_controller: