diff --git a/CMakeLists.txt b/CMakeLists.txt
index 53f54681664ae8a3d89df4f33f8805ff8245b1ff..4f7188378e3f250dae565a516efceb45e8b48bf6 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)
@@ -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
diff --git a/cfg/FirewireCamera.cfg b/cfg/FirewireCameraDriver.cfg
similarity index 98%
rename from cfg/FirewireCamera.cfg
rename to cfg/FirewireCameraDriver.cfg
index 3a19b37a35eeba63bfe5356a65f5228ca4238196..2e464e36b26981232b3be1b75333d22c6cc7a2f6 100755
--- a/cfg/FirewireCamera.cfg
+++ b/cfg/FirewireCameraDriver.cfg
@@ -31,9 +31,9 @@
 
 # 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()
@@ -73,4 +73,4 @@ gen.add("Gain_mode",               int_t,     SensorLevels.RECONFIGURE_STOP,   "
 gen.add("Gain_value",              int_t,     SensorLevels.RECONFIGURE_STOP,   "Gain value",                     0,        48,   730)
 import roslib; roslib.load_manifest(PACKAGE)
 
-exit(gen.generate(PACKAGE, "FirewireCameraDriver", "FirewireCamera"))
+exit(gen.generate(PACKAGE, "FirewireCameraDriver", "FirewireCameraDriver"))
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..3cf7744692c9e2a634e86234c387b4b3fd0037d0 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
diff --git a/include/firewire_camera_driver_node.h b/include/firewire_camera_driver_node.h
index 976ce6040fdba4231954a9175968f280ae7b6224..4e36f765349a886e6588d9b165079ee87677d4a8 100644
--- a/include/firewire_camera_driver_node.h
+++ b/include/firewire_camera_driver_node.h
@@ -202,7 +202,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 +213,7 @@ class FirewireCameraNodelet : public nodelet::Nodelet
   protected:
     static void *spin_thread(void *param);
   public:
-    FirewireCameraNodelet();
+    FirewireCameraDriverNodelet();
 
    /**
     * \brief Destructor
@@ -221,7 +221,7 @@ class FirewireCameraNodelet : public nodelet::Nodelet
     * This destructor is called when the object is about to be destroyed.
     *
     */
-    ~FirewireCameraNodelet();
+    ~FirewireCameraDriverNodelet();
 };
 
 
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..6fd2c4ba0595712781c635eba59e5057b92495c3 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 -->
@@ -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..bc077d3a04043356f0a6900586e6df57e4088eb1 100644
--- a/src/firewire_camera_driver.cpp
+++ b/src/firewire_camera_driver.cpp
@@ -155,7 +155,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 +166,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 +175,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);
@@ -208,7 +208,7 @@ void FirewireCameraDriver::config_update(Config& new_cfg, uint32_t level)
       }
       break;
 
-    case FirewireCameraDriver::RUNNING:
+    case iri_base_driver::RUNNING:
       break;
   }
 
@@ -216,7 +216,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 +255,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;
diff --git a/src/firewire_camera_driver_node.cpp b/src/firewire_camera_driver_node.cpp
index d52b3ecd8993dbdc7b8c2f2bef3ff0da2a40a839..770914c77ce7065cc0479c2ac35558388e1e1b34 100644
--- a/src/firewire_camera_driver_node.cpp
+++ b/src/firewire_camera_driver_node.cpp
@@ -7,7 +7,9 @@ FirewireCameraDriverNode::FirewireCameraDriverNode(ros::NodeHandle &nh) : iri_ba
   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;
 
@@ -212,17 +214,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 +236,7 @@ FirewireCameraNodelet::~FirewireCameraNodelet(void)
     delete this->node;
 }
 
-void FirewireCameraNodelet::onInit()
+void FirewireCameraDriverNodelet::onInit()
 {
   // initialize the driver node
   this->node=new FirewireCameraDriverNode(getPrivateNodeHandle());
@@ -247,9 +249,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 +259,5 @@ 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);