diff --git a/cfg/FirewireCamera.cfg b/cfg/FirewireCamera.cfg
index 18fdb0700476ac902f6938a593a6163ba8530499..9eaebda7624e2acf54f4d3c4259ea2e9d9f86ede 100755
--- a/cfg/FirewireCamera.cfg
+++ b/cfg/FirewireCamera.cfg
@@ -53,6 +53,7 @@ gen.const("RAW16", int_t, 7, "RAW coding with 16 bits per pixel")],"Available co
 #       Name                       Type       Reconfiguration level            Description                       Default   Min   Max
 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("cal_file",                str_t,     SensorLevels.RECONFIGURE_STOP,   "Camera calibration file",        "")
 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)
diff --git a/include/firewire_camera_driver.h b/include/firewire_camera_driver.h
index 18fa4e95fb5c933276a56d86fd7b897740d2b6be..4b39431829002ff15f1e0f32aa110cde90e259fe 100644
--- a/include/firewire_camera_driver.h
+++ b/include/firewire_camera_driver.h
@@ -58,7 +58,8 @@ class FirewireCameraDriver : public iri_base_driver::IriBaseDriver
     // private attributes and methods
     CFirewireCamera *camera;
     CFirewireServer *server;
-    long int camera_id;
+    int camera_id;
+    std::string camera_serial;
     int ISO_speed;
     // desired configuration
     TCameraConfig desired_conf;
diff --git a/launch/firewire.launch b/launch/firewire.launch
index 9490be351f3805de0aaf4b4e9f347b130e745bea..553e6da55c4383aee9492c50b3e3f5068f6ad05f 100755
--- a/launch/firewire.launch
+++ b/launch/firewire.launch
@@ -9,19 +9,20 @@
   <!-- action servers: -->
   <node pkg ="iri_firewire_camera"
         type="iri_firewire_camera"
-        name="bumblebee">
+        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="frame_id"     value="bumblebee_right" type="string" />
     <!-- set calibration file -->
-    <param name="cal_file"     value="file://$(find iri_firewire_camera)/calibration/$(env ROBOT)_right_camera.yaml" type="string" />
+    <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="7.5" />
     <param name="Color_coding" value="3" />
     <param name="Image_width"  value="1024" />
     <param name="Image_height" value="768" />
-    <param name="~tf_prefix"   value="/$(env ROBOT)" type="str"/>
+    <param name="~tf_prefix"   value="/bumblebee_frame" type="str"/>
   </node>
 
   <!-- published topics: /processed_image -->
diff --git a/launch/firewire_arpose_nodelet.launch b/launch/firewire_arpose_nodelet.launch
index 5a262097515ad953c763c585769d951ae7d8096b..6744c281cdb40419e21d6690bfafbf82049c3784 100755
--- a/launch/firewire_arpose_nodelet.launch
+++ b/launch/firewire_arpose_nodelet.launch
@@ -1,14 +1,14 @@
 <launch>
   <node pkg="nodelet" type="nodelet" name="standalone_nodelet"  args="manager" output="screen">
-    <param name="Camera_node"  value="2" />
-    <param name="frame_id"     value="bumblebee_frame" type="string" />
-    <param name="cal_file"     value="file://$(find iri_firewire_camera)/calibration/$(env ROBOT)_right_camera.yaml" type="string" />
-    <param name="ISO_speed"    value="400" />
-    <param name="Framerate"    value="7.5" />
-    <param name="Color_coding" value="6" />
-    <param name="Image_width"  value="1024" />
-    <param name="Image_height" value="768" />
-    <param name="autosize"     value="true"/>
+    <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="400" />
+    <param name="Framerate"     value="7.5" />
+    <param name="Color_coding"  value="6" />
+    <param name="Image_width"   value="1024" />
+    <param name="Image_height"  value="768" />
+    <param name="autosize"      value="true"/>
     <remap from="/standalone_nodelet/camera_image"
              to="/camera/image_raw" />
     <remap from="/standalone_nodelet/camera_info"
diff --git a/launch/firewire_nodelet.launch b/launch/firewire_nodelet.launch
index 07bcfc93090bdbf464884cb566757108edf49aa2..9c04521badfd51bd0de88b6f5012bb1e98bda420 100755
--- a/launch/firewire_nodelet.launch
+++ b/launch/firewire_nodelet.launch
@@ -1,14 +1,14 @@
 <launch>
   <node pkg="nodelet" type="nodelet" name="standalone_nodelet"  args="manager" output="screen">
-    <param name="Camera_node"  value="1" />
-    <param name="frame_id"     value="bumblebee_frame" type="string" />
-    <param name="cal_file"     value="file://$(find iri_firewire_camera)/calibration/$(env ROBOT)_right_camera.yaml" type="string" />
-    <param name="ISO_speed"    value="400" />
-    <param name="Framerate"    value="7.5" />
-    <param name="Color_coding" value="3" />
-    <param name="Image_width"  value="1024" />
-    <param name="Image_height" value="768" />
-    <param name="autosize"     value="true"/>
+    <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="400" />
+    <param name="Framerate"     value="7.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"
diff --git a/src/firewire_camera_driver.cpp b/src/firewire_camera_driver.cpp
index 0db011172d277203b9b78b3d4f6fb1a4dac9ced6..119860a405450608ede9cb8f1edf083ab4637715 100644
--- a/src/firewire_camera_driver.cpp
+++ b/src/firewire_camera_driver.cpp
@@ -40,13 +40,23 @@ FirewireCameraDriver::FirewireCameraDriver()
 
 bool FirewireCameraDriver::openDriver(void)
 {
+  std::stringstream buffer;
+  unsigned long long serial;
+
   //setDriverId(driver string id);
-  if(this->camera_id!=-1)
+  if(this->camera_id!=-1 || this->camera_serial.size()!=0)
   {
     this->server->init();
     if(this->server->get_num_cameras()>0)
     {
-      this->server->get_camera(this->camera_id,&this->camera);
+      if(this->camera_serial.size()==0)
+        this->server->get_camera(this->camera_id,&this->camera);
+      else
+      { 
+        buffer << this->camera_serial;
+        buffer >> std::hex >> serial;
+        this->server->get_camera_guid(serial,&this->camera);
+      }
       this->camera->set_ISO_speed(this->ISO_speed);
       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,
@@ -131,6 +141,7 @@ void FirewireCameraDriver::config_update(Config& new_cfg, uint32_t level)
     case FirewireCameraDriver::CLOSED:
       this->lock();
       this->camera_id=new_cfg.Camera_node;
+      this->camera_serial=new_cfg.Camera_serial;
       this->ISO_speed=new_cfg.ISO_speed;
       this->dyn_rec_to_camera(new_cfg,this->desired_conf);
       // change the calibration file
@@ -153,6 +164,12 @@ void FirewireCameraDriver::config_update(Config& new_cfg, uint32_t level)
             this->camera_id=new_cfg.Camera_node;
             this->open();
           }
+          if(this->camera_serial!=new_cfg.Camera_serial)
+          {
+            this->close();
+            this->camera_serial=new_cfg.Camera_serial;
+            this->open();
+          }
           this->dyn_rec_to_camera(new_cfg,conf);
           this->change_config(&conf);
           // write the configuration back to the dynamic reconfigure window