diff --git a/tutorial/model/forcetorque/README.md b/tutorial/model/forcetorque/README.md
new file mode 100644
index 000000000..3bf2ee268
--- /dev/null
+++ b/tutorial/model/forcetorque/README.md
@@ -0,0 +1,36 @@
+# Example of a model using a gazebo_yarp_forcetorque plugin
+
+This directory contains the example of a model using the `gazebo_yarp_forcetorque` plugin.
+
+For more information on simulation of Force/Torque sensors in Gazebo Classic, see [https://classic.gazebosim.org/tutorials?tut=force_torque_sensor&cat=sensors](https://classic.gazebosim.org/tutorials?tut=force_torque_sensor&cat=sensors).
+
+
+To run this example, first of all run `yarpserver` in a terminal, then make sure to have added `gazebo-yarp-plugins/tutorial/model` directory to `GAZEBO_MODEL_PATH` as documented in the "Example models" section of the `doc/embed_plugins.md` documentation and then run the world:
+~~~
+gazebo --verbose forcetorque_world.world
+~~~
+
+If the simulation starts correctly, you should see a model composed by a cylinder and a box. The FT sensor measures the force exchanged between the cylinder and the box. To check if the YARP plugin works as expected, open a new terminal and type:
+~~~
+yarp name list
+~~~
+
+To list all the YARP ports open. You should see the port `/forcetorque/measures:o`, that is the one opened by the plugin.
+
+You can then read the measures from the the `/forcetorque/measures:o` with the command:
+~~~
+traversaro@IITICUBLAP257:~$ yarp read ... /forcetorque/measures:o
+[INFO] |yarp.os.Port|/tmp/port/1| Port /tmp/port/1 active at tcp://172.22.196.221:10004/
+[INFO] |yarp.os.impl.PortCoreInputUnit|/tmp/port/1| Receiving input from /forcetorque/measures:o to /tmp/port/1 using tcp
+() () () () () (((0.0 0.0 -98.0000000000000568434 0.0 0.0 0.0) 59.0670000000000001705)) () () () ()
+() () () () () (((0.0 0.0 -97.9999999999999573674 0.0 0.0 0.0) 59.542999999999999261)) () () () ()
+() () () () () (((0.0 0.0 -98.0000000000000568434 0.0 0.0 0.0) 60.0240000000000009095)) () () () ()
+() () () () () (((0.0 0.0 -98.0000000000000568434 0.0 0.0 0.0) 60.5)) () () () ()
+() () () () () (((0.0 0.0 -97.9999999999999573674 0.0 0.0 0.0) 60.9759999999999990905)) () () () ()
+() () () () () (((0.0 0.0 -97.9999999999999573674 0.0 0.0 0.0) 61.4530000000000029559)) () () () ()
+() () () () () (((0.0 0.0 -98.0000000000000568434 0.0 0.0 0.0) 61.93200000000000216)) () () () ()
+~~~
+
+There is a parenthesis with six numbers, the first three are force and the last three are torques. In this case, it is possible
+to see that the force measure make sense as the weight of the link is 10 Kg, and the acceleration of gravity is 9.8, so the measure
+norm on the Z axis is correctly approximately 9.8*10 = 98.0 .
\ No newline at end of file
diff --git a/tutorial/model/forcetorque/forcetorque_nws.xml b/tutorial/model/forcetorque/forcetorque_nws.xml
new file mode 100644
index 000000000..d56fbd04e
--- /dev/null
+++ b/tutorial/model/forcetorque/forcetorque_nws.xml
@@ -0,0 +1,17 @@
+
+
+
+
+
+
+
+ /forcetorque
+ 100
+
+
+ forcetorque_plugin_device
+
+
+
+
+
diff --git a/tutorial/model/forcetorque/forcetorque_world.world b/tutorial/model/forcetorque/forcetorque_world.world
new file mode 100644
index 000000000..2e3b04d4a
--- /dev/null
+++ b/tutorial/model/forcetorque/forcetorque_world.world
@@ -0,0 +1,14 @@
+
+
+
+
+ model://ground_plane
+
+
+ model://sun
+
+
+ model://forcetorque
+
+
+
diff --git a/tutorial/model/forcetorque/model.config b/tutorial/model/forcetorque/model.config
new file mode 100644
index 000000000..551c7d0b8
--- /dev/null
+++ b/tutorial/model/forcetorque/model.config
@@ -0,0 +1,16 @@
+
+
+
+ ForceTorque
+ 1.0
+ model.sdf
+
+
+ Silvio Traversaro
+ silvio.traversaro@iit.it
+
+
+
+ A simple model with an forcetorque sensor exposed via YARP plugins.
+
+
diff --git a/tutorial/model/forcetorque/model.sdf b/tutorial/model/forcetorque/model.sdf
new file mode 100644
index 000000000..81edb0406
--- /dev/null
+++ b/tutorial/model/forcetorque/model.sdf
@@ -0,0 +1,103 @@
+
+
+
+
+
+
+
+ 0 0 0.05 0 0 0
+
+ 0.020000
+ 0.000000
+ 0.000000
+ 0.020000
+ 0.000000
+ 0.020000
+
+ 10.000000
+
+
+ 0 0 0.05 0 0 0
+
+
+ 0.100000
+ 0.100000
+
+
+
+
+ 0 0 0.05 0 0 0
+ 250
+
+
+ 0.100000
+ 0.100000
+
+
+
+
+
+ 0 0 0.15 0 0 0
+
+ 0 0 0.0 0 0 0
+
+ 0.020000
+ 0.000000
+ 0.000000
+ 0.020000
+ 0.000000
+ 0.020000
+
+ 10.000000
+
+
+ 0 0 0.0 0 0 0
+
+
+ 0.1 0.1 0.1
+
+
+
+
+ 0 0 0.0 0 0 0
+
+
+ 0.1 0.1 0.1
+
+
+
+
+
+ world
+ link_1
+ 0 0 0.0 0 0 0
+
+ true
+ true
+ 30
+
+
+
+ link_1
+ link_2
+
+
+
+ 0 0 0 0 0 0
+
+ true
+ true
+ 30
+
+
+ (yarpDeviceName forcetorque_plugin_device) (disableImplicitNetworkWrapper)
+
+
+
+
+
+ model://forcetorque/forcetorque_nws.xml
+
+
+