diff --git a/talos_bringup/config/talos_full_hardware.yaml b/talos_bringup/config/talos_full_hardware.yaml
index 127342bb675744dd326f2cd1de255f81a5aec633..f65bf2216b31ff46b9325880fdb851e27a27f93b 100644
--- a/talos_bringup/config/talos_full_hardware.yaml
+++ b/talos_bringup/config/talos_full_hardware.yaml
@@ -9,6 +9,8 @@ actuators:
     mode_cmd_port: ref_control_mode
     absolute_encoder_position_port: act_abs_position
     torque_sensor_port: act_torque
+    temperature_sensor_port: act_temperature
+
 
 e_stop:
   raw_data:
@@ -31,6 +33,22 @@ force_torque:
     raw_data:
       force_port: force_ankle_right
       torque_port: torque_ankle_right
+  left_wrist_ft:
+    frame: wrist_left_ft_link
+    transformation:
+      force: [x, y, z]
+      torque: [x, y, z]
+    raw_data:
+      force_port: force_wrist_left
+      torque_port: torque_wrist_left
+  right_wrist_ft:
+    frame: wrist_right_ft_link
+    transformation:
+      force: [x, y, z]
+      torque: [x, y, z]
+    raw_data:
+      force_port: force_wrist_right
+      torque_port: torque_wrist_right
 
 imu:
   base_imu:
diff --git a/talos_description/urdf/head/head.urdf.xacro b/talos_description/urdf/head/head.urdf.xacro
index f4dd9c087c65bef992b5ba9641da1e47771d09ca..85938fd3c7c0697c90b93dbfbdd282643ffe6e47 100644
--- a/talos_description/urdf/head/head.urdf.xacro
+++ b/talos_description/urdf/head/head.urdf.xacro
@@ -151,7 +151,7 @@
       <origin xyz="0 0 0" rpy="${-90 * deg_to_rad} 0 ${-90 * deg_to_rad}"/>
     </xacro:xtion_pro_live>
     <xacro:talos_head_differential_transmission name="${name}" number1="1" number2="2"
-                                                act_reduction1="1.0" act_reduction2="-1.0"
+                                                act_reduction1="1.0" act_reduction2="1.0"
                                                 jnt_reduction1="1.0" jnt_reduction2="2.0" />
   </xacro:macro>