diff --git a/calibration/tibi_right_camera.yaml b/calibration/tibi_right_camera.yaml
index 7935691979876fac323516739adb4146938b72eb..0566710aa866465605e37657eed52612704d1892 100644
--- a/calibration/tibi_right_camera.yaml
+++ b/calibration/tibi_right_camera.yaml
@@ -17,4 +17,4 @@ rectification_matrix:
 projection_matrix:
   rows: 3
   cols: 4
-  data: [713.326843261719, 0, 518.830156137115, 0, 0, 768.828002929688, 391.548470335729, 0, 0, 0, 1, 0]
\ No newline at end of file
+  data: [713.326843261719, 0, 518.830156137115, 0, 0, 768.828002929688, 391.548470335729, 0, 0, 0, 1, 0]
diff --git a/include/firewire_camera_driver.h b/include/firewire_camera_driver.h
index 585e111396b728dc2cbd64acab5ad7d0d69e4a34..72be8e30e6f9beac868aaab460cb866c193fccfd 100644
--- a/include/firewire_camera_driver.h
+++ b/include/firewire_camera_driver.h
@@ -242,7 +242,11 @@ class FirewireCameraDriver : public iri_base_driver::IriBaseDriver
      *
      */
     void set_calibration_params(unsigned int width, unsigned int height);
-
+    /**
+     * \brief
+     *
+     */
+    std::string get_bayer_pattern(void);
    /**
     * \brief Destructor
     *
diff --git a/launch/camera_flea.launch b/launch/camera_flea.launch
index 22ba6dad196751d13c2525efa8c3cda74957300b..e2fcc95e6b229739eba4774b1a93e1d2bf0e5e34 100644
--- a/launch/camera_flea.launch
+++ b/launch/camera_flea.launch
@@ -4,7 +4,8 @@
         name="iri_firewire_camera"
         type="iri_firewire_camera"
         output="screen">
-    <param name="Camera_serial"  value="00b09d01006cf72a" />
+    <!--<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" />
diff --git a/launch/firewire.launch b/launch/firewire.launch
index 553e6da55c4383aee9492c50b3e3f5068f6ad05f..07b86949e91abd75a6c2c3ffbef2643866dae82c 100755
--- a/launch/firewire.launch
+++ b/launch/firewire.launch
@@ -13,12 +13,13 @@
         output="screen">
     <remap from="/bumblebee/camera_image"
              to="/sensors/head_right/image_raw"/>
-    <param name="Camera_serial"  value="00b09d01006b6fb5" />
+    <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/tibi_right_camera.yaml" type="string" />
-    <param name="ISO_speed"    value="400" />
-    <param name="Framerate"    value="7.5" />
+    <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" />
diff --git a/launch/firewire_nodelet.launch b/launch/firewire_nodelet.launch
index 9c04521badfd51bd0de88b6f5012bb1e98bda420..07b60a0418de7b7b00082243f6b4456497299a85 100755
--- a/launch/firewire_nodelet.launch
+++ b/launch/firewire_nodelet.launch
@@ -1,10 +1,11 @@
 <launch>
   <node pkg="nodelet" type="nodelet" name="standalone_nodelet"  args="manager" output="screen">
-    <param name="Camera_serial" value="00b09d01006b6fb5" />
+    <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="400" />
-    <param name="Framerate"     value="7.5" />
+    <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" />
diff --git a/src/firewire_camera_driver.cpp b/src/firewire_camera_driver.cpp
index f315e77cdb5e49853e5f7a86fff532c184686c22..d629b9ddf7f9525baddfafe1fe912fc27adede59 100644
--- a/src/firewire_camera_driver.cpp
+++ b/src/firewire_camera_driver.cpp
@@ -63,6 +63,7 @@ bool FirewireCameraDriver::openDriver(void)
                                &this->default_conf.height,&this->default_conf.framerate,&this->default_conf.depth,
                                &this->default_conf.coding);
       // set the desired configuration
+      this->change_config(&this->desired_conf);
       if((this->cal_width!=-1 && this->desired_conf.width!=this->cal_width) ||
          (this->cal_height!=-1 && this->desired_conf.height!=this->cal_height))
       {
@@ -71,7 +72,6 @@ bool FirewireCameraDriver::openDriver(void)
         this->camera=NULL;
         return false;
       }
-      this->change_config(&this->desired_conf);
       ROS_INFO("Driver opened");
       return true;
     }
@@ -592,6 +592,26 @@ void FirewireCameraDriver::set_calibration_params(unsigned int width, unsigned i
   this->cal_height=height;
 }
 
+std::string FirewireCameraDriver::get_bayer_pattern(void)
+{
+  dc1394color_filter_t bayer;
+
+  if(this->camera!=NULL)
+  {
+    this->camera->get_bayer_pattern(&bayer);
+    if((int)bayer==512)
+      return std::string("bayer_rggb8");
+    else if((int)bayer==513)
+      return std::string("bayer_gbrg8");
+    else if((int)bayer==514)
+      return std::string("bayer_grbg8");
+    else 
+      return std::string("bayer_bggr8");
+  }
+  else
+    return std::string(""); 
+}
+
 FirewireCameraDriver::~FirewireCameraDriver()
 {
   this->server->close();
diff --git a/src/firewire_camera_driver_node.cpp b/src/firewire_camera_driver_node.cpp
index 541b9798aea17579a7514545596a1ea5b49ab5a8..9d66d1447585fc1bfaefb7ddc87411fdbb3afd6b 100644
--- a/src/firewire_camera_driver_node.cpp
+++ b/src/firewire_camera_driver_node.cpp
@@ -27,11 +27,16 @@ FirewireCameraDriverNode::FirewireCameraDriverNode(ros::NodeHandle &nh) : iri_ba
   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());
+      cal_ok=true;
+    }
     else
+    {
       ROS_INFO("Invalid calibration file for the camera");
+      cal_ok=false;
+    }
     this->camera.CameraInfo_msg_.reset(new sensor_msgs::CameraInfo(this->camera_manager.getCameraInfo()));
-    cal_ok=true;
   }
   else
   {
@@ -84,7 +89,7 @@ void FirewireCameraDriverNode::mainNodeThread(void)
           this->camera.Image_msg_->step=config.width*config.depth/8;
           this->camera.Image_msg_->data.resize(config.width*config.height*config.depth/8);
           this->driver_.get_image((char *)this->camera.Image_msg_->data.data());
-          if(config.coding==MONO || config.coding==RAW)
+          if(config.coding==MONO)
           {
             if(config.depth==DEPTH8)
               this->camera.Image_msg_->encoding="mono8";
@@ -93,6 +98,10 @@ void FirewireCameraDriverNode::mainNodeThread(void)
             else
               this->camera.Image_msg_->encoding="16UC1";
           }
+          else if(config.coding==RAW)
+          {
+            this->camera.Image_msg_->encoding=this->driver_.get_bayer_pattern();
+          }
           else if(config.coding==YUV)
           {
             this->camera.Image_msg_->encoding="yuv422";