diff --git a/set_path.sh b/set_path.sh
index bab1743..30478f5 100644
--- a/set_path.sh
+++ b/set_path.sh
@@ -1,4 +1,4 @@
export CMAKE_INSTALL_PREFIX=$CONDA_PREFIX
export YARP_DATA_DIRS=$CMAKE_INSTALL_PREFIX/share/yarp:$CMAKE_INSTALL_PREFIX/share/iCub:$PIXI_PROJECT_ROOT/suites
export LD_LIBRARY_PATH=$CMAKE_INSTALL_PREFIX/lib/robottestingframework:$PIXI_PROJECT_ROOT/.build/plugins
-export CMAKE_PREFIX_PATH=$CONDA_PREFIX:$CMAKE_PREFIX_PATH
\ No newline at end of file
+export CMAKE_PREFIX_PATH=$CONDA_PREFIX
\ No newline at end of file
diff --git a/src/imu/README.md b/src/imu/README.md
new file mode 100644
index 0000000..faff195
--- /dev/null
+++ b/src/imu/README.md
@@ -0,0 +1,95 @@
+IMU orientation test
+====================
+
+## Prerequisites
+
+If you want to test multiple IMUs at once, the robot must expose in its `yarprobotinterface` configuration file a `multipleanalogsensorsserver` that publishes the orientation measurements for all of available sensors, with a `prefix` that matches exactly the `port` parameter of the test (the default one is `${portprefix}/alljoints/inertials`).
+
+An example of `alljoints-inertials_wrapper.xml` for iCubV2_* models:
+
+```sh
+
+
+
+
+ 10
+ ${portprefix}/alljoints/inertials
+
+
+
+ alljoints-inertials_remapper
+
+
+
+
+
+```
+
+and `alljoints-inertials_remapper.xml`:
+
+```sh
+
+
+
+
+
+
+ (l_arm_ft r_arm_ft head_imu_0)
+
+
+
+ head_inertial_hardware_device
+ left_arm_inertial_hardware_device
+ right_arm_inertial_hardware_device
+
+
+
+
+
+
+```
+
+## Usage
+
+There are essentially two methods to install and run the IMU orientation test, which are going to be described in the following sections. In both cases, after launching the test, a .mat file containing the relevant measurements involved in the test will be generated.
+
+### robotology-superbuild
+
+If you have installed `icub-tests` as a part of the `robotology superbuild` framework with the [Robot Testing profile](https://github.com/robotology/robotology-superbuild/blob/master/doc/cmake-options.md#robot-testing) activation, i.e. by enabling the `ROBOTOLOGY_ENABLE_ROBOT_TESTING` CMake option of the superbuild, this test, like the others, is already available.
+
+In this case, after compiling and being sure that `yarpserver` is up, you can run:
+
+```sh
+cd robotology-superbuild/src/icub-tests
+robottestingframework-testrunner --suite suites/imu.xml
+```
+
+Otherwise, if you want to launch the test in a simulation environment, in a shell open a `gazebo` environment and import, for example, your iCub model. After that, open a separated shell, and:
+
+```sh
+#set YARP_ROBOT_NAME env variable with the name of the model you imported in gazebo
+#example:
+export YARP_ROBOT_NAME=iCubGazeboV2_7
+cd robotology-superbuild/src/icub-tests
+robottestingframework-testrunner --suite suites/imu-icubGazeboSim.xml
+```
+
+### pixi
+
+If you want to run the test without depending on the whole robotology-superbuild, you can use `pixi`. First of all, be sure to have [`pixi`](https://pixi.sh/#installation) installed. Then, clone `icub-tests` and run the test as a pixi task:
+
+```sh
+git clone https://github.com/robotology/icub-tests
+cd icub-tests
+pixi run imu_test
+```
+
+In simulation, instead, import your model in `gazebo` and then run:
+
+```sh
+#set YARP_ROBOT_NAME env variable with the name of the model you imported in gazebo
+#example:
+export YARP_ROBOT_NAME=iCubGazeboV2_7
+cd icub-tests
+pixi run imu_sim_test
+```
\ No newline at end of file
diff --git a/src/imu/imu.h b/src/imu/imu.h
index 40795d6..78c5500 100644
--- a/src/imu/imu.h
+++ b/src/imu/imu.h
@@ -20,23 +20,19 @@
* It takes as input the urdf of the robot and make a comparison between the expected values retrieved from the forward kinematics and the ones read from the IMU itself.
* The test involves the movements of the joints belonging to the part on which the sensors are mounted.
*
-* You can find the parameters involved in the test in suites/contexts/icub/test_imu.ini file.
-* To run the test, you have to install pixi and then, after cloning this repo, you can run:
+* You can find the parameters involved in the test in the following table:
*
-* pixi run imu_test
+* | Parameter name | Type | Required | Description | Notes |
+* |:------------------:|:------------------:|:--------:|:-----------:|:-----:|
+* | robot | string | Yes | The name of the robot. | e.g. icub |
+* | model | string | Yes | The name of the robot model. | e.g. model.urdf |
+* | port | string | Yes | The name of the port streaming IMU data. | e.g. /icub/alljoints/inertials |
+* | remoteControlBoards| vector of string | Yes | The list of the controlboards to open. | e.g. ("torso", "head") |
+* | axesNames | vector of string | Yes | The list of the controlled joints. | e.g. ("torso_pitch", "torso_roll", "torso_yaw", "neck_pitch", "neck_roll", "neck_yaw") |
+* | sensorsList | vector of string | Yes | The list of the sensors to be tested. | e.g. ("head_imu_0", "l_arm_ft") or ("all")|
+* | maxError | double | Yes | The tolerance on the error. | |
*
-* This will compile the dependencies, launch the test and, at the end, a .mat file is generated containing the relevant measurements of the test.
-*
-* Accepts the following parameters:
-* | Parameter name | Type | Units | Default Value | Required | Description | Notes |
-* |:------------------:|:------------------:|:-----:|:-------------:|:--------:|:-----------:|:-----:|
-* | robot | string | - | - | Yes | The name of the robot. | e.g. icub |
-* | model | string | - | - | Yes | The name of the robot model. | e.g. model.urdf |
-* | port | string | - | - | Yes | The name of the port streaming IMU data. | e.g. /icub/head/inertials |
-* | remoteControlBoards| vector of string | - | - | Yes | The list of the controlboards to open. | e.g. ("torso", "head") |
-* | axesNames | vector of string | - | - | Yes | The list of the controlled joints. | e.g. ("torso_pitch", "torso_roll", "torso_yaw", "neck_pitch", "neck_roll", "neck_yaw") |
-* | sensorsList | vector of string | - | - | Yes | The list of the sensors to be tested | e.g. ("head_imu_0", "l_arm_ft") or ("all)|
-* | maxError | double | - | - | Yes | The tolerance on the error. | |
+* Further instructions about how to install, configure and run the test can be found in the related page.
*/
class Imu : public yarp::robottestingframework::TestCase {
diff --git a/suites/contexts/icub/test_imu.ini b/suites/contexts/icub/test_imu.ini
index 0d9cbc3..fe00d7d 100644
--- a/suites/contexts/icub/test_imu.ini
+++ b/suites/contexts/icub/test_imu.ini
@@ -3,6 +3,5 @@ model model.urdf
port /${robotname}/alljoints/inertials
remoteControlBoards ("torso", "head", "left_arm", "right_arm")
axesNames ("torso_pitch", "torso_roll", "torso_yaw", "neck_pitch", "neck_roll", "neck_yaw", "l_shoulder_pitch", "l_shoulder_roll", "l_shoulder_yaw", "r_shoulder_pitch", "r_shoulder_roll", "r_shoulder_yaw")
-; sensorsList ("head_imu_0", "l_arm_ft", "r_arm_ft")
-sensorsList ("all")
+sensorsList ("all")
maxError 0.1