diff --git a/talos_roscontrol_sot_talos/config/sot_talos_params_effort.yaml b/talos_roscontrol_sot_talos/config/sot_talos_params_effort.yaml
index ccdef5fc426b4015c440a31905df2a00d24471dc..9bd89c712d231f3ea4302f5576f8180121b21688 100644
--- a/talos_roscontrol_sot_talos/config/sot_talos_params_effort.yaml
+++ b/talos_roscontrol_sot_talos/config/sot_talos_params_effort.yaml
@@ -7,6 +7,6 @@ sot_controller:
     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,
-  torques: torques, cmd-joints: control, cmd-effort: control }
+  joint-angles: joint-angles, velocities: velocities, forces: forces, currents: currents,
+  torques: torques, cmd-joints: control, cmd-effort: control, accelerometer_0: accelerometer_0, gyrometer_0: gyrometer_0 }
   control_mode: EFFORT