diff --git a/roscontrol_sot_talos/config/sot_talos_params_gazebo.yaml b/roscontrol_sot_talos/config/sot_talos_params_gazebo.yaml
index 9b0f8ae761eb8c1c6de3c557cbb052cbb7886652..480ab0d225bb22dc6189c902f569896f19d00f94 100644
--- a/roscontrol_sot_talos/config/sot_talos_params_gazebo.yaml
+++ b/roscontrol_sot_talos/config/sot_talos_params_gazebo.yaml
@@ -3,9 +3,9 @@ sot_controller:
   simulation_mode: gazebo
   joint_names: [ leg_left_1_joint, leg_left_2_joint, leg_left_3_joint, leg_left_4_joint, leg_left_5_joint, leg_left_6_joint,
     leg_right_1_joint, leg_right_2_joint, leg_right_3_joint, leg_right_4_joint, leg_right_5_joint, leg_right_6_joint,
-    torso_1_joint,torso_2_joint,    head_1_joint, head_2_joint, 
+    torso_1_joint,torso_2_joint,
     arm_left_1_joint, arm_left_2_joint, arm_left_3_joint, arm_left_4_joint, arm_left_5_joint, arm_left_6_joint, arm_left_7_joint, gripper_left_joint,
-    arm_right_1_joint, arm_right_2_joint, arm_right_3_joint, arm_right_4_joint, arm_right_5_joint, arm_right_6_joint, arm_right_7_joint, gripper_right_joint
+    arm_right_1_joint, arm_right_2_joint, arm_right_3_joint, arm_right_4_joint, arm_right_5_joint, arm_right_6_joint, arm_right_7_joint, gripper_right_joint, head_1_joint, head_2_joint
   ]
   map_rc_to_sot_device: { motor-angles: motor-angles ,
   joint-angles: joint-angles, velocities: velocities,
@@ -50,7 +50,7 @@ sot_controller:
     - name: arm_left_5_joint
       des_pos: 0.0
     - name: arm_left_6_joint
-      des_pos: 0.1
+      des_pos: 0.0
     - name: arm_left_7_joint
       des_pos: 0.1
     - name: gripper_left_joint
@@ -66,7 +66,7 @@ sot_controller:
     - name: arm_right_5_joint
       des_pos: 0.0
     - name: arm_right_6_joint
-      des_pos: 0.1
+      des_pos: 0.0
     - name: arm_right_7_joint
       des_pos: 0.1
     - name: gripper_right_joint
@@ -77,4 +77,4 @@ sot_controller:
       des_pos:: 0.0   
   control_mode: POSITION
   dt: 0.001
-  jitter: 0.0004
\ No newline at end of file
+  jitter: 0.0004