diff --git a/CMakeLists.txt b/CMakeLists.txt
index cb9073c717b7a52c6835c7a72461551787a7ff4f..873cba09dedf0adcc03c8e78f79b2bddfbef000e 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -7,11 +7,8 @@ find_package(catkin REQUIRED)
 #                 Add catkin additional components here
 # ******************************************************************** 
 find_package(catkin REQUIRED COMPONENTS iri_base_driver sensor_msgs image_transport camera_info_manager)
-# find_package(catkin REQUIRED COMPONENTS iri_base_driver cv_bridge image_transport camera_info_manager sensor_msgs)
 find_package(mvbluefox3 REQUIRED)
 find_package(mvIMPACT REQUIRED)
-#find_package(OpenCV 3 REQUIRED)
-#find_package(OpenCV 2.4 REQUIRED)
 
 ## System dependencies are found with CMake's conventions
 # find_package(Boost REQUIRED COMPONENTS system)
@@ -66,7 +63,7 @@ catkin_package(
 #            Add ROS and IRI ROS run time dependencies
 # ******************************************************************** 
  CATKIN_DEPENDS iri_base_driver sensor_msgs image_transport camera_info_manager
- # CATKIN_DEPENDS iri_base_driver cv_bridge image_transport camera_info_manager sensor_msgs
+
 # ******************************************************************** 
 #      Add system and labrobotica run time dependencies here
 # ******************************************************************** 
@@ -87,7 +84,6 @@ include_directories(include)
 include_directories(${catkin_INCLUDE_DIRS})
 include_directories(${mvbluefox3_INCLUDE_DIR})
 include_directories(${mvIMPACT_INCLUDE_DIR})
-# include_directories(${OpenCV_INCLUDE_DIRS})
 # include_directories(${<dependency>_INCLUDE_DIR})
 
 ## Declare a cpp library
@@ -102,8 +98,6 @@ add_executable(${PROJECT_NAME} src/mvbluefox3_camera_driver.cpp src/mvbluefox3_c
 target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})
 target_link_libraries(${PROJECT_NAME} ${mvbluefox3_LIBRARY})
 target_link_libraries(${PROJECT_NAME} ${mvIMPACT_LIBRARY})
-# target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBRARIES})
-# TARGET_LINK_LIBRARIES(${PROJECT_NAME} ${OpenCV_LIBS})
 # target_link_libraries(${PROJECT_NAME} ${<dependency>_LIBRARY})
 
 # ******************************************************************** 
diff --git a/launch/iri_mvbluefox3_camera.launch b/launch/iri_mvbluefox3_camera.launch
index edb0450a1e08cc1774a919da698d9cb6d1ea305f..1ba4f848d360133c643bac50f797ef92de6b765c 100644
--- a/launch/iri_mvbluefox3_camera.launch
+++ b/launch/iri_mvbluefox3_camera.launch
@@ -1,20 +1,20 @@
 <!--DOCTYPE html-->
 <launch>
 
-  <arg name="num_cams" default="1" />
+  <arg name="num_cams" default="2" />
 
   <arg name="c1_name" default="cam1" />
   <arg name="c1_serial" default="F0300141" />
   <arg name="c1_frame_id" default="$(arg c1_name)" />
   <arg name="c1_tf_prefix" default="" />
-  <arg name="c1_params_path" default="$(find iri_mvbluefox3_camera)/params/F0300141.xml" />
+  <arg name="c1_params_path" default="$(find iri_mvbluefox3_camera)/params/F0300141_params.xml" />
   <arg name="c1_calib_file" default="file://$(find iri_mvbluefox3_camera)/params/F0300141_calib.yaml" />
 
   <arg name="c2_name" default="cam2" />
   <arg name="c2_serial"    default="F0300123" />
   <arg name="c2_frame_id"  default="$(arg c2_name)" />
   <arg name="c2_tf_prefix" default="" />
-  <arg name="c2_params_path" default="$(find iri_mvbluefox3_camera)/params/F0300123.xml" />
+  <arg name="c2_params_path" default="$(find iri_mvbluefox3_camera)/params/F0300123_params.xml" />
   <arg name="c2_calib_file" default="file://$(find iri_mvbluefox3_camera)/params/F0300123_calib.yaml" />  
 
   <node pkg="iri_mvbluefox3_camera"
@@ -46,8 +46,8 @@
     <remap from="/image" to="/iri_mvbluefox3_camera/$(arg c1_name)/image_raw"/>
   </node>
 
-<!--   <node pkg="image_view" type="image_view" name="image_view_$(arg c2_name)" >
+  <node pkg="image_view" type="image_view" name="image_view_$(arg c2_name)" >
     <remap from="/image" to="/iri_mvbluefox3_camera/$(arg c2_name)/image_raw"/>
   </node>  
- -->
+
 </launch>
diff --git a/package.xml b/package.xml
index 236b83fefaa1ef446f67298ee2e3982813f3a6bf..16ec69f32a9cba2fe0086fead7c47d6305ddb433 100644
--- a/package.xml
+++ b/package.xml
@@ -7,7 +7,7 @@
   <!-- One maintainer tag required, multiple allowed, one person per tag --> 
   <!-- Example:  -->
   <!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
-  <maintainer email="asantamaria@todo.todo">asantamaria</maintainer>
+  <maintainer email="asantamaria@iri.upc.edu">asantamaria</maintainer>
 
 
   <!-- One license tag required, multiple allowed, one license per tag -->
@@ -41,12 +41,11 @@
   <!--   <test_depend>gtest</test_depend> -->
   <buildtool_depend>catkin</buildtool_depend>
   <build_depend>iri_base_driver</build_depend>
-  <!-- <build_depend>cv_bridge</build_depend> -->
   <build_depend>image_transport</build_depend>
   <build_depend>camera_info_manager</build_depend>
   <build_depend>sensor_msgs</build_depend>
+
   <run_depend>iri_base_driver</run_depend>
-  <!-- <run_depend>cv_bridge</run_depend> -->
   <run_depend>image_transport</run_depend>
   <run_depend>camera_info_manager</run_depend>
   <run_depend>sensor_msgs</run_depend>
diff --git a/params/F0300123_params.xml b/params/F0300123_params.xml
index dee7488ff3f60787e36b8ebf6ff87fafdc8c7d50..b75af7e9ea97ebe079a6d0a89d0e9d3939bf2ad5 100644
--- a/params/F0300123_params.xml
+++ b/params/F0300123_params.xml
@@ -22,7 +22,7 @@ Width	1280
 Height	960
 OffsetX	0
 OffsetY	0
-PixelFormat	Auto
+PixelFormat	BayerGR8
 TestPattern	Off
 BinningHorizontal	1
 DecimationHorizontal	1
@@ -31,10 +31,10 @@ ReverseX	0
 ReverseY	0
 AcquisitionMode	Continuous
 ExposureMode	Timed
-ExposureTime	32132
+ExposureTime	23399
 ExposureAuto	Continuous
 mvExposureAutoLowerLimit	74
-mvExposureAutoUpperLimit	32759
+mvExposureAutoUpperLimit	23399
 mvExposureAutoAverageGrey	50
 mvExposureAutoHighlightAOI	Off
 mvExposureAutoAOIMode	mvFull
@@ -100,8 +100,9 @@ TriggerSelector	FrameBurstActive
 TriggerDelay	0
 TriggerSelector	FrameStart
 mvAcquisitionFrameRateLimitMode	mvDeviceLinkThroughput
-AcquisitionFrameRateEnable	0
-mvAcquisitionFrameRateEnable	Off
+AcquisitionFrameRateEnable	1
+mvAcquisitionFrameRateEnable	On
+AcquisitionFrameRate	25.3
 AcquisitionFrameCount	1
 mvAcquisitionMemoryMode	Default
 CounterSelector	Counter1
@@ -165,12 +166,12 @@ TimerSelector	Timer2
 TimerDelay	0
 TimerSelector	Timer1
 TimerSelector	Timer1
-TimerValue	17046
+TimerValue	16407
 TimerSelector	Timer2
-TimerValue	7981
+TimerValue	14452
 TimerSelector	Timer1
 GainSelector	AnalogAll
-Gain	0
+Gain	6.209
 GainSelector	DigitalAll
 Gain	0
 GainSelector	AnalogAll
@@ -202,9 +203,9 @@ BlackLevelSelector	All
 BlackLevelAuto	Continuous
 BlackLevelSelector	DigitalAll
 BalanceRatioSelector	Red
-BalanceRatio	1.41268
+BalanceRatio	0.800271
 BalanceRatioSelector	Blue
-BalanceRatio	1.96385
+BalanceRatio	3.30967
 BalanceRatioSelector	Blue
 BalanceWhiteAuto	Continuous
 mvBalanceWhiteAutoAOIMode	mvFull
diff --git a/params/F0300141_params.xml b/params/F0300141_params.xml
index 09a53d82ccc130a0ac34c00a45dd5eaecde01eb7..c8f8f0d8f4477db96aa087371fdd311a5e5f1a6d 100644
--- a/params/F0300141_params.xml
+++ b/params/F0300141_params.xml
@@ -31,7 +31,7 @@ ReverseX	0
 ReverseY	0
 AcquisitionMode	Continuous
 ExposureMode	Timed
-ExposureTime	6117
+ExposureTime	23399
 ExposureAuto	Continuous
 mvExposureAutoLowerLimit	74
 mvExposureAutoUpperLimit	23399
@@ -100,8 +100,9 @@ TriggerSelector	FrameBurstActive
 TriggerDelay	0
 TriggerSelector	FrameStart
 mvAcquisitionFrameRateLimitMode	mvDeviceLinkThroughput
-AcquisitionFrameRateEnable	0
-mvAcquisitionFrameRateEnable	Off
+AcquisitionFrameRateEnable	1
+mvAcquisitionFrameRateEnable	On
+AcquisitionFrameRate	25.3
 AcquisitionFrameCount	1
 mvAcquisitionMemoryMode	Default
 CounterSelector	Counter1
@@ -165,12 +166,12 @@ TimerSelector	Timer2
 TimerDelay	0
 TimerSelector	Timer1
 TimerSelector	Timer1
-TimerValue	4047
+TimerValue	17376
 TimerSelector	Timer2
-TimerValue	11839
+TimerValue	15776
 TimerSelector	Timer1
 GainSelector	AnalogAll
-Gain	0
+Gain	6.209
 GainSelector	DigitalAll
 Gain	0
 GainSelector	AnalogAll
@@ -202,9 +203,9 @@ BlackLevelSelector	All
 BlackLevelAuto	Continuous
 BlackLevelSelector	DigitalAll
 BalanceRatioSelector	Red
-BalanceRatio	0.968241
+BalanceRatio	0.800271
 BalanceRatioSelector	Blue
-BalanceRatio	2.28045
+BalanceRatio	3.30967
 BalanceRatioSelector	Blue
 BalanceWhiteAuto	Continuous
 mvBalanceWhiteAutoAOIMode	mvFull
diff --git a/src/mvbluefox3_camera_driver.cpp b/src/mvbluefox3_camera_driver.cpp
index 67c2a2bc7dd8088aff0cf3f49bdfae614e4b196d..b79f8a2f6c145aae42bf2aae0fc9a38077af7281 100644
--- a/src/mvbluefox3_camera_driver.cpp
+++ b/src/mvbluefox3_camera_driver.cpp
@@ -285,7 +285,7 @@ void Mvbluefox3CameraDriver::GetROSImage(const int &ncam, sensor_msgs::Image &im
   char *image = NULL;
   this->vcam_ptr[ncam]->GetImage(&image);
   GetConfig(ncam);
-
+  
   std::string encoding;
   encoding = CMvbluefox3::codings_str[this->vparams[ncam].pixel_format];
 
@@ -296,15 +296,33 @@ void Mvbluefox3CameraDriver::GetROSImage(const int &ncam, sensor_msgs::Image &im
   switch (this->vparams[ncam].pixel_format)
   {
     case CMvbluefox3::raw: 
-      // switch (depth*bp) 
-      // {
-      //   case 8: encoding = "8UC1"; break;
-      //   case 16: encoding = "8UC2"; break;
-      //   case 24: encoding = "8UC3"; break;
-      //   case 32: encoding = "8UC4"; break;
-      //   default: ROS_WARN("Invalid depth. Depth not implemented for sensor_msgs."); break;
-      // }
-      encoding = "rgb8";
+
+      if (depth/8 == 1)
+      {
+        encoding = "8UC1";
+        switch (bp) 
+        {
+          case 1: encoding = "8UC1"; break;
+          case 2: encoding = "8UC2"; break;
+          case 3: encoding = "8UC3"; break;
+          case 4: encoding = "8UC4"; break;
+          default: ROS_WARN("Invalid depth. Depth not implemented here."); break;
+        }
+      }
+      else if (depth/8 == 2)
+      {
+        encoding = "16UC1";
+        switch (bp) 
+        {
+          case 1: encoding = "16UC1"; break;
+          case 2: encoding = "16UC2"; break;
+          case 3: encoding = "16UC3"; break;
+          case 4: encoding = "16UC4"; break;
+          default: ROS_WARN("Invalid depth. Depth not implemented here."); break;
+        }
+      }
+      else
+        ROS_WARN("Invalid depth. Depth not implemented here.");
       break; 
     case CMvbluefox3::mono8: break; 
     case CMvbluefox3::mono10: ROSvalid = false; break; 
@@ -337,24 +355,6 @@ void Mvbluefox3CameraDriver::GetROSImage(const int &ncam, sensor_msgs::Image &im
   if (!ROSvalid)
     ROS_WARN("mvBlueFOX3 pixel format %s no valid within ROS messages.",encoding.c_str());
 
-        //   else if(config.coding==RAW)
-        //   {
-        //     this->camera.Image_msg_->encoding=this->driver_.get_bayer_pattern();
-        //   }
-
-        //   else
-        //   {
-        //     if(config.depth==DEPTH24)
-        //       this->camera.Image_msg_->encoding="rgb8";
-        //     else if(config.depth==DEPTH48)
-        //       this->camera.Image_msg_->encoding="16UC3";
-        //     else
-        //       this->camera.Image_msg_->encoding="16UC3";
-        //   }
-        // }
-        // //
-
-
   sensor_msgs::fillImage(img_msg, 
     encoding, 
     this->vparams[ncam].height,