diff --git a/calibration/flea_6mm.yaml b/calibration/flea_6mm.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..58335798696ee786a1590ef00e7b68a19aafa4c0
--- /dev/null
+++ b/calibration/flea_6mm.yaml
@@ -0,0 +1,20 @@
+image_width: 1024
+image_height: 768
+camera_name: narrow_stereo
+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]
\ No newline at end of file
diff --git a/launch/camera_flea.launch b/launch/camera_flea.launch
index fc4faa76b44a7d4203571fa4d8a36e29735b71c0..22ba6dad196751d13c2525efa8c3cda74957300b 100644
--- a/launch/camera_flea.launch
+++ b/launch/camera_flea.launch
@@ -4,10 +4,10 @@
         name="iri_firewire_camera"
         type="iri_firewire_camera"
         output="screen">
-    <param name="Camera_node"  value="2" />
-    <param name="Color_coding" value="0" />
+    <param name="Camera_serial"  value="00b09d01006cf72a" />
+    <param name="Color_coding" value="3" />
     <param name="ISO_speed"    value="400" />
-    <param name="Framerate"    value="30" />
+    <param name="Framerate"    value="2.5" />
     <param name="Image_width"  value="1024" />
     <param name="Image_height" value="768" />
   </node>
diff --git a/src/firewire_camera_driver_node.cpp b/src/firewire_camera_driver_node.cpp
index a2696af6cf39e3c4617c5c730fe1a5eaae355ef0..e11831d1f8be244e39b9fcf739692de9c52dd538 100644
--- a/src/firewire_camera_driver_node.cpp
+++ b/src/firewire_camera_driver_node.cpp
@@ -20,7 +20,7 @@ FirewireCameraDriverNode::FirewireCameraDriverNode(ros::NodeHandle &nh) : iri_ba
   this->camera_image_publisher_ = this->it->advertiseCamera("camera_image", 1);
 
   // try to load the calibration file
-  public_node_handle_.param<std::string>("left_cal_file", cal_file, "");
+  public_node_handle_.param<std::string>("cal_file", cal_file, "");
   if(this->camera_manager.validateURL(cal_file))
   {
     if(!this->camera_manager.loadCameraInfo(this->driver_.get_calibration_file()))