diff --git a/.README.mk.swp b/.README.mk.swp
new file mode 100644
index 0000000000000000000000000000000000000000..8aa0ba1a6cdd75205cb6f12bafd3bbfdfe065d49
Binary files /dev/null and b/.README.mk.swp differ
diff --git a/README.mk b/README.mk
new file mode 100644
index 0000000000000000000000000000000000000000..3f0d7302dc73bad218070289c82a0d92a3c000bb
--- /dev/null
+++ b/README.mk
@@ -0,0 +1,87 @@
+# Description
+
+This ROS node implements the BlobDetector provided in OpenCV. Each input image is trasformed to the HSV color
+space and then filtered with the desired maximum and minimum values for the Hue, Saturation and Value parameters. 
+Then all the connected regions within a desired maximum and minimum sizes are detected and published. The 
+segmented image is also published.
+
+This ROS node does not require the camera to be calibrated, however it is highly recommended. Follow the calibration 
+procedure presented here.
+
+## subscribers
+
+This node subscribes to the following topics:
+
+ * ~/image_in/camera_info (sensor_msgs/CameraInfo.msg): provides the calibration information for the camera.
+
+ * ~/image_in/image_raw (sensor_msgs/Image.msg): The input image itself. 
+
+## publishers
+
+This node publishes the following topics:
+
+ * ~/image_out/camera_info (sensor_msgs/CameraInfo.msg): the same camera information message received.
+	
+ * ~/image_out/image_raw (sensor_msgs/Image.msg): a black and white image with the segmented regions. The segmented blobs will
+appear as balck regions, being the background white.
+
+ * ~/blobs (iri_blob_detector/blob_array.msg): a list of all the connected regions that comply with the desired 
+parameters. The information provided for each blob is:
+
+    ** id (string): the identifier of each blob is build from the color_id parameter and the index of the blob.
+    ** center_x (unsigned int): position in pixels of the center of the blob in the image (x axis).
+    ** center_y (unsigned int): position in pixels of the center of the blob in the image (y axis).  
+    ** size (float): Size of the blob in pixels.
+
+## parameters
+
+This node has the following parameters. These parameters can be modified with the dynamic reconfigure tool.
+
+ * H_center (integer): the desierd window center value for the Hue parameter. This parameter is defined from 0 to 180.
+
+ * H_window (integer): the desired width of the Hue parameter window. This parameter is defined from 0 to 180.
+
+ * S_center (integer): the desierd window center value for the Saturation parameter. This parameter is defined from 0 to 255.
+
+ * S_window (integer): the desired width of the Saturation parameter window. This parameter is defined from 0 to 255.
+  
+ * V_center (integer): the desierd window center value for the Value parameter. This parameter is defined from 0 to 255.
+
+ * V_window (integer): the desired width of the Value parameter window. This parameter is defined from 0 to 255.
+
+ * color_id (string): the identifier of the color segmented. This name is used for the blob identifier.
+  
+ * max_area (integer): the maximum area in pixels of the desired regions.
+ 
+ * min_area (integer): the minimum area in pixels of the desired regions.
+
+# Dependencies
+
+This node has the following dependencies:
+
+ * OpenCV (at least version 3.0)
+
+ * boost
+
+# How to use it
+
+This node provides two launch files:
+
+ * blob_detector.launch: this file load the default parameters from ./config/default_params.yaml and launches the blob detector 
+node together with the usb_cam ROS node. This launch file will use the first USB camera compatible found in the system. If a 
+specific camera is desired, fill in the vendor, product and serial parameters for the desired camera.
+
+ * blob_detector_sim.launch: this file load the default parameters from ./config/default_params.yaml and launches the blob detector
+node, but expects the model car simulator to be already running.
+
+You can use the iri_color_calibration ROS node to easily generate new yaml configuration files for this node.
+
+Once the node is running, use the dynamic reconfigure ROS tool to change online the blob detector parameters:
+
+ * rosrun rqt_reconfigure rqt_reconfigure
+
+Display the output image using the ROS tools to see the result of the segmentation:
+
+ * rosrun rqt_image_view rqt_image_view
+
+
diff --git a/cfg/BlobDetector.cfg b/cfg/BlobDetector.cfg
index 67733912ab2ebeda883f37039ec7b96548f1d4ae..fff635837eb0a58fe4f7613e60a2afe5f9d2f747 100755
--- a/cfg/BlobDetector.cfg
+++ b/cfg/BlobDetector.cfg
@@ -41,8 +41,8 @@ gen = ParameterGenerator()
 #gen.add("velocity_scale_factor",  double_t,  0,                               "Maximum velocity scale factor",  0.5,      0.0,  1.0)
 gen.add("get_filter",              bool_t, 0,                                  "Get current filter coeficients", False)
 gen.add("color_id",                str_t,  0,                                  "ID of the color",                "")
-gen.add("H_center",                int_t,  0,                                  "Hue window center",              150,      0,    360)
-gen.add("H_window",                int_t,  0,                                  "Hue window width",               100,      0,    360)
+gen.add("H_center",                int_t,  0,                                  "Hue window center",              90,       0,    180)
+gen.add("H_window",                int_t,  0,                                  "Hue window width",               180,      0,    180)
 gen.add("S_center",                int_t,  0,                                  "Saturation window center",       128,      0,    256)
 gen.add("S_window",                int_t,  0,                                  "Saturation window width",        255,      0,    256)
 gen.add("V_center",                int_t,  0,                                  "Value window center",            128,      0,    256)
diff --git a/launch/blob_detector.launch b/launch/blob_detector.launch
index 9562a8c6a11f00efbd6b748d3383e2c119bf1b11..501979e99bb88e0940aecfe1f25882f66f385827 100644
--- a/launch/blob_detector.launch
+++ b/launch/blob_detector.launch
@@ -6,9 +6,9 @@
   <group ns="usb_cam">
     <node pkg="libuvc_camera" type="camera_node" name="mycam">
       <!-- Parameters used to find the camera -->
-      <param name="vendor" value="0x046d"/>
+<!--      <param name="vendor" value="0x046d"/>
       <param name="product" value="0x0802"/>
-      <param name="serial" value="BEE76360"/>
+      <param name="serial" value="BEE76360"/>-->
       <!-- If the above parameters aren't unique, choose the first match: -->
       <param name="index" value="0"/>