diff --git a/README.md b/README.md
index 2544f252f839f375364e59eab1191733ad5c76b9..c737b2415ac8a8db20924926b205870adac4a468 100644
--- a/README.md
+++ b/README.md
@@ -1,6 +1,7 @@
 # Description
 
 This package is a Gazebo plugin to change a model reference material.
+
 For example, it is used to change the state of a simulated sempahore light from [iri_sign_description](https://gitlab.iri.upc.edu/mobile_robotics/adc/adc_2021/iri_sign_description)
 
 This package has been tested ROS Melodic (Gazebo 9) under Linux Ubuntu 18.04, although it may work with other ROS-Gazebo versions and Linux variations.
@@ -40,11 +41,14 @@ See example files provided:
 
 ## Launch
 
+Test launch of an empty Gazebo world with a sample_box model.
+
 `roslaunch gazebo_ros empty_world.launch`
 
 `roslaunch iri_gazebo_set_material_plugin spawn.launch`
 
+You can switch between defined Gazebo/Red and Gazebo/Green materials, leaving the name empty, or set a different material, like Gazebo/Blue.
+
 `rostopic pub /sample_box_set_material_plugin/set_material  std_msgs/String "data: ''"`
 
 `rostopic pub /sample_box_set_material_plugin/set_material  std_msgs/String "data: 'Gazebo/Blue'"`
-```