diff --git a/CMakeLists.txt b/CMakeLists.txt
index 53f54681664ae8a3d89df4f33f8805ff8245b1ff..091fb34673c9112e9cdff9120dd3bc02a4e5d2a8 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -1,5 +1,5 @@
 cmake_minimum_required(VERSION 2.8.3)
-project(iri_firewire_camera)
+project(iri_firewire_camera_driver)
 
 ## Find catkin macros and libraries
 find_package(catkin REQUIRED)
@@ -16,18 +16,18 @@ find_package(catkin REQUIRED COMPONENTS sensor_msgs image_transport camera_info_
 # ******************************************************************** 
 # find_package(<dependency> REQUIRED)
 FIND_PACKAGE(iriutils REQUIRED)
-FIND_PACKAGE(firewire REQUIRED)
+FIND_PACKAGE(firewire_camera REQUIRED)
 
-FIND_LIBRARY(raw1394_LIBRARY
+FIND_LIBRARY(raw1394_LIBRARIES
     NAMES raw1394
     PATHS /usr/lib /usr/local/lib)
-FIND_LIBRARY(dc1394_LIBRARY
+FIND_LIBRARY(dc1394_LIBRARIES
     NAMES dc1394
     PATHS /usr/lib /usr/local/lib)
 
-IF (raw1394_INCLUDE_DIR AND raw1394_LIBRARY AND dc1394_INCLUDE_DIR AND dc1394_LIBRARY)
-   SET(firewire_ready TRUE)
-ENDIF (raw1394_INCLUDE_DIR AND raw1394_LIBRARY AND dc1394_INCLUDE_DIR AND dc1394_LIBRARY)
+IF (raw1394_INCLUDE_DIRS AND raw1394_LIBRARIES AND dc1394_INCLUDE_DIRS AND dc1394_LIBRARIES)
+   SET(firewire_camera_ready TRUE)
+ENDIF (raw1394_INCLUDE_DIRS AND raw1394_LIBRARIES AND dc1394_INCLUDE_DIRS AND dc1394_LIBRARIES)
 
 # ******************************************************************** 
 #           Add topic, service and action definition here
@@ -62,7 +62,7 @@ ENDIF (raw1394_INCLUDE_DIR AND raw1394_LIBRARY AND dc1394_INCLUDE_DIR AND dc1394
 # ******************************************************************** 
 #                 Add the dynamic reconfigure file 
 # ******************************************************************** 
-generate_dynamic_reconfigure_options(cfg/FirewireCamera.cfg)
+generate_dynamic_reconfigure_options(cfg/FirewireCameraDriver.cfg)
 
 # ******************************************************************** 
 #                 Add run time dependencies here
@@ -90,9 +90,9 @@ catkin_package(
 include_directories(include)
 include_directories(${catkin_INCLUDE_DIRS})
 include_directories(${iriutils_INCLUDE_DIR})
-include_directories(${firewire_INCLUDE_DIR})
-include_directories(${raw1394_INCLUDE_DIR})
-include_directories(${dc1394_INCLUDE_DIR})
+include_directories(${firewire_camera_INCLUDE_DIR})
+include_directories(${raw1394_INCLUDE_DIRS})
+include_directories(${dc1394_INCLUDE_DIRS})
 
 ## Declare a cpp library
 add_library(${PROJECT_NAME}_nodelet src/firewire_camera_driver_node.cpp src/firewire_camera_driver.cpp)
@@ -105,24 +105,26 @@ add_executable(${PROJECT_NAME} src/firewire_camera_driver.cpp src/firewire_camer
 #                   Add the libraries
 # ******************************************************************** 
 target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})
-target_link_libraries(${PROJECT_NAME} ${iriutils_LIBRARY})
-target_link_libraries(${PROJECT_NAME} ${firewire_LIBRARY})
-target_link_libraries(${PROJECT_NAME} ${raw1394_LIBRARY})
-target_link_libraries(${PROJECT_NAME} ${dc1394_LIBRARY})
+target_link_libraries(${PROJECT_NAME} ${iriutils_LIBRARIES})
+target_link_libraries(${PROJECT_NAME} ${firewire_camera_LIBRARIES})
+target_link_libraries(${PROJECT_NAME} ${raw1394_LIBRARIES})
+target_link_libraries(${PROJECT_NAME} ${dc1394_LIBRARIES})
 
 target_link_libraries(${PROJECT_NAME}_nodelet ${catkin_LIBRARIES})
-target_link_libraries(${PROJECT_NAME}_nodelet ${iriutils_LIBRARY})
-target_link_libraries(${PROJECT_NAME}_nodelet ${firewire_LIBRARY})
-target_link_libraries(${PROJECT_NAME}_nodelet ${raw1394_LIBRARY})
-target_link_libraries(${PROJECT_NAME}_nodelet ${dc1394_LIBRARY})
+target_link_libraries(${PROJECT_NAME}_nodelet ${iriutils_LIBRARIES})
+target_link_libraries(${PROJECT_NAME}_nodelet ${firewire_camera_LIBRARIES})
+target_link_libraries(${PROJECT_NAME}_nodelet ${raw1394_LIBRARIES})
+target_link_libraries(${PROJECT_NAME}_nodelet ${dc1394_LIBRARIES})
 # ******************************************************************** 
 #               Add message headers dependencies 
 # ******************************************************************** 
 # add_dependencies(${PROJECT_NAME} <msg_package_name>_generate_messages_cpp)
+add_dependencies(${PROJECT_NAME}_gencfg         iri_base_driver_generate_messages_py)
 # ******************************************************************** 
 #               Add dynamic reconfigure dependencies 
 # ******************************************************************** 
-add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}         ${${PROJECT_NAME}_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}_nodelet ${${PROJECT_NAME}_EXPORTED_TARGETS})
 
 ## Specify libraries to link a library or executable target against
 # target_link_libraries(foo_node
diff --git a/README.md b/README.md
new file mode 100644
index 0000000000000000000000000000000000000000..4e32f43f734408f2c1f0639527e302123149dee7
--- /dev/null
+++ b/README.md
@@ -0,0 +1,47 @@
+# Description
+
+The iri_firewire_camera_driver ROS package is a wrapper of the firewire_camera C++ driver library.
+
+
+# Dependencies
+
+This node has the following dependencies:
+
+ * [firewire_camera](https://gitlab.iri.upc.edu/labrobotica/drivers/firewire_camera)
+
+ * [iri_base_driver](https://gitlab.iri.upc.edu/labrobotica/ros/iri_core/iri_base_driver): 
+
+
+# Install
+
+This package, as well as all IRI dependencies, can be installed by cloning the 
+repository inside the active workspace:
+
+```
+roscd
+cd ../src
+git clone https://gitlab.iri.upc.edu/labrobotica/ros/platforms/segway/iri_segway_rmp200_driver.git 
+```
+
+However, this package is normally used as part of a wider installation (i.e. a 
+robot, an experiment or a demosntration) which will normally include a complete 
+rosinstall file to be used with the [wstool](http://wiki.ros.org/wstool) tool.
+
+# How to use it
+
+<!--
+The *node.launch* launch file is intended to be included in any launch file 
+that needs the node. It has the following arguments:
+
+  * name: (default: robot) namespace of the node
+
+  * config_file: (default: $(find iri_segway_rmp200_driver)/config/params.yaml) a configuration file with all the supported parameters. 
+  A default YAML configuration file is provided in the config folder, 
+  but each application can define a new file with the desired parameters and pass it to this launch file.
+ 
+  * output: (default: log) the desired output for the node. Possible values for this parameter are log and screen.
+ 
+  * launch_prefix: (default: none)
+
+To remap the topics and services of the driver, use a global remap command.
+-->
\ No newline at end of file
diff --git a/calibration/default_camera.yaml b/calibration/default_camera.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..0c9dee4fb1606cb2c6bed7c5cb2d0bf21bd46703
--- /dev/null
+++ b/calibration/default_camera.yaml
@@ -0,0 +1,20 @@
+image_width: 1024
+image_height: 768
+camera_name: firewire_camera
+camera_matrix:
+  rows: 3
+  cols: 3
+  data: [1296.554904, 0, 683.998137, 0, 1300.230368, 533.151633, 0, 0, 1]
+distortion_model: plumb_bob
+distortion_coefficients:
+  rows: 1
+  cols: 5
+  data: [-0.24349, 0.227189, -0.000748, -4.6e-05, 0]
+rectification_matrix:
+  rows: 3
+  cols: 3
+  data: [1, 0, 0, 0, 1, 0, 0, 0, 1]
+projection_matrix:
+  rows: 3
+  cols: 4
+  data: [1241.253662, 0, 692.043757, 0, 0, 1262.634277, 536.985341, 0, 0, 0, 1, 0]
diff --git a/cfg/FirewireCamera.cfg b/cfg/FirewireCameraDriver.cfg
similarity index 65%
rename from cfg/FirewireCamera.cfg
rename to cfg/FirewireCameraDriver.cfg
index 3a19b37a35eeba63bfe5356a65f5228ca4238196..70e720df0b524f1cdce596759f020414f98b3d64 100755
--- a/cfg/FirewireCamera.cfg
+++ b/cfg/FirewireCameraDriver.cfg
@@ -31,46 +31,50 @@
 
 # Author: 
 
-PACKAGE='iri_firewire_camera'
+PACKAGE='iri_firewire_camera_driver'
 
-from driver_base.msg import SensorLevels
+from iri_base_driver.msg import SensorLevels
 from dynamic_reconfigure.parameter_generator_catkin import *
 
 gen = ParameterGenerator()
 
-enum_mode = gen.enum([ gen.const("Auto", int_t, 0, "Auto mode"),
-gen.const("Manual", int_t, 1, "Manual mode")],"Available feature modes")
+enum_mode = gen.enum([ gen.const("Auto",   int_t, 0, "Auto mode"),
+                       gen.const("Manual", int_t, 1, "Manual mode")],
+                       "Available feature modes")
 
-enum_color_coding = gen.enum([ gen.const("MONO8", int_t, 0, "Mono coding with 8 bits per pixel"),
-gen.const("YUV8", int_t, 1, "YUV coding with 4,2,2 pixels per channel"),
-gen.const("YUV16", int_t, 2, "YUV coding with 4,4,4 pixels per channel"),
-gen.const("RGB24", int_t, 3, "RGB coding with 8 bits per channel"),
-gen.const("MONO16", int_t, 4, "MONO coding with 16 bits per pixel"),
-gen.const("RGB48", int_t, 5, "RGB coding with 16 bits per channel"),
-gen.const("RAW8", int_t, 6, "RAW coding with 8 bits per pixel"),
-gen.const("RAW16", int_t, 7, "RAW coding with 16 bits per pixel")],"Available color modes")
+enum_color_coding = gen.enum([  gen.const("MONO8",  int_t, 0, "Mono coding with 8 bits per pixel"),
+                                gen.const("YUV8",   int_t, 1, "YUV coding with 4,2,2 pixels per channel"),
+                                gen.const("YUV16",  int_t, 2, "YUV coding with 4,4,4 pixels per channel"),
+                                gen.const("RGB24",  int_t, 3, "RGB coding with 8 bits per channel"),
+                                gen.const("MONO16", int_t, 4, "MONO coding with 16 bits per pixel"),
+                                gen.const("RGB48",  int_t, 5, "RGB coding with 16 bits per channel"),
+                                gen.const("RAW8",   int_t, 6, "RAW coding with 8 bits per pixel"),
+                                gen.const("RAW16",  int_t, 7, "RAW coding with 16 bits per pixel")],
+                                "Available color modes")
 
 #       Name                       Type       Reconfiguration level            Description                       Default   Min   Max
+gen.add("camera_name",             str_t,     SensorLevels.RECONFIGURE_STOP,   "Camera name",                    "firewire_camera")
 gen.add("frame_id",                str_t,     SensorLevels.RECONFIGURE_STOP,   "Camera frame identifier",        "camera_frame")
 gen.add("Camera_node",             int_t,     SensorLevels.RECONFIGURE_STOP,   "Desired camera id",              -1,       -1 ,  100)
 gen.add("Camera_serial",           str_t,     SensorLevels.RECONFIGURE_STOP,   "Desired camera serial number",   "")
 gen.add("ISO_speed",               int_t,     SensorLevels.RECONFIGURE_STOP,   "Desired ISO speed",              800,      100,  800)
 gen.add("Image_width",             int_t,     SensorLevels.RECONFIGURE_STOP,   "Desired image width in pixels",  640,      160 , 2448)
 gen.add("Image_height",            int_t,     SensorLevels.RECONFIGURE_STOP,   "Desired image height in pixels", 480,      120 , 2048)
-gen.add("Left_offset",             int_t,     SensorLevels.RECONFIGURE_STOP,   "Desired left offset in pixels",  0,        0,    2448)
-gen.add("Top_offset",              int_t,     SensorLevels.RECONFIGURE_STOP,   "Desired top offset in pixels",   0,        0,    2048)
+gen.add("Left_offset",             int_t,     SensorLevels.RECONFIGURE_STOP,   "Desired left offset in pixels",  0,         0,   2448)
+gen.add("Top_offset",              int_t,     SensorLevels.RECONFIGURE_STOP,   "Desired top offset in pixels",   0,         0,   2048)
 gen.add("Framerate",               double_t,  SensorLevels.RECONFIGURE_STOP,   "Desired framerate in frames per second", 50,1.875 ,200)
-gen.add("Color_coding",            int_t,     SensorLevels.RECONFIGURE_STOP,   "Desired color coding",           0,        0,    7, edit_method=enum_color_coding)
+gen.add("Color_coding",            int_t,     SensorLevels.RECONFIGURE_STOP,   "Desired color coding",           0,         0,    7, edit_method=enum_color_coding)
 gen.add("White_balance_enabled",   bool_t,    SensorLevels.RECONFIGURE_STOP,   "Enable white balance feature",   True)
-gen.add("White_balance_mode",      int_t,     SensorLevels.RECONFIGURE_STOP,   "White balance mode",             0,        0,    1, edit_method=enum_mode)
-gen.add("White_balance_u_b_value", int_t,     SensorLevels.RECONFIGURE_STOP,   "White balance U/B value",        0,        0,    1023)
-gen.add("White_balance_v_r_value", int_t,     SensorLevels.RECONFIGURE_STOP,   "White balance V/R value",        0,        0,    1023)
+gen.add("White_balance_mode",      int_t,     SensorLevels.RECONFIGURE_STOP,   "White balance mode",             0,         0,    1, edit_method=enum_mode)
+gen.add("White_balance_u_b_value", int_t,     SensorLevels.RECONFIGURE_STOP,   "White balance U/B value",        0,         0,    1023)
+gen.add("White_balance_v_r_value", int_t,     SensorLevels.RECONFIGURE_STOP,   "White balance V/R value",        0,         0,    1023)
 gen.add("Shutter_enabled",         bool_t,    SensorLevels.RECONFIGURE_STOP,   "Enable shutter feature",         True)
-gen.add("Shutter_mode",            int_t,     SensorLevels.RECONFIGURE_STOP,   "Shutter mode",                   0,        0,    1, edit_method=enum_mode)
-gen.add("Shutter_value",           int_t,     SensorLevels.RECONFIGURE_STOP,   "Shutter value",                  0,        28,   4095)
+gen.add("Shutter_mode",            int_t,     SensorLevels.RECONFIGURE_STOP,   "Shutter mode",                   0,         0,    1, edit_method=enum_mode)
+gen.add("Shutter_value",           int_t,     SensorLevels.RECONFIGURE_STOP,   "Shutter value",                  28,        0,   4095)
 gen.add("Gain_enabled",            bool_t,    SensorLevels.RECONFIGURE_STOP,   "Enable gain feature",            True)
-gen.add("Gain_mode",               int_t,     SensorLevels.RECONFIGURE_STOP,   "Gain mode",                      0,        0,    1, edit_method=enum_mode)
-gen.add("Gain_value",              int_t,     SensorLevels.RECONFIGURE_STOP,   "Gain value",                     0,        48,   730)
+gen.add("Gain_mode",               int_t,     SensorLevels.RECONFIGURE_STOP,   "Gain mode",                      0,         0,    1, edit_method=enum_mode)
+gen.add("Gain_value",              int_t,     SensorLevels.RECONFIGURE_STOP,   "Gain value",                     48,        0,   730)
 import roslib; roslib.load_manifest(PACKAGE)
 
-exit(gen.generate(PACKAGE, "FirewireCameraDriver", "FirewireCamera"))
+exit(gen.generate(PACKAGE, "FirewireCameraDriver", "FirewireCameraDriver"))
+
diff --git a/config/default_camera.yaml b/config/default_camera.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..ff786a46c6a4274038d75065f11fe0dc23f0d176
--- /dev/null
+++ b/config/default_camera.yaml
@@ -0,0 +1,25 @@
+tf_prefix:               robot
+camera_name:             firewire_camera
+frame_id:                camera_frame
+Camera_node:             0  #-1=use serial, 0,1,2...=use camera
+Camera_serial:           ""
+  #known serials
+  #FLEA2-R:        00b09d0100a96262
+  #FLEA2-L:        00b09d01006cf72a
+ISO_speed:               400
+Image_width:             1024
+Image_height:            768
+Left_offset:             0
+Top_offset:              0
+Framerate:               7.5
+Color_coding:            6     # 0=MONO8, 1=YUV8, 2=YUV16, 3=RGB24, 4=MONO16, 5=RGB48, 6=RAW8, 7=RAW16
+White_balance_enabled:   true
+White_balance_mode:      0     # 0=Auto, 1=Manual
+White_balance_u_b_value: 0
+White_balance_v_r_value: 0
+Shutter_enabled:         true
+Shutter_mode:            0     # 0=Auto, 1=Manual
+Shutter_value:           28
+Gain_enabled:            true
+Gain_mode:               0     # 0=Auto, 1=Manual
+Gain_value:              48
diff --git a/docs/FirewireCameraConfig-usage.dox b/docs/FirewireCameraConfig-usage.dox
deleted file mode 100644
index bd6e8fda9396f8d0d8e308c5f4ddf52d94173b55..0000000000000000000000000000000000000000
--- a/docs/FirewireCameraConfig-usage.dox
+++ /dev/null
@@ -1,26 +0,0 @@
-\subsubsection usage Usage
-\verbatim
-<node name="FirewireCameraDriver" pkg="iri_firewire_camera" type="FirewireCameraDriver">
-  <param name="frame_id" type="str" value="camera_frame" />
-  <param name="Camera_node" type="int" value="-1" />
-  <param name="cal_file" type="str" value="" />
-  <param name="ISO_speed" type="int" value="800" />
-  <param name="Image_width" type="int" value="640" />
-  <param name="Image_height" type="int" value="480" />
-  <param name="Left_offset" type="int" value="0" />
-  <param name="Top_offset" type="int" value="0" />
-  <param name="Framerate" type="double" value="50.0" />
-  <param name="Color_coding" type="int" value="0" />
-  <param name="White_balance_enabled" type="bool" value="False" />
-  <param name="White_balance_mode" type="int" value="0" />
-  <param name="White_balance_u_b_value" type="int" value="0" />
-  <param name="White_balance_v_r_value" type="int" value="0" />
-  <param name="Shutter_enabled" type="bool" value="False" />
-  <param name="Shutter_mode" type="int" value="0" />
-  <param name="Shutter_value" type="int" value="0" />
-  <param name="Gain_enabled" type="bool" value="False" />
-  <param name="Gain_mode" type="int" value="0" />
-  <param name="Gain_value" type="int" value="0" />
-</node>
-\endverbatim
-
diff --git a/docs/FirewireCameraConfig.dox b/docs/FirewireCameraConfig.dox
deleted file mode 100644
index 6228e37ee25bdf758de2e1695006d920e30bd28e..0000000000000000000000000000000000000000
--- a/docs/FirewireCameraConfig.dox
+++ /dev/null
@@ -1,25 +0,0 @@
-\subsubsection parameters ROS parameters
-
-Reads and maintains the following parameters on the ROS server
-
-- \b "~frame_id" : \b [str] Camera frame identifier min: , default: camera_frame, max: 
-- \b "~Camera_node" : \b [int] Desired camera id min: -1, default: -1, max: 100
-- \b "~cal_file" : \b [str] Camera calibration file min: , default: , max: 
-- \b "~ISO_speed" : \b [int] Desired ISO speed min: 100, default: 800, max: 800
-- \b "~Image_width" : \b [int] Desired image width in pixels min: 160, default: 640, max: 2448
-- \b "~Image_height" : \b [int] Desired image height in pixels min: 120, default: 480, max: 2048
-- \b "~Left_offset" : \b [int] Desired left offset in pixels min: 0, default: 0, max: 2448
-- \b "~Top_offset" : \b [int] Desired top offset in pixels min: 0, default: 0, max: 2048
-- \b "~Framerate" : \b [double] Desired framerate in frames per second min: 1.875, default: 50.0, max: 200.0
-- \b "~Color_coding" : \b [int] Desired color coding min: 0, default: 0, max: 7
-- \b "~White_balance_enabled" : \b [bool] Enable white balance feature min: False, default: False, max: True
-- \b "~White_balance_mode" : \b [int] White balance mode min: 0, default: 0, max: 1
-- \b "~White_balance_u_b_value" : \b [int] White balance U/B value min: 0, default: 0, max: 1023
-- \b "~White_balance_v_r_value" : \b [int] White balance V/R value min: 0, default: 0, max: 1023
-- \b "~Shutter_enabled" : \b [bool] Enable shutter feature min: False, default: False, max: True
-- \b "~Shutter_mode" : \b [int] Shutter mode min: 0, default: 0, max: 1
-- \b "~Shutter_value" : \b [int] Shutter value min: 28, default: 0, max: 4095
-- \b "~Gain_enabled" : \b [bool] Enable gain feature min: False, default: False, max: True
-- \b "~Gain_mode" : \b [int] Gain mode min: 0, default: 0, max: 1
-- \b "~Gain_value" : \b [int] Gain value min: 48, default: 0, max: 730
-
diff --git a/docs/FirewireCameraConfig.wikidoc b/docs/FirewireCameraConfig.wikidoc
deleted file mode 100644
index 56034eda267e686fe5f40984d556b25cfe09f6da..0000000000000000000000000000000000000000
--- a/docs/FirewireCameraConfig.wikidoc
+++ /dev/null
@@ -1,88 +0,0 @@
-# Autogenerated param section. Do not hand edit.
-param {
-group.0 {
-name=Dynamically Reconfigurable Parameters
-desc=See the [[dynamic_reconfigure]] package for details on dynamically reconfigurable parameters.
-0.name= ~frame_id
-0.default= camera_frame
-0.type= str
-0.desc=Camera frame identifier 
-1.name= ~Camera_node
-1.default= -1
-1.type= int
-1.desc=Desired camera id Range: -1 to 100
-2.name= ~cal_file
-2.default= 
-2.type= str
-2.desc=Camera calibration file 
-3.name= ~ISO_speed
-3.default= 800
-3.type= int
-3.desc=Desired ISO speed Range: 100 to 800
-4.name= ~Image_width
-4.default= 640
-4.type= int
-4.desc=Desired image width in pixels Range: 160 to 2448
-5.name= ~Image_height
-5.default= 480
-5.type= int
-5.desc=Desired image height in pixels Range: 120 to 2048
-6.name= ~Left_offset
-6.default= 0
-6.type= int
-6.desc=Desired left offset in pixels Range: 0 to 2448
-7.name= ~Top_offset
-7.default= 0
-7.type= int
-7.desc=Desired top offset in pixels Range: 0 to 2048
-8.name= ~Framerate
-8.default= 50.0
-8.type= double
-8.desc=Desired framerate in frames per second Range: 1.875 to 200.0
-9.name= ~Color_coding
-9.default= 0
-9.type= int
-9.desc=Desired color coding Possible values are: MONO8 (0): Mono coding with 8 bits per pixel, YUV8 (1): YUV coding with 4,2,2 pixels per channel, YUV16 (2): YUV coding with 4,4,4 pixels per channel, RGB24 (3): RGB coding with 8 bits per channel, MONO16 (4): MONO coding with 16 bits per pixel, RGB48 (5): RGB coding with 16 bits per channel, RAW8 (6): RAW coding with 8 bits per pixel, RAW16 (7): RAW coding with 16 bits per pixel
-10.name= ~White_balance_enabled
-10.default= False
-10.type= bool
-10.desc=Enable white balance feature 
-11.name= ~White_balance_mode
-11.default= 0
-11.type= int
-11.desc=White balance mode Possible values are: Auto (0): Auto mode, Manual (1): Manual mode
-12.name= ~White_balance_u_b_value
-12.default= 0
-12.type= int
-12.desc=White balance U/B value Range: 0 to 1023
-13.name= ~White_balance_v_r_value
-13.default= 0
-13.type= int
-13.desc=White balance V/R value Range: 0 to 1023
-14.name= ~Shutter_enabled
-14.default= False
-14.type= bool
-14.desc=Enable shutter feature 
-15.name= ~Shutter_mode
-15.default= 0
-15.type= int
-15.desc=Shutter mode Possible values are: Auto (0): Auto mode, Manual (1): Manual mode
-16.name= ~Shutter_value
-16.default= 0
-16.type= int
-16.desc=Shutter value Range: 28 to 4095
-17.name= ~Gain_enabled
-17.default= False
-17.type= bool
-17.desc=Enable gain feature 
-18.name= ~Gain_mode
-18.default= 0
-18.type= int
-18.desc=Gain mode Possible values are: Auto (0): Auto mode, Manual (1): Manual mode
-19.name= ~Gain_value
-19.default= 0
-19.type= int
-19.desc=Gain value Range: 48 to 730
-}
-}
-# End of autogenerated section. You may edit below.
diff --git a/firewire_camera_driver_nodelet_plugin.xml b/firewire_camera_driver_nodelet_plugin.xml
new file mode 100755
index 0000000000000000000000000000000000000000..c619328d157c54f37402477eef61790240ba3554
--- /dev/null
+++ b/firewire_camera_driver_nodelet_plugin.xml
@@ -0,0 +1,7 @@
+<library path="lib/libiri_firewire_camera_driver_nodelet">
+  <class name="iri_firewire_camera_driver/FirewireCameraDriverNodelet" type="FirewireCameraDriverNodelet" base_class_type="nodelet::Nodelet">
+    <description>
+      Nodelet for the iri firewire camera module
+    </description>
+  </class>
+</library>
diff --git a/firewire_nodelet_plugin.xml b/firewire_nodelet_plugin.xml
deleted file mode 100755
index 90cb46ea380d61741b704a7976a64f07cf26b48f..0000000000000000000000000000000000000000
--- a/firewire_nodelet_plugin.xml
+++ /dev/null
@@ -1,7 +0,0 @@
-<library path="lib/libiri_firewire_camera_nodelet">
-  <class name="iri_firewire_camera/FirewireCameraNodelet" type="FirewireCameraNodelet" base_class_type="nodelet::Nodelet">
-    <description>
-      Nodelete for the iri firewire camera module
-    </description>
-  </class>
-</library>
diff --git a/include/firewire_camera_driver.h b/include/firewire_camera_driver.h
index 72be8e30e6f9beac868aaab460cb866c193fccfd..59f3cce7235ad3ebc241e0ee2e35c33a61413462 100644
--- a/include/firewire_camera_driver.h
+++ b/include/firewire_camera_driver.h
@@ -26,7 +26,7 @@
 #define _firewire_camera_driver_h_
 
 #include <iri_base_driver/iri_base_driver.h>
-#include <iri_firewire_camera/FirewireCameraConfig.h>
+#include <iri_firewire_camera_driver/FirewireCameraDriverConfig.h>
 
 //include firewire_camera_driver main library
 #include "firewirecamera.h"
@@ -46,7 +46,7 @@
  * safetely open, close, run and stop the driver at any time. It also must 
  * guarantee an accessible interface for all driver's parameters.
  *
- * The FirewireCameraConfig.cfg needs to be filled up with those parameters suitable
+ * The FirewireCameraDriverConfig.cfg needs to be filled up with those parameters suitable
  * to be changed dynamically by the ROS dyanmic reconfigure application. The 
  * implementation of the CIriNode class will manage those parameters through
  * methods like postNodeOpenHook() and reconfigureNodeHook().
@@ -81,12 +81,12 @@ class FirewireCameraDriver : public iri_base_driver::IriBaseDriver
      * \brief
      *
      */
-    void dyn_rec_to_camera(iri_firewire_camera::FirewireCameraConfig &dyn_rec_config,TCameraConfig &camera_config);
+    void dyn_rec_to_camera(iri_firewire_camera_driver::FirewireCameraDriverConfig &dyn_rec_config,TCameraConfig &camera_config);
     /**
      * \brief
      *
      */
-    void camera_to_dyn_rec(TCameraConfig &camera_config,iri_firewire_camera::FirewireCameraConfig &dyn_rec_config);
+    void camera_to_dyn_rec(TCameraConfig &camera_config,iri_firewire_camera_driver::FirewireCameraDriverConfig &dyn_rec_config);
     /**
      * \brief
      *
@@ -106,10 +106,10 @@ class FirewireCameraDriver : public iri_base_driver::IriBaseDriver
    /**
     * \brief define config type
     *
-    * Define a Config type with the FirewireCameraConfig. All driver implementations
+    * Define a Config type with the FirewireCameraDriverConfig. All driver implementations
     * will then use the same variable type Config.
     */
-    typedef iri_firewire_camera::FirewireCameraConfig Config;
+    typedef iri_firewire_camera_driver::FirewireCameraDriverConfig Config;
 
    /**
     * \brief config variable
@@ -256,4 +256,4 @@ class FirewireCameraDriver : public iri_base_driver::IriBaseDriver
     ~FirewireCameraDriver();
 };
 
-#endif
+#endif
\ No newline at end of file
diff --git a/include/firewire_camera_driver_node.h b/include/firewire_camera_driver_node.h
index 976ce6040fdba4231954a9175968f280ae7b6224..0040d476154944f0e4bf29b10c4023101c59d571 100644
--- a/include/firewire_camera_driver_node.h
+++ b/include/firewire_camera_driver_node.h
@@ -86,6 +86,7 @@ class FirewireCameraDriverNode : public iri_base_driver::IriBaseNodeDriver<Firew
     CEventServer *event_server;
     std::string new_frame_event;
     std::string tf_prefix_;
+    std::string camera_name;
 
    /**
     * \brief post open hook
@@ -202,7 +203,7 @@ class FirewireCameraDriverNode : public iri_base_driver::IriBaseNodeDriver<Firew
 
 #include "nodelet/nodelet.h"
 
-class FirewireCameraNodelet : public nodelet::Nodelet
+class FirewireCameraDriverNodelet : public nodelet::Nodelet
 {
   private:
     FirewireCameraDriverNode *node;
@@ -213,7 +214,7 @@ class FirewireCameraNodelet : public nodelet::Nodelet
   protected:
     static void *spin_thread(void *param);
   public:
-    FirewireCameraNodelet();
+    FirewireCameraDriverNodelet();
 
    /**
     * \brief Destructor
@@ -221,8 +222,8 @@ class FirewireCameraNodelet : public nodelet::Nodelet
     * This destructor is called when the object is about to be destroyed.
     *
     */
-    ~FirewireCameraNodelet();
+    ~FirewireCameraDriverNodelet();
 };
 
 
-#endif
+#endif
\ No newline at end of file
diff --git a/launch/camera0rgb.launch b/launch/camera0rgb.launch
deleted file mode 100644
index 748bc50609aedee3e659546d11a372e14d25e9b5..0000000000000000000000000000000000000000
--- a/launch/camera0rgb.launch
+++ /dev/null
@@ -1,9 +0,0 @@
-<!-- -->
-<launch>
-
-       <node name="iri_firewire_camera" pkg="iri_firewire_camera" type="iri_firewire_camera" output="screen">
-       <param name="Camera_node" value="0" />
-       <param name="Framerate" value="30" />
-       <param name="Color_coding" value="3" />
-       </node>
-</launch>
diff --git a/launch/camera_flea.launch b/launch/camera_flea.launch
deleted file mode 100644
index 9a200220d6f465ba01b0653338b6b92f3ece91dc..0000000000000000000000000000000000000000
--- a/launch/camera_flea.launch
+++ /dev/null
@@ -1,24 +0,0 @@
-<!-- -->
-<launch>
-
-  <node pkg="iri_firewire_camera"
-        name="iri_firewire_camera"
-        type="iri_firewire_camera"
-        output="screen">
-    <!--<param name="Camera_serial"  value="00b09d01006cf72a" />-->
-    <param name="Camera_node"  value="0" />
-    <param name="Color_coding" value="3" />
-    <param name="ISO_speed"    value="400" />
-    <param name="Framerate"    value="2.5" />
-    <param name="Image_width"  value="1024" />
-    <param name="Image_height" value="768" />
-  </node>
-
-<!--  <node pkg="image_view"
-        type="image_view"
-        name="image_view" >
-    <remap from="/image" to="/iri_firewire_camera/camera_image"/>
-  </node>-->
-
-
-</launch>
diff --git a/launch/crop_by_2_rect.launch b/launch/crop_by_2_rect.launch
deleted file mode 100644
index 7f11c67ede58d37fe484a6b8fb41db2c14f443a0..0000000000000000000000000000000000000000
--- a/launch/crop_by_2_rect.launch
+++ /dev/null
@@ -1,31 +0,0 @@
-<!-- -->
-<launch>
-
-  <!-- published topics: /processed_image -->
-  <!-- subscribed topics: /camera/image_raw -->
-  <!--                    /camera/camera_info -->
-  <!-- service clients: -->
-  <!-- service servers: -->
-  <!-- action clients: -->
-  <!-- action servers: -->
-  <!-- image crop -->
-  <node pkg ="nodelet"
-        type="nodelet"
-        name="image_proc_dec"
-        args="standalone image_proc/crop_decimate">
-    <param name="decimation_x" value="2" />
-    <param name="decimation_y" value="2" />
-  </node>
-
-  <!-- image rectification -->
-  <node pkg ="image_proc"
-        type="image_proc"
-        name="image_proc_rect">
-    <remap from="/image_raw"
-             to="/camera_out/image_raw" />
-    <remap from="/camera_info"
-             to="/camera_out/camera_info" />
-    <remap from="/image_rect_color"
-             to="/processed_image" />
-  </node>
-</launch>
diff --git a/launch/firewire.launch b/launch/firewire.launch
deleted file mode 100755
index 50aad10f92efcd6bedd9119907242b1f03e17f1b..0000000000000000000000000000000000000000
--- a/launch/firewire.launch
+++ /dev/null
@@ -1,72 +0,0 @@
-<!-- -->
-<launch>
-
-  <!-- bumblebee -->
-  <!-- published topics: /sensors/head_right/image_raw -->
-  <!-- subscribed topics: -->
-  <!-- service clients: -->
-  <!-- service servers: -->
-  <!-- action clients: -->
-  <!-- action servers: -->
-  <node pkg ="iri_firewire_camera"
-        type="iri_firewire_camera"
-        name="bumblebee"
-        output="screen">
-    <remap from="/bumblebee/camera_image"
-             to="/sensors/head_right/image_raw"/>
-    <!--<param name="Camera_node"  value="0" />-->
-    <!--<param name="Camera_serial"  value="00b09d01006b6fb5" />-->
-    <param name="Camera_serial"  value="00b09d0100a96262" />
-    <param name="frame_id"     value="bumblebee_right" type="string" />
-    <!-- set calibration file -->
-    <param name="cal_file"     value="file://$(find iri_firewire_camera)/calibration/tibi_right_camera.yaml" type="string" />
-    <param name="ISO_speed"    value="400" />
-    <param name="Framerate"    value="1.875" />
-    <param name="Color_coding" value="6" />
-    <param name="Image_width"  value="1024" />
-    <param name="Image_height" value="768" />
-    <param name="Shutter_enabled"   value="True"/>
-    <param name="Shutter_mode"      value="0" />
-    <param name="Shutter_value"     value="10"/>
-    <param name="~tf_prefix"   value="/bumblebee_frame" type="str"/>
-  </node>
-
-  <!-- published topics: /processed_image -->
-  <!-- subscribed topics: /sensors/head_right/image_raw -->
-  <!--                    /sensors/head_right/camera_info -->
-  <!-- service clients: -->
-  <!-- service servers: -->
-  <!-- action clients: -->
-  <!-- action servers: -->
-  <!-- image crop -->
-  <node pkg ="nodelet"
-        type="nodelet"
-        name="image_proc_dec"
-        args="standalone image_proc/crop_decimate">
-    <param name="decimation_x" value="2" />
-    <param name="decimation_y" value="2" />
-    <remap from="/camera/image_raw"
-             to="/sensors/head_right/image_raw"/>
-    <remap from="/camera/camera_info"
-             to="/sensors/head_right/camera_info"/>
-  </node>
-
-  <!-- image rectification -->
-  <node pkg ="image_proc"
-        type="image_proc"
-        name="image_proc_rect">
-    <remap from="/image_raw"
-             to="/camera_out/image_raw" />
-    <remap from="/camera_info"
-             to="/camera_out/camera_info" />
-    <remap from="/image_rect_color"
-             to="/processed_image" />
-  </node>
-
-  <node pkg="image_view"
-        type="image_view"
-        name="image_view" >
-    <remap from="/image" to="/processed_image"/>
-  </node>
-
-</launch>
diff --git a/launch/firewire_arpose_nodelet.launch b/launch/firewire_arpose_nodelet.launch
deleted file mode 100755
index 4dcb332524da0dd21955925e29b8611572564c9a..0000000000000000000000000000000000000000
--- a/launch/firewire_arpose_nodelet.launch
+++ /dev/null
@@ -1,70 +0,0 @@
-<!-- -->
-<launch>
-  <node pkg="nodelet" type="nodelet" name="standalone_nodelet"  args="manager" output="screen">
-    <!--<param name="Camera_serial" value="00b09d01006cf72a" />--> <!-- tibi rear left -->
-    <param name="Camera_serial" value="00b09d0100a96262" /> <!-- tibi rear right  -->
-    <param name="frame_id"      value="bumblebee_frame" type="string" />
-    <param name="cal_file"      value="file://$(find iri_firewire_camera)/calibration/tibi_right_camera.yaml" type="string" />
-    <param name="ISO_speed"     value="800" />
-    <param name="Framerate"     value="2.5" />
-    <param name="Color_coding"  value="6" />
-    <param name="Image_width"   value="1024" />
-    <param name="Image_height"  value="768" />
-    <param name="Shutter_enabled"   value="True"/>
-    <param name="Shutter_mode"      value="1" />
-    <param name="Shutter_value"     value="10"/>
-    <param name="autosize"      value="true"/>
-    <remap from="/standalone_nodelet/camera_image"
-             to="/camera/image_raw" />
-    <remap from="/standalone_nodelet/camera_info"
-             to="/camera/camera_info" />
-  </node>
-
-  <!-- firewire camera driver -->
-  <node pkg="nodelet" type="nodelet" name="iri_firewire_nodelet" args="load iri_firewire_camera/FirewireCameraNodelet standalone_nodelet" output="screen">
-  </node>
-
-  <node pkg ="nodelet" type="nodelet" name="image_proc_debayer" args="load image_proc/debayer standalone_nodelet" output="screen">
-    <remap from="/image_raw"
-             to="/camera/image_raw"/>
-    <remap from="/camera_info"
-             to="/camera/camera_info"/>
-    <remap from="/image_mono"
-             to="/camera/image_mono"/>
-  </node>
-  <!-- image rectification -->
-  <node pkg ="nodelet" type="nodelet" name="image_proc_rect" args="load image_proc/rectify standalone_nodelet" output="screen">
-    <remap from="/image_mono"
-             to="/camera/image_mono"/>
-    <remap from="/camera_info"
-             to="/camera/camera_info"/>
-    <remap from="/image_rect"
-             to="/camera/image_rect"/>
-  </node>
-
-  <node pkg ="nodelet" type="nodelet" name="local_th" args="load iri_image_local_binarization/ImageLocalBinNodelet standalone_nodelet" output="screen">
-    <remap from="local_th/image_in/image_raw"
-             to="/camera/image_rect"/>
-    <remap from="local_th/image_in/camera_info"
-             to="/camera/camera_info"/>
-    <remap from="local_th/image_out/image_raw"
-             to="/ar_pose/image_raw"/>
-    <remap from="local_th/image_out/camera_info"
-             to="/ar_pose/camera_info"/>
-  </node>
-
-  <node name="ar_pose"
-        pkg ="ar_pose"
-        type="ar_multi"
-        respawn="false"
-        output="screen">
-    <param name="marker_pattern_list" type="string" value="$(find iri_ladybug2)/data/object_4x4_front"/>
-    <param name="threshold"       type="int"    value="100"/>
-    <param name="use_history"     type="bool"   value="true"/>
-    <remap from="/camera/image_raw"
-             to="/ar_pose/image_raw"/>
-    <remap from="/camera/camera_info"
-             to="/ar_pose/camera_info"/>
-  </node>
-
-</launch>
diff --git a/launch/firewire_nodelet.launch b/launch/firewire_nodelet.launch
deleted file mode 100755
index fbd7abe8fe4db4201b404a37e796a4e5cbfca49b..0000000000000000000000000000000000000000
--- a/launch/firewire_nodelet.launch
+++ /dev/null
@@ -1,44 +0,0 @@
-<!-- -->
-<launch>
-  <node pkg="nodelet" type="nodelet" name="standalone_nodelet"  args="manager" output="screen">
-    <param name="Camera_node"   value="0" />
-    <!--<param name="Camera_serial" value="00b09d01006b6fb5" />-->
-    <param name="frame_id"      value="bumblebee_frame" type="string" />
-    <param name="cal_file"      value="file://$(find iri_firewire_camera)/calibration/tibi_right_camera.yaml" type="string" />
-    <param name="ISO_speed"     value="800" />
-    <param name="Framerate"     value="2.5" />
-    <param name="Color_coding"  value="3" />
-    <param name="Image_width"   value="1024" />
-    <param name="Image_height"  value="768" />
-    <param name="autosize"      value="true"/>
-    <remap from="/camera_out/image_raw"
-             to="/image_mono" />
-    <remap from="/camera_out/camera_info"
-             to="/camera_info" />
-    <remap from="/camera/image_raw"
-             to="/standalone_nodelet/camera_image" />
-    <remap from="/camera/camera_info"
-             to="/standalone_nodelet/camera_info" />
-    <remap from="image"
-             to="/image_rect" />
-  </node>
-
-  <!-- firewire camera driver -->
-  <node pkg="nodelet" type="nodelet" name="iri_firewire_nodelet" args="load iri_firewire_camera/FirewireCameraNodelet standalone_nodelet" output="screen">
-  </node>
-
-  <!-- image decimation -->
-  <node pkg ="nodelet" type="nodelet" name="image_proc_dec" args="load image_proc/crop_decimate standalone_nodelet" output="screen">
-    <param name="decimation_x" value="2" />
-    <param name="decimation_y" value="2" />
-  </node>
-
-  <!-- image rectification -->
-  <node pkg ="nodelet" type="nodelet" name="image_proc_rect" args="load image_proc/rectify standalone_nodelet" output="screen">
-  </node>
-
-  <!-- image view -->
-  <node pkg="nodelet" type="nodelet" name="image" args="load image_view/image standalone_nodelet" output="screen">
-  </node>
-
-</launch>
diff --git a/launch/node.launch b/launch/node.launch
new file mode 100644
index 0000000000000000000000000000000000000000..a6bbe947031965557c5de5a34e03747ad2eb15b1
--- /dev/null
+++ b/launch/node.launch
@@ -0,0 +1,33 @@
+<?xml version="1.0"?>
+<!-- -->
+<launch>
+
+  <arg name="ns" default="robot" />
+  <arg name="name" default="firewire"/>
+  <arg name="config_file" default="$(find iri_firewire_camera_driver)/config/default_camera.yaml" />
+  <arg name="cal_file"  default="file://$(find iri_firewire_camera_driver)/calibration/default_camera.yaml"/>
+  <arg name="output" default="screen" />
+  <arg name="launch_prefix" default="" />
+
+  <group ns="$(arg ns)">
+    
+    <node pkg ="iri_firewire_camera_driver"
+          type="iri_firewire_camera_driver"
+          name="$(arg name)"
+          output="$(arg output)"
+          launch-prefix="$(arg launch_prefix)">
+      <rosparam file="$(arg config_file)" command="load" />
+      <param name="cal_file"  value="$(arg cal_file)"/>
+    </node>
+    
+  </group>
+
+</launch>
+
+<!--
+published
+
+/<arg ns>/<arg name>/*
+/robot/firewire/image_raw
+/robot/firewire/camera_info
+-->
\ No newline at end of file
diff --git a/launch/nodelet.launch b/launch/nodelet.launch
new file mode 100644
index 0000000000000000000000000000000000000000..69df5292aa636f265eca89cbbe10e90fa4afe486
--- /dev/null
+++ b/launch/nodelet.launch
@@ -0,0 +1,34 @@
+<?xml version="1.0"?>
+<!-- -->
+<launch>
+
+  <arg name="name" default="robot" />
+  <arg name="config_file" default="$(find iri_firewire_camera_driver)/config/default_camera.yaml" />
+  <arg name="output" default="log" />
+  <arg name="launch_prefix" default="" />
+
+  <group ns="$(arg name)">
+
+    <node pkg ="nodelet" 
+          type="nodelet" 
+          name="standalone_nodelet"  
+          args="manager" 
+          output="$(arg output)"
+          launch-prefix="$(arg launch_prefix)"/>
+    
+    <node pkg="nodelet"
+          type="nodelet"
+          name="iri_firewire_camera_driver_nodelet"
+          args="load iri_firewire_camera_driver/FirewireCameraDriverNodelet standalone_nodelet"
+          output="$(arg output)"
+          launch-prefix="$(arg launch_prefix)">
+      <rosparam file="$(arg config_file)" command="load" />
+    </node>
+    
+  </group>
+
+</launch>
+
+<!-- TODO remaps image_raw, camera_info-->
+<!-- TODO params nodelet? -->
+<!-- TODO test with image_proc/crop_decimate, image_proc/rectify -->
\ No newline at end of file
diff --git a/launch/tibi_dabo_crop_by_2_rect.launch b/launch/tibi_dabo_crop_by_2_rect.launch
deleted file mode 100644
index 1eab31a45baaf4e126eca9fdc62ef687d971f9fd..0000000000000000000000000000000000000000
--- a/launch/tibi_dabo_crop_by_2_rect.launch
+++ /dev/null
@@ -1,42 +0,0 @@
-<launch>
-
-  <!-- load robot defined machines -->
-  <include file="$(find tibi_dabo_base)/machines/$(env ROBOT)_$(env ROS_MODE).machines" />
-
-  <group ns="$(env ROBOT)">
-    <!-- published topics: /$(env ROBOT)/processed_image -->
-    <!-- subscribed topics: /$(env ROBOT)/sensors/head_right/image_raw -->
-    <!--                    /$(env ROBOT)/sensors/head_right/camera_info -->
-    <!-- service clients: -->
-    <!-- service servers: -->
-    <!-- action clients: -->
-    <!-- action servers: -->
-    <!-- image crop -->
-    <node pkg ="nodelet"
-          type="nodelet"
-          name="image_proc_dec"
-          machine="visio"
-          args="standalone image_proc/crop_decimate">
-      <param name="decimation_x" value="2" />
-      <param name="decimation_y" value="2" />
-      <remap from="/$(env ROBOT)/camera/image_raw"
-               to="/$(env ROBOT)/sensors/head_right/image_raw"/>
-      <remap from="/$(env ROBOT)/camera/camera_info"
-               to="/$(env ROBOT)/sensors/head_right/camera_info"/>
-    </node>
-
-    <!-- image rectification -->
-    <node pkg ="image_proc"
-          type="image_proc"
-          name="image_proc_rect"
-          machine="visio">
-      <remap from="/$(env ROBOT)/image_raw"
-               to="/$(env ROBOT)/camera_out/image_raw" />
-      <remap from="/$(env ROBOT)/camera_info"
-               to="/$(env ROBOT)/camera_out/camera_info" />
-      <remap from="/$(env ROBOT)/image_rect_color"
-               to="/$(env ROBOT)/processed_image" />
-    </node>
-  </group>
-</launch>
-
diff --git a/mainpage.dox b/mainpage.dox
deleted file mode 100644
index 1fb14f58f0d5c719de3759a6bdb55c0d9019210c..0000000000000000000000000000000000000000
--- a/mainpage.dox
+++ /dev/null
@@ -1,26 +0,0 @@
-/**
-\mainpage
-\htmlinclude manifest.html
-
-\b firewire_camera_node is ... 
-
-<!-- 
-Provide an overview of your package.
--->
-
-
-\section codeapi Code API
-
-<!--
-Provide links to specific auto-generated API documentation within your
-package that is of particular interest to a reader. Doxygen will
-document pretty much every part of your code, so do your best here to
-point the reader to the actual API.
-
-If your codebase is fairly large or has different sets of APIs, you
-should use the doxygen 'group' tag to keep these APIs together. For
-example, the roscpp documentation has 'libros' group.
--->
-
-
-*/
diff --git a/package.xml b/package.xml
index 99c438411984c5328fdb2eb52ccb8bbbd376e77f..cd7fa94e66cddbd68059a9551037748c5d0dc643 100644
--- a/package.xml
+++ b/package.xml
@@ -1,18 +1,17 @@
 <?xml version="1.0"?>
 <package>
-  <name>iri_firewire_camera</name>
+  <name>iri_firewire_camera_driver</name>
   <version>1.0.0</version>
   <description>Firewire camera driver</description>
 
   <!-- One maintainer tag required, multiple allowed, one person per tag --> 
   <!-- Example:  -->
-  <maintainer email="shernand@iri.upc.edu">Sergi Hernandez</maintainer>
   <maintainer email="labrobotica@iri.upc.edu">labrobotica</maintainer>
 
   <!-- One license tag required, multiple allowed, one license per tag -->
   <!-- Commonly used license strings: -->
   <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
-  <license>BSD</license>
+  <license>LGPL</license>
 
   <!-- Url tags are optional, but mutiple are allowed, one per tag -->
   <!-- Optional attribute type can be: website, bugtracker, or repository -->
@@ -30,10 +29,10 @@
   <!--                 Place build dependencies here                      -->
   <!-- ****************************************************************** -->
   <!--   <build_depend>message_generation</build_depend> -->
-  <build_depend>iriutils</build_depend>
-  <build_depend>firewire</build_depend>
-  <build_depend>raw1394</build_depend>
-  <build_depend>dc1394</build_depend>
+  <!--<build_depend>iriutils</build_depend>-->
+  <!--<build_depend>firewire</build_depend>-->
+  <!--<build_depend>raw1394</build_depend>-->
+  <!--<build_depend>dc1394</build_depend>-->
   <build_depend>iri_base_driver</build_depend>
   <build_depend>sensor_msgs</build_depend>
   <build_depend>image_transport</build_depend>
@@ -44,10 +43,10 @@
   <!--                   Place run dependencies here                      -->
   <!-- ****************************************************************** -->
   <!--   <run_depend>message_runtime</run_depend> -->
-  <run_depend>iriutils</run_depend>
-  <run_depend>firewire</run_depend>
-  <run_depend>raw1394</run_depend>
-  <run_depend>dc1394</run_depend>
+  <!--<run_depend>iriutils</run_depend>-->
+  <!--<run_depend>firewire</run_depend>-->
+  <!--<run_depend>raw1394</run_depend>-->
+  <!--<run_depend>dc1394</run_depend>-->
   <run_depend>iri_base_driver</run_depend>
   <run_depend>sensor_msgs</run_depend>
   <run_depend>image_transport</run_depend>
@@ -57,10 +56,10 @@
   <!-- Use test_depend for packages you need only for testing: -->
   <!--   <test_depend>gtest</test_depend> -->
   <buildtool_depend>catkin</buildtool_depend>
-
+  
   <!-- The export tag contains other, unspecified, tags -->
   <export>
     <!-- Other tools can request additional information be placed here -->
-    <nodelet plugin="${prefix}/firewire_nodelet_plugin.xml" />
+    <nodelet plugin="${prefix}/firewire_camera_driver_nodelet_plugin.xml" />
   </export>
 </package>
diff --git a/src/firewire_camera_driver.cpp b/src/firewire_camera_driver.cpp
index 254df2a33001663a8f0823a885ca89c531dc8b40..528c8f6778f89be80d92f504c751de102858adcf 100644
--- a/src/firewire_camera_driver.cpp
+++ b/src/firewire_camera_driver.cpp
@@ -59,6 +59,7 @@ bool FirewireCameraDriver::openDriver(void)
         this->server->get_camera_guid(serial,&this->camera);
       }
       this->camera->set_ISO_speed(this->ISO_speed);
+      //this->camera->show_features();
       this->camera->get_config(&this->default_conf.left_offset,&this->default_conf.top_offset,&this->default_conf.width,
                                &this->default_conf.height,&this->default_conf.framerate,&this->default_conf.depth,
                                &this->default_conf.coding);
@@ -67,7 +68,7 @@ bool FirewireCameraDriver::openDriver(void)
       if((this->cal_width!=-1 && this->desired_conf.width!=this->cal_width) ||
          (this->cal_height!=-1 && this->desired_conf.height!=this->cal_height))
       {
-        ROS_ERROR("The calibration file does not coincide with the current configuration ");
+        ROS_ERROR("FirewireCameraDriver: The calibration file does not coincide with the current configuration ");
         delete this->camera;
         this->camera=NULL;
         return false;
@@ -79,18 +80,18 @@ bool FirewireCameraDriver::openDriver(void)
       this->set_shutter(&this->config_.Shutter_enabled,&this->config_.Shutter_mode,&this->config_.Shutter_value);
       // gain feature
       this->set_gain(&this->config_.Gain_enabled,&this->config_.Gain_mode,&this->config_.Gain_value);
-      ROS_INFO("Driver opened");
+      ROS_INFO("FirewireCameraDriver: Driver opened");
       return true;
     }
     else
     {   
-      ROS_INFO("No cameras available");
+      ROS_ERROR("FirewireCameraDriver: No cameras available");
       return false;
     }
   }
   else
   {
-    ROS_INFO("Waiting for a valid id ...");
+    ROS_WARN("FirewireCameraDriver: Waiting for a valid id ...");
     return false;
   
   }
@@ -115,11 +116,11 @@ bool FirewireCameraDriver::startDriver(void)
       this->lock();
       this->camera->start();
       this->unlock();
-      ROS_INFO("Driver started");
+      ROS_INFO("FirewireCameraDriver: Driver started");
       return true;
     }catch(CException &e){
       this->unlock();
-      //ROS_INFO(e.what().data());
+      ROS_ERROR("FirewireCameraDriver:startDriver:Exception: %s", e.what().data());
       return false;
     }
   }
@@ -135,11 +136,11 @@ bool FirewireCameraDriver::stopDriver(void)
       this->lock();
       this->camera->stop();
       this->unlock();
-      ROS_INFO("Driver stopped");
+      ROS_INFO("FirewireCameraDriver: Driver stopped");
       return true;
     }catch(CException &e){
       this->unlock();
-      //ROS_INFO(e.what().data());
+      ROS_ERROR("FirewireCameraDriver:stopDriver:Exception: %s", e.what().data());
       return false;
     }
   }
@@ -155,7 +156,7 @@ void FirewireCameraDriver::config_update(Config& new_cfg, uint32_t level)
   // update driver with new_cfg data
   switch(this->getState())
   {
-    case FirewireCameraDriver::CLOSED:
+    case iri_base_driver::CLOSED:
       this->lock();
       this->camera_id=new_cfg.Camera_node;
       this->camera_serial=new_cfg.Camera_serial;
@@ -166,7 +167,7 @@ void FirewireCameraDriver::config_update(Config& new_cfg, uint32_t level)
       this->unlock();
       break;
 
-    case FirewireCameraDriver::OPENED:
+    case iri_base_driver::OPENED:
       if(new_cfg.Camera_node!=-1)
       {
         try{
@@ -175,15 +176,15 @@ void FirewireCameraDriver::config_update(Config& new_cfg, uint32_t level)
           this->ISO_speed=new_cfg.ISO_speed;
           if(this->camera_id!=new_cfg.Camera_node)
           {
-            this->close();
+            this->closeDriver();
             this->camera_id=new_cfg.Camera_node;
-            this->open();
+            this->openDriver();
           }
           if(this->camera_serial!=new_cfg.Camera_serial)
           {
-            this->close();
+            this->closeDriver();
             this->camera_serial=new_cfg.Camera_serial;
-            this->open();
+            this->openDriver();
           }
           this->dyn_rec_to_camera(new_cfg,conf);
           this->change_config(&conf);
@@ -200,7 +201,7 @@ void FirewireCameraDriver::config_update(Config& new_cfg, uint32_t level)
           this->frame_id=new_cfg.frame_id;
           this->unlock();
         }catch(CFirewireCameraException &e){
-          ROS_INFO("Invalid configuration. Setting back the default configuration ...");
+          ROS_WARN("FirewireCameraDriver:config_update: Invalid configuration. Setting back the default configuration ...[%s]", e.what().c_str());
           this->change_config(&this->default_conf);
           this->camera_to_dyn_rec(this->default_conf,new_cfg);
           this->unlock();
@@ -208,7 +209,7 @@ void FirewireCameraDriver::config_update(Config& new_cfg, uint32_t level)
       }
       break;
 
-    case FirewireCameraDriver::RUNNING:
+    case iri_base_driver::RUNNING:
       break;
   }
 
@@ -216,7 +217,7 @@ void FirewireCameraDriver::config_update(Config& new_cfg, uint32_t level)
   this->config_=new_cfg;
 }
 
-void FirewireCameraDriver::dyn_rec_to_camera(iri_firewire_camera::FirewireCameraConfig &dyn_rec_config,TCameraConfig &camera_config)
+void FirewireCameraDriver::dyn_rec_to_camera(iri_firewire_camera_driver::FirewireCameraDriverConfig &dyn_rec_config,TCameraConfig &camera_config)
 {
   camera_config.left_offset=dyn_rec_config.Left_offset;
   camera_config.top_offset=dyn_rec_config.Top_offset;
@@ -255,7 +256,7 @@ void FirewireCameraDriver::dyn_rec_to_camera(iri_firewire_camera::FirewireCamera
   }
 }
 
-void FirewireCameraDriver::camera_to_dyn_rec(TCameraConfig &camera_config,iri_firewire_camera::FirewireCameraConfig &dyn_rec_config)
+void FirewireCameraDriver::camera_to_dyn_rec(TCameraConfig &camera_config,iri_firewire_camera_driver::FirewireCameraDriverConfig &dyn_rec_config)
 {
   dyn_rec_config.Left_offset=camera_config.left_offset;
   dyn_rec_config.Top_offset=camera_config.top_offset;
@@ -313,7 +314,7 @@ void FirewireCameraDriver::change_config(TCameraConfig *new_conf)
       new_conf->coding=current_conf.coding;
     }
   }catch(CFirewireCameraException &e){
-    ROS_INFO("Invalid configuration. Setting back the default configuration ...");
+    ROS_WARN("FirewireCameraDriver:change_config: Invalid configuration. Setting back the default configuration ...[%s]", e.what().c_str());
     this->change_config(&this->default_conf);
     new_conf->left_offset=this->default_conf.left_offset;
     new_conf->top_offset=this->default_conf.top_offset;
@@ -339,7 +340,7 @@ void FirewireCameraDriver::set_white_balance(bool *enable,int *mode, int *u_b_va
             this->camera->enable_feature(DC1394_FEATURE_WHITE_BALANCE);
         }catch(CFirewireFeatureException &e){
           (*enable)=false;
-          ROS_INFO("The white balance feature can not be enabled");
+          ROS_WARN("FirewireCameraDriver: The white balance feature can not be enabled");
           return;
         }
         if((*mode)==0)
@@ -348,7 +349,7 @@ void FirewireCameraDriver::set_white_balance(bool *enable,int *mode, int *u_b_va
             this->camera->set_feature_auto(DC1394_FEATURE_WHITE_BALANCE);
           }catch(CFirewireFeatureException &e){
             (*mode)=1;
-            ROS_INFO("The white balance feature can not be set in auto mode");
+            ROS_WARN("FirewireCameraDriver: The white balance feature can not be set in auto mode");
             return;
           }
         }
@@ -358,14 +359,14 @@ void FirewireCameraDriver::set_white_balance(bool *enable,int *mode, int *u_b_va
             this->camera->set_feature_manual(DC1394_FEATURE_WHITE_BALANCE);
           }catch(CFirewireFeatureException &e){
             (*mode)=0;
-            ROS_INFO("The white balance feature can not be set in manual mode");
+            ROS_WARN("FirewireCameraDriver: The white balance feature can not be set in manual mode");
             return;
           }
           try{
             this->camera->set_white_balance_value((*u_b_value),(*v_r_value));
           }catch(CFirewireFeatureException &e){
             this->camera->get_white_balance_value((unsigned int *)u_b_value,(unsigned int *)v_r_value);
-            ROS_INFO("The white balance value is out of range");
+            ROS_WARN("FirewireCameraDriver: The white balance value is out of range");
             return;
           }
         }
@@ -377,7 +378,7 @@ void FirewireCameraDriver::set_white_balance(bool *enable,int *mode, int *u_b_va
             this->camera->disable_feature(DC1394_FEATURE_WHITE_BALANCE);
         }catch(CFirewireFeatureException &e){
           (*enable)=true;
-          ROS_INFO("The white balance feature can not be disabled");
+          ROS_WARN("FirewireCameraDriver: The white balance feature can not be disabled");
           return;
         }
       }
@@ -385,10 +386,10 @@ void FirewireCameraDriver::set_white_balance(bool *enable,int *mode, int *u_b_va
     else
     {
       (*enable)=false;
-      ROS_INFO("The white balance feature is not present");
+      ROS_WARN("FirewireCameraDriver: The white balance feature is not present");
     }
   }catch(CFirewireInternalException &e){
-    ROS_INFO("Impossible to set the white balance feature");
+    ROS_ERROR("FirewireCameraDriver: Impossible to set the white balance feature");
   }
 }
 
@@ -404,7 +405,7 @@ void FirewireCameraDriver::set_shutter(bool *enable,int *mode, int *value)
             this->camera->enable_feature(DC1394_FEATURE_SHUTTER);
         }catch(CFirewireFeatureException &e){
           (*enable)=false;
-          ROS_INFO("The shutter feature is not present");
+          ROS_WARN("FirewireCameraDriver: The shutter feature is not present");
           return;
         }
         if((*mode)==0)
@@ -413,7 +414,7 @@ void FirewireCameraDriver::set_shutter(bool *enable,int *mode, int *value)
             this->camera->set_feature_auto(DC1394_FEATURE_SHUTTER);
           }catch(CFirewireFeatureException &e){
             (*mode)=1;
-            ROS_INFO("The shutter feature can not be set in auto mode");
+            ROS_WARN("FirewireCameraDriver: The shutter feature can not be set in auto mode");
             return;
           }
         }
@@ -423,14 +424,14 @@ void FirewireCameraDriver::set_shutter(bool *enable,int *mode, int *value)
             this->camera->set_feature_manual(DC1394_FEATURE_SHUTTER);
           }catch(CFirewireFeatureException &e){
             (*mode)=0;
-            ROS_INFO("The shutter feature can not be set in manual mode");
+            ROS_WARN("FirewireCameraDriver: The shutter feature can not be set in manual mode");
             return;
           }
           try{
             this->camera->set_feature_value(DC1394_FEATURE_SHUTTER,(*value));
           }catch(CFirewireFeatureException &e){
             (*value)=this->camera->get_feature_value(DC1394_FEATURE_SHUTTER);
-            ROS_INFO("The shutter value is out of range");
+            ROS_WARN("FirewireCameraDriver: The shutter value is out of range");
             return;
           }
         }
@@ -442,7 +443,7 @@ void FirewireCameraDriver::set_shutter(bool *enable,int *mode, int *value)
             this->camera->disable_feature(DC1394_FEATURE_SHUTTER);
         }catch(CFirewireFeatureException &e){
           (*enable)=true;
-          ROS_INFO("The shutter feature can not be disabled");
+          ROS_WARN("FirewireCameraDriver: The shutter feature can not be disabled");
           return;
         }
       }
@@ -450,10 +451,10 @@ void FirewireCameraDriver::set_shutter(bool *enable,int *mode, int *value)
     else
     {
       (*enable)=false;
-      ROS_INFO("The shutter feature is not present");
+      ROS_WARN("FirewireCameraDriver: The shutter feature is not present");
     }
   }catch(CFirewireInternalException &e){
-    ROS_INFO("Impossible to set the shutter feature");
+    ROS_ERROR("FirewireCameraDriver: Impossible to set the shutter feature");
   }
 }
 
@@ -469,7 +470,7 @@ void FirewireCameraDriver::set_gain(bool *enable, int *mode, int *value)
             this->camera->enable_feature(DC1394_FEATURE_GAIN);
         }catch(CFirewireFeatureException &e){
           (*enable)=false;
-          ROS_INFO("The gain feature is not present");
+          ROS_WARN("FirewireCameraDriver: The gain feature is not present");
           return;
         }
         if((*mode)==0)
@@ -478,7 +479,7 @@ void FirewireCameraDriver::set_gain(bool *enable, int *mode, int *value)
             this->camera->set_feature_auto(DC1394_FEATURE_GAIN);
           }catch(CFirewireFeatureException &e){
             (*mode)=1;
-            ROS_INFO("The gain feature can not be set in auto mode");
+            ROS_WARN("FirewireCameraDriver: The gain feature can not be set in auto mode");
             return;
           }
         }
@@ -488,14 +489,14 @@ void FirewireCameraDriver::set_gain(bool *enable, int *mode, int *value)
             this->camera->set_feature_manual(DC1394_FEATURE_GAIN);
           }catch(CFirewireFeatureException &e){
             (*mode)=0;
-            ROS_INFO("The gain feature can not be set in manual mode");
+            ROS_WARN("FirewireCameraDriver: The gain feature can not be set in manual mode");
             return;
           }
           try{
             this->camera->set_feature_value(DC1394_FEATURE_GAIN,(*value));
           }catch(CFirewireFeatureException &e){
             (*value)=this->camera->get_feature_value(DC1394_FEATURE_GAIN);
-            ROS_INFO("The gain value is out of range");
+            ROS_WARN("FirewireCameraDriver: The gain value is out of range");
             return;
           }
         }
@@ -507,7 +508,7 @@ void FirewireCameraDriver::set_gain(bool *enable, int *mode, int *value)
             this->camera->disable_feature(DC1394_FEATURE_GAIN);
         }catch(CFirewireFeatureException &e){
           (*enable)=true;
-          ROS_INFO("The gain feature can not be disabled");
+          ROS_WARN("FirewireCameraDriver: The gain feature can not be disabled");
           return;
         }
       }
@@ -515,10 +516,10 @@ void FirewireCameraDriver::set_gain(bool *enable, int *mode, int *value)
     else
     {
       (*enable)=false;
-      ROS_INFO("The gain feature is not present");
+      ROS_WARN("FirewireCameraDriver: The gain feature is not present");
     }
   }catch(CFirewireInternalException &e){
-    ROS_INFO("Impossible to set the gain feature");
+    ROS_ERROR("FirewireCameraDriver: Impossible to set the gain feature");
   }
 }
 
@@ -622,4 +623,4 @@ std::string FirewireCameraDriver::get_bayer_pattern(void)
 FirewireCameraDriver::~FirewireCameraDriver()
 {
   this->server->close();
-}
+}
\ No newline at end of file
diff --git a/src/firewire_camera_driver_node.cpp b/src/firewire_camera_driver_node.cpp
index d52b3ecd8993dbdc7b8c2f2bef3ff0da2a40a839..1667f556b0785261d69d54f98cf2f5caa2430fa1 100644
--- a/src/firewire_camera_driver_node.cpp
+++ b/src/firewire_camera_driver_node.cpp
@@ -1,46 +1,51 @@
 #include "firewire_camera_driver_node.h"
 
 FirewireCameraDriverNode::FirewireCameraDriverNode(ros::NodeHandle &nh) : iri_base_driver::IriBaseNodeDriver<FirewireCameraDriver>(nh), 
-                                                                          camera_manager(ros::NodeHandle(this->public_node_handle_))
+                                                                          camera_manager(ros::NodeHandle(nh))
 {
   std::string cal_file;
   bool cal_ok=false;
 
   //init class attributes if necessary
-  this->loop_rate_ = 1000;//in [Hz]
+  double loop_rate = 1000;//in [Hz]
+  this->setRate(loop_rate);
+  
   this->desired_framerate=30.0;
   this->diagnosed_camera_image=NULL;
 
-  this->camera.it.reset(new image_transport::ImageTransport(this->public_node_handle_));
+  this->camera.it.reset(new image_transport::ImageTransport(this->private_node_handle_));
   this->camera.Image_msg_=sensor_msgs::ImagePtr(new sensor_msgs::Image);
-  this->diagnosed_camera_image = new diagnostic_updater::HeaderlessTopicDiagnostic("camera_image",this->diagnostic_,
+  this->diagnosed_camera_image = new diagnostic_updater::HeaderlessTopicDiagnostic("image_raw",this->diagnostic_,
                                      diagnostic_updater::FrequencyStatusParam(&this->desired_framerate,&this->desired_framerate,0.01,5));
 
   this->event_server=CEventServer::instance();
 
+  
+  
   // [init publishers]
-  this->camera.camera_image_publisher_ = this->camera.it->advertiseCamera("camera_image", 1);
+  this->camera.camera_image_publisher_ = this->camera.it->advertiseCamera("image_raw", 1);
 
   // try to load the calibration file
-  public_node_handle_.param<std::string>("cal_file", cal_file, "");
-  this->camera_manager.setCameraName("firewire_camera");
+  private_node_handle_.param<std::string>("cal_file", cal_file, "");
+  private_node_handle_.param<std::string>("camera_name", this->camera_name, "firewire_camera");
+  this->camera_manager.setCameraName(this->camera_name);
   if(this->camera_manager.validateURL(cal_file))
   {
     if(this->camera_manager.loadCameraInfo(cal_file))
     {
-      ROS_INFO("Found calibration file for the camera: %s",cal_file.c_str());
+      ROS_INFO("FirewireCameraDriverNode: Found calibration file for the camera: %s",cal_file.c_str());
       cal_ok=true;
     }
     else
     {
-      ROS_INFO("Invalid calibration file for the camera");
+      ROS_ERROR("FirewireCameraDriverNode: Invalid calibration file for the camera: %s", cal_file.c_str());
       cal_ok=false;
     }
     this->camera.CameraInfo_msg_.reset(new sensor_msgs::CameraInfo(this->camera_manager.getCameraInfo()));
   }
   else
   {
-    ROS_INFO("Calibration file does not exist");
+    ROS_ERROR("FirewireCameraDriverNode: Calibration file does not exist: %s", cal_file.c_str());
     cal_ok=false;
   }
 
@@ -128,7 +133,7 @@ void FirewireCameraDriverNode::mainNodeThread(void)
     this->driver_.unlock();
   }catch(CException &e){
     this->driver_.unlock();
-    ROS_INFO("Impossible to capture frame");
+    ROS_ERROR("FirewireCameraDriverNode:Impossible to capture frame[%s]", e.what().c_str());
   }
   //fill srv structure and make request to the server
 }
@@ -212,17 +217,17 @@ FirewireCameraDriverNode::~FirewireCameraDriverNode()
 /* main function */
 int main(int argc,char *argv[])
 {
-  return driver_base::main<FirewireCameraDriverNode>(argc,argv,"firewire_camera_driver_node");
+  return iri_base_driver::main<FirewireCameraDriverNode>(argc,argv,"firewire_camera_driver_node");
 }
 
 #include <pluginlib/class_list_macros.h>
 
-FirewireCameraNodelet::FirewireCameraNodelet()
+FirewireCameraDriverNodelet::FirewireCameraDriverNodelet()
 {
   this->node=NULL;
 }
 
-FirewireCameraNodelet::~FirewireCameraNodelet(void)
+FirewireCameraDriverNodelet::~FirewireCameraDriverNodelet(void)
 {
   // kill the thread
   this->thread_server->kill_thread(this->spin_thread_id);
@@ -234,7 +239,7 @@ FirewireCameraNodelet::~FirewireCameraNodelet(void)
     delete this->node;
 }
 
-void FirewireCameraNodelet::onInit()
+void FirewireCameraDriverNodelet::onInit()
 {
   // initialize the driver node
   this->node=new FirewireCameraDriverNode(getPrivateNodeHandle());
@@ -247,9 +252,9 @@ void FirewireCameraNodelet::onInit()
   this->thread_server->start_thread(this->spin_thread_id);
 }
 
-void *FirewireCameraNodelet::spin_thread(void *param)
+void *FirewireCameraDriverNodelet::spin_thread(void *param)
 {
-  FirewireCameraNodelet *nodelet=(FirewireCameraNodelet *)param;
+  FirewireCameraDriverNodelet *nodelet=(FirewireCameraDriverNodelet *)param;
 
   nodelet->node->spin();
 
@@ -257,5 +262,4 @@ void *FirewireCameraNodelet::spin_thread(void *param)
 }
 
 // parameters are: package, class name, class type, base class type
-PLUGINLIB_DECLARE_CLASS(iri_firewire_camera, FirewireCameraNodelet, FirewireCameraNodelet, nodelet::Nodelet);
-
+PLUGINLIB_DECLARE_CLASS(iri_firewire_camera_driver, FirewireCameraDriverNodelet, FirewireCameraDriverNodelet, nodelet::Nodelet);
\ No newline at end of file