diff --git a/ReadMe.md b/ReadMe.md
index e941453c076ab81cb9e804ad58237038a556d39a..c527b374214622d6900589cb120473ee20842f5a 100644
--- a/ReadMe.md
+++ b/ReadMe.md
@@ -9,7 +9,7 @@ ROS wrapper to work with [mvBlueFOX3](https://gitlab.iri.upc.edu/asantamaria/mvB
 - [Matrix Vision driver](https://www.matrix-vision.com/software-drivers-en.html). Orientative installation for a Linux x86_64. For detailed specifications and driver installations, please visit [Matrix 
 Vision Drivers and Software](https://www.matrix-vision.com/software-drivers-en.html)
   - `cd ~/Downloads`
-  - `wget http://static.matrix-vision.com/mvIMPACT_Acquire/2.19.0/mvGenTL_Acquire-x86_64_ABI2-2.19.0.tgz -O mvGenTL_Acquire-x86_64_ABI2-2.19.0.tgz`
+  - `wget http://static.matrix-vision.com/mvIMPACT_Acquire/2.26.0/mvGenTL_Acquire-x86_64_ABI2-2.26.0.tgz -O mvGenTL_Acquire-x86_64_ABI2-2.26.0.tgz`
   - `wget https://www.matrix-vision.com/USB3-vision-camera-mvbluefox3.html?file=tl_files/mv11/support/mvIMPACT_Acquire/01/install_mvGenTL_Acquire.sh -O install_mvGenTL_Acquire.sh`
   - `sudo chmod +x install_mvGenTL_Acquire.sh`
   - `./install_mvGenTL_Acquire.sh` 
diff --git a/cfg/Mvbluefox3Camera.cfg b/cfg/Mvbluefox3Camera.cfg
new file mode 100755
index 0000000000000000000000000000000000000000..ac3bd0221617a7656e07966e72016061ee1fc486
--- /dev/null
+++ b/cfg/Mvbluefox3Camera.cfg
@@ -0,0 +1,124 @@
+#! /usr/bin/env python
+#*  All rights reserved.
+#*
+#*  Redistribution and use in source and binary forms, with or without
+#*  modification, are permitted provided that the following conditions
+#*  are met:
+#*
+#*   * Redistributions of source code must retain the above copyright
+#*     notice, this list of conditions and the following disclaimer.
+#*   * Redistributions in binary form must reproduce the above
+#*     copyright notice, this list of conditions and the following
+#*     disclaimer in the documentation and/or other materials provided
+#*     with the distribution.
+#*   * Neither the name of the Willow Garage nor the names of its
+#*     contributors may be used to endorse or promote products derived
+#*     from this software without specific prior written permission.
+#*
+#*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+#*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+#*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+#*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+#*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+#*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+#*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+#*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+#*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+#*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+#*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+#*  POSSIBILITY OF SUCH DAMAGE.
+#***********************************************************
+
+# Author: 
+
+PACKAGE='iri_mvbluefox3_camera'
+
+from driver_base.msg import SensorLevels
+from dynamic_reconfigure.parameter_generator_catkin import *
+
+gen = ParameterGenerator()
+
+#       Name                       Type       Reconfiguration level            Description                       Default   Min   Max
+#gen.add("velocity_scale_factor",  double_t,  SensorLevels.RECONFIGURE_STOP,   "Maximum velocity scale factor",  0.5,      0.0,  1.0)
+
+enum_mirror = gen.enum([ gen.const("Off", int_t, 0, "No mirror"),
+gen.const("TopDown", int_t, 1, "Top-Down mirror"), gen.const("LeftRight", int_t, 2, "Left-Right mirror")],"Available mirror modes")
+
+enum_mode = gen.enum([ gen.const("Auto", bool_t, True, "Auto mode"),
+gen.const("Manual", bool_t, False, "Manual mode")],"Available feature modes")
+
+enum_clock = gen.enum([ gen.const("kHz_40000", int_t, 40000, "kHz_40000"),
+gen.const("kHz_66000", int_t, 66000, "kHz_66000")],"Available pixel clock frequencies [kHz]")
+
+enum_speed = gen.enum([ gen.const("Slow", int_t, 0, "Slow"),
+gen.const("Medium", int_t, 1, "Medium"),
+gen.const("Fast", int_t, 2, "Fast")],"Available auto control speed modes")
+
+enum_dark_filter = gen.enum([ gen.const("df_Off", int_t, 0, "Off"),
+gen.const("df_On", int_t, 1, "On"),
+gen.const("df_Calibrate", int_t, 2, "Calibrate")],"Available dark filter modes")
+
+enum_color_coding = gen.enum([ 
+gen.const("RAW8", int_t, 0, "RAW coding with 8 bits per pixel"),
+gen.const("MONO8", int_t, 1, "Mono coding with 8 bits per pixel"),
+gen.const("MONO16", int_t, 2, "MONO coding with 16 bits per pixel"),
+gen.const("RGB8", int_t, 3, "RGB coding with 8 bits per channel"),
+gen.const("RGB16", int_t, 4, "RGB coding with 16 bits per channel"),
+gen.const("BGR8", int_t, 5, "BGR coding with 8 bits per channel"),
+gen.const("YUV422", int_t, 6, "YUV coding with 4,2,2 pixels per channel"),
+gen.const("YUV444", int_t, 7, "YUV coding with 4,4,4 pixels per channel")],"Available color modes")
+
+gen.add("cam_name",         str_t,       SensorLevels.RECONFIGURE_STOP,   "Camera number to apply settings",     "<< FILL CAMERA NAME TO UPDATE  PARAMS>>")
+
+gen.add("apply_cfg",      bool_t,       SensorLevels.RECONFIGURE_STOP,   "Apply new configuration", False)
+
+gen.add("pixel_format",   int_t,        SensorLevels.RECONFIGURE_STOP,        "Color modes",            1,           0,       7, edit_method=enum_color_coding)
+gen.add("width",          int_t,        SensorLevels.RECONFIGURE_STOP,        "Image width",            1280,        0,       1280)
+gen.add("height",         int_t,        SensorLevels.RECONFIGURE_STOP,        "Image height",           960,         0,        960)
+
+gen.add("frame_rate",     int_t,        SensorLevels.RECONFIGURE_STOP,        "Frame rate",             1,           1,       29)
+gen.add("pixel_clock",    int_t,        SensorLevels.RECONFIGURE_STOP,        "Pixel Clock (kHz)",      40000,       40000,   66000, edit_method=enum_clock)
+
+gen.add("auto_expose",    bool_t,       SensorLevels.RECONFIGURE_STOP,   "Enable automatic exposure control",    True)
+gen.add("auto_expose_upperlimit",    int_t,        SensorLevels.RECONFIGURE_STOP,        "Auto exposure upper limit [us]",  30000,   10000,       500000)
+gen.add("auto_expose_des_grey_val",    int_t,        SensorLevels.RECONFIGURE_STOP,        "Auto exposure desired grey value [%]",  50,   0,       100)
+gen.add("expose_us",    int_t,        SensorLevels.RECONFIGURE_STOP,        "Exposure (auto_expose = off) [us]",  10000,   1000,       100000)
+
+gen.add("auto_gain",    bool_t,       SensorLevels.RECONFIGURE_STOP,   "Enable automatic gain control",    False)
+gen.add("gain_db",      int_t,        SensorLevels.RECONFIGURE_STOP,        "Gain (auto_gain = off) [dB]",  0,   0,       40)
+
+gen.add("gamma",        bool_t,       SensorLevels.RECONFIGURE_STOP,   "Gamma gain (LUT)",    False)
+
+gen.add("img_rot_angle",  int_t,        SensorLevels.RECONFIGURE_STOP,        "Image rotation angle",   0,           0,        360)
+gen.add("mirror",         int_t,        SensorLevels.RECONFIGURE_STOP,   "Image mirror",           0,           0,          2, edit_method=enum_mirror)
+
+gen.add("set_aoi",        bool_t,       SensorLevels.RECONFIGURE_STOP,   "Set AOI",                     False)
+gen.add("aoi_width",      int_t,        SensorLevels.RECONFIGURE_STOP,        "AOI width",              1280,        0,       1280)
+gen.add("aoi_height",     int_t,        SensorLevels.RECONFIGURE_STOP,        "AOI height",             960,         0,       960)
+gen.add("aoi_start_x",    int_t,        SensorLevels.RECONFIGURE_STOP,        "AOI start x pixel",      0,           0,       1280)
+gen.add("aoi_start_y",    int_t,        SensorLevels.RECONFIGURE_STOP,        "AOI start y pixel",      0,           0,       1280)
+gen.add("h_binning_enbl", bool_t,       SensorLevels.RECONFIGURE_STOP,   "Enable horizontal binning",            False)
+gen.add("h_binning",      int_t,        SensorLevels.RECONFIGURE_STOP,        "Horizontal binning factor (1/x)",     1,         1,       2)
+gen.add("v_binning_enbl", bool_t,       SensorLevels.RECONFIGURE_STOP,   "Enable vertical binning",              False)
+gen.add("v_binning",      int_t,        SensorLevels.RECONFIGURE_STOP,        "Vertical binning factor (1/x)",       1,         1,       2)
+
+gen.add("req_timeout",    int_t,        SensorLevels.RECONFIGURE_STOP,        "Image request timeout [ms]",  2000,   0,       5000)
+
+gen.add("auto_ctrl_enbl", bool_t,       SensorLevels.RECONFIGURE_STOP,   "Enable automatic control: auto exposure and gain controls",    False)
+gen.add("auto_ctrl_speed",    int_t,        SensorLevels.RECONFIGURE_STOP,        "Auto control speed",      2,       0,   2, edit_method=enum_speed)
+
+gen.add("whiteblnce_auto_enbl",        bool_t,       SensorLevels.RECONFIGURE_STOP,   "Auto white balance",    True)
+gen.add("wb_r_gain",      int_t,        SensorLevels.RECONFIGURE_STOP,        "Red channel white balance gain (auto_white_balance = off) [dB]",  0,   0,       40)
+gen.add("wb_b_gain",      int_t,        SensorLevels.RECONFIGURE_STOP, 
+"Blue channel white balance gain (auto_white_balance = off) [dB]",  0,   0,       40)
+
+gen.add("auto_blck_level",        bool_t,       SensorLevels.RECONFIGURE_STOP,   "Auto black level",    True)
+gen.add("blck_level",      int_t,        SensorLevels.RECONFIGURE_STOP,    "Black level (auto_black_level = off)",  0,   0,       100)
+
+gen.add("hdr_enbl",    bool_t,       SensorLevels.RECONFIGURE_STOP,   "HDR",    False)
+
+gen.add("dark_cfilter",      int_t,        SensorLevels.RECONFIGURE_STOP,    "Dark filter modes",  0,   0,       2,  edit_method=enum_dark_filter)
+
+gen.add("twist_cfilter",    bool_t,       SensorLevels.RECONFIGURE_STOP,   "Color Twist Filter enable",    False)
+
+exit(gen.generate(PACKAGE, "Mvbluefox3CameraDriver", "Mvbluefox3Camera"))
diff --git a/include/mvbluefox3_camera_driver.h b/include/mvbluefox3_camera_driver.h
new file mode 100644
index 0000000000000000000000000000000000000000..c76410909aa92adf8804ebb6fe759b5bad74e46e
--- /dev/null
+++ b/include/mvbluefox3_camera_driver.h
@@ -0,0 +1,246 @@
+// Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC.
+// Author 
+// All rights reserved.
+//
+// This file is part of iri-ros-pkg
+// iri-ros-pkg is free software: you can redistribute it and/or modify
+// it under the terms of the GNU Lesser General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// at your option) any later version.
+//
+// This program is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+// GNU Lesser General Public License for more details.
+//
+// You should have received a copy of the GNU Lesser General Public License
+// along with this program.  If not, see <http://www.gnu.org/licenses/>.
+// 
+// IMPORTANT NOTE: This code has been generated through a script from the 
+// iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness
+// of the scripts. ROS topics can be easly add by using those scripts. Please
+// refer to the IRI wiki page for more information:
+// http://wikiri.upc.es/index.php/Robotics_Lab
+
+#ifndef _mvbluefox3_camera_driver_h_
+#define _mvbluefox3_camera_driver_h_
+
+#include <iri_base_driver/iri_base_driver.h>
+#include <iri_mvbluefox3_camera/Mvbluefox3CameraConfig.h>
+
+#include "mvbluefox3.h"
+
+#include <sensor_msgs/Image.h>
+#include <sensor_msgs/fill_image.h>
+
+/**
+ * \brief IRI ROS Specific Driver Class
+ *
+ * This class inherits from the IRI Base class IriBaseDriver, which provides the
+ * guidelines to implement any specific driver. The IriBaseDriver class offers an 
+ * easy framework to integrate functional drivers implemented in C++ with the
+ * ROS driver structure. ROS driver_base state transitions are already managed
+ * by IriBaseDriver.
+ *
+ * The Mvbluefox3CameraDriver class must implement all specific driver requirements to
+ * safetely open, close, run and stop the driver at any time. It also must 
+ * guarantee an accessible interface for all driver's parameters.
+ *
+ * The Mvbluefox3CameraConfig.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().
+ *
+ */
+class Mvbluefox3CameraDriver : public iri_base_driver::IriBaseDriver
+{
+  private:
+    // private attributes and methods
+
+    mvIMPACT::acquire::DeviceManager devMgr;            // Device Manager.
+
+    std::vector<CMvbluefox3::CMvbluefox3*> vcam_ptr;  // Camera pointer. 
+
+    bool ini_dynrec; // To control parameters initialization after device is found.
+
+   /**
+    * \brief Dynamic reconfigure to camera parameters
+    *
+    * Dynamic reconfigure to camera parameters.
+    */     
+    CMvbluefox3::CParams DynRecToParams(iri_mvbluefox3_camera::Mvbluefox3CameraConfig &cfg);
+
+   /**
+    * \brief Camera parameters to dynamic reconfigure
+    *
+    * Camera parameters to dynamic reconfigure.
+    */     
+    iri_mvbluefox3_camera::Mvbluefox3CameraConfig ParamsToDynRec(const int &cam_num, const CMvbluefox3::CParams &p);
+
+  public:
+
+    int num_cams;                               // Number of cameras.   
+    std::vector<std::string> vserial;           // Serial numbers.
+    std::vector<std::string> vframe_id;         // Frame ids. 
+    std::vector<std::string> vcam_name;         // Camera names. 
+    std::vector<std::string> vparams_path;      // Parameters' paths.
+
+    std::vector<CMvbluefox3::CParams> vparams;  // Camera parameters.
+    bool ini_user_params; // To control parameters initialization after device is found.
+
+   /**
+    * \brief define config type
+    *
+    * Define a Config type with the Mvbluefox3CameraConfig. All driver implementations
+    * will then use the same variable type Config.
+    */
+    typedef iri_mvbluefox3_camera::Mvbluefox3CameraConfig Config;
+
+   /**
+    * \brief config variable
+    *
+    * This variable has all the driver parameters defined in the cfg config file.
+    * Is updated everytime function config_update() is called.
+    */
+    Config config_;
+
+   /**
+    * \brief constructor
+    *
+    * In this constructor parameters related to the specific driver can be
+    * initalized. Those parameters can be also set in the openDriver() function.
+    * Attributes from the main node driver class IriBaseDriver such as loop_rate,
+    * may be also overload here.
+    */
+    Mvbluefox3CameraDriver(void);
+
+   /**
+    * \brief open driver
+    *
+    * In this function, the driver must be openned. Openning errors must be
+    * taken into account. This function is automatically called by 
+    * IriBaseDriver::doOpen(), an state transition is performed if return value
+    * equals true.
+    *
+    * \return bool successful
+    */
+    bool openDriver(void);
+
+   /**
+    * \brief close driver
+    *
+    * In this function, the driver must be closed. Variables related to the
+    * driver state must also be taken into account. This function is automatically
+    * called by IriBaseDriver::doClose(), an state transition is performed if 
+    * return value equals true.
+    *
+    * \return bool successful
+    */
+    bool closeDriver(void);
+
+   /**
+    * \brief start driver
+    *
+    * After this function, the driver and its thread will be started. The driver
+    * and related variables should be properly setup. This function is 
+    * automatically called by IriBaseDriver::doStart(), an state transition is  
+    * performed if return value equals true.
+    *
+    * \return bool successful
+    */
+    bool startDriver(void);
+
+   /**
+    * \brief stop driver
+    *
+    * After this function, the driver's thread will stop its execution. The driver
+    * and related variables should be properly setup. This function is 
+    * automatically called by IriBaseDriver::doStop(), an state transition is  
+    * performed if return value equals true.
+    *
+    * \return bool successful
+    */
+    bool stopDriver(void);
+
+   /**
+    * \brief config update
+    *
+    * In this function the driver parameters must be updated with the input
+    * config variable. Then the new configuration state will be stored in the 
+    * Config attribute.
+    *
+    * \param new_cfg the new driver configuration state
+    *
+    * \param level level in which the update is taken place
+    */
+    void config_update(Config& new_cfg, uint32_t level=0);
+
+   /**
+    * \brief Get image
+    *
+    * Get image.
+    */ 
+    // void GetImage(char *image);
+    void GetROSImage(const int &ncam, sensor_msgs::Image &img_msg);
+
+   /**
+    * \brief Resize objects in driver class
+    *
+    * Resize objects in driver class.
+    *
+    */
+    void ResizeObjs(void);
+
+   /**
+    * \brief Set Configuration
+    *
+    * Set Configuration with vparams_ object (to be filled externally).
+    */    
+    void SetConfig(const int &ncam);  
+
+   /**
+    * \brief Get Configuration
+    *
+    * Get Configuration.
+    */  
+    void GetConfig(const int &ncam);
+
+   /**
+    * \brief Conversion from pixel format to codings_t
+    *
+    * Conversion from pixel format to codings_t.
+    */   
+    CMvbluefox3::codings_t PfToCodes(int &pf);
+
+   /**
+    * \brief Conversion from codings_t to pixel format
+    *
+    * Conversion from codings_t to pixel format.
+    */   
+    int CodesToPf(CMvbluefox3::codings_t ct);
+
+    /**
+     * \brief Delete pointer
+     *
+     *  Function to delete pointers.
+     */
+    template <typename Ptr_t>
+    void DelPtr(Ptr_t &ptr) 
+    {
+      if (ptr != NULL) 
+      {
+        ptr = NULL;
+        delete [] ptr;
+      }
+    }
+
+   /**
+    * \brief Destructor
+    *
+    * This destructor is called when the object is about to be destroyed.
+    *
+    */
+    ~Mvbluefox3CameraDriver(void);
+};
+
+#endif
diff --git a/include/mvbluefox3_camera_driver_node.h b/include/mvbluefox3_camera_driver_node.h
new file mode 100644
index 0000000000000000000000000000000000000000..d84d3be47951f9f36e1a799cf44d8023028a391f
--- /dev/null
+++ b/include/mvbluefox3_camera_driver_node.h
@@ -0,0 +1,200 @@
+// Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC.
+// Author 
+// All rights reserved.
+//
+// This file is part of iri-ros-pkg
+// iri-ros-pkg is free software: you can redistribute it and/or modify
+// it under the terms of the GNU Lesser General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// at your option) any later version.
+//
+// This program is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+// GNU Lesser General Public License for more details.
+//
+// You should have received a copy of the GNU Lesser General Public License
+// along with this program.  If not, see <http://www.gnu.org/licenses/>.
+// 
+// IMPORTANT NOTE: This code has been generated through a script from the 
+// iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness
+// of the scripts. ROS topics can be easly add by using those scripts. Please
+// refer to the IRI wiki page for more information:
+// http://wikiri.upc.es/index.php/Robotics_Lab
+
+#ifndef _mvbluefox3_camera_driver_node_h_
+#define _mvbluefox3_camera_driver_node_h_
+
+#include <iri_base_driver/iri_base_driver_node.h>
+#include "mvbluefox3_camera_driver.h"
+
+#include <sstream>
+
+// [publisher subscriber headers]
+#include <camera_info_manager/camera_info_manager.h>
+#include <image_transport/image_transport.h>
+
+// [service client headers]
+
+// [action server client headers]
+
+/**
+ * \brief IRI ROS Specific Driver Class
+ *
+ * This class inherits from the IRI Core class IriBaseNodeDriver<IriBaseDriver>, 
+ * to provide an execution thread to the driver object. A complete framework  
+ * with utilites to test the node functionallity or to add diagnostics to  
+ * specific situations is also given. The inherit template design form allows  
+ * complete access to any IriBaseDriver object implementation.
+ *
+ * As mentioned, tests in the different driver states can be performed through 
+ * class methods such as addNodeOpenedTests() or addNodeRunningTests(). Tests
+ * common to all nodes may be also executed in the pattern class IriBaseNodeDriver.
+ * Similarly to the tests, diagnostics can easyly be added. See ROS Wiki for
+ * more details:
+ * http://www.ros.org/wiki/diagnostics/ (Tutorials: Creating a Diagnostic Analyzer)
+ * http://www.ros.org/wiki/self_test/ (Example: Self Test)
+ */
+class Mvbluefox3CameraDriverNode : public iri_base_driver::IriBaseNodeDriver<Mvbluefox3CameraDriver>
+{
+  private:
+
+    // [publisher attributes]
+
+    image_transport::ImageTransport it;
+
+    std::vector<camera_info_manager::CameraInfoManager*> camera_manager;
+    std::vector<image_transport::CameraPublisher> image_publisher_;
+    std::vector<sensor_msgs::Image> image_msg_;
+
+   /**
+    * \brief Set camera parameters
+    * 
+    * This function sets the camera parameters. The parameters must be loaded to parameter server (yaml) within a namepsace with the camera name.
+    */
+    void SetParams(const ros::NodeHandle &nh, const std::string &cam_name);
+    
+    // [subscriber attributes]
+
+    // [service attributes]
+
+    // [client attributes]
+
+    // [action server attributes]
+
+    // [action client attributes]
+
+   /**
+    * \brief post open hook
+    * 
+    * This function is called by IriBaseNodeDriver::postOpenHook(). In this function
+    * specific parameters from the driver must be added so the ROS dynamic 
+    * reconfigure application can update them.
+    */
+    void postNodeOpenHook(void);
+
+  public:
+   /**
+    * \brief constructor
+    *
+    * This constructor mainly creates and initializes the Mvbluefox3CameraDriverNode topics
+    * through the given public_node_handle object. IriBaseNodeDriver attributes 
+    * may be also modified to suit node specifications.
+    *
+    * All kind of ROS topics (publishers, subscribers, servers or clients) can 
+    * be easyly generated with the scripts in the iri_ros_scripts package. Refer
+    * to ROS and IRI Wiki pages for more details:
+    *
+    * http://www.ros.org/wiki/ROS/Tutorials/WritingPublisherSubscriber(c++)
+    * http://www.ros.org/wiki/ROS/Tutorials/WritingServiceClient(c++)
+    * http://wikiri.upc.es/index.php/Robotics_Lab
+    *
+    * \param nh a reference to the node handle object to manage all ROS topics.
+    */
+    Mvbluefox3CameraDriverNode(ros::NodeHandle& nh);
+
+   /**
+    * \brief Destructor
+    *
+    * This destructor is called when the object is about to be destroyed.
+    *
+    */
+    ~Mvbluefox3CameraDriverNode(void);
+
+
+  protected:
+   /**
+    * \brief main node thread
+    *
+    * This is the main thread node function. Code written here will be executed
+    * in every node loop while the driver is on running state. Loop frequency 
+    * can be tuned by modifying loop_rate attribute.
+    *
+    * Here data related to the process loop or to ROS topics (mainly data structs
+    * related to the MSG and SRV files) must be updated. ROS publisher objects 
+    * must publish their data in this process. ROS client servers may also
+    * request data to the corresponding server topics.
+    */
+    void mainNodeThread(void);
+
+    // [diagnostic functions]
+
+   /**
+    * \brief node add diagnostics
+    *
+    * In this function ROS diagnostics applied to this specific node may be
+    * added. Common use diagnostics for all nodes are already called from 
+    * IriBaseNodeDriver::addDiagnostics(), which also calls this function. Information
+    * of how ROS diagnostics work can be readen here:
+    * http://www.ros.org/wiki/diagnostics/
+    * http://www.ros.org/doc/api/diagnostic_updater/html/example_8cpp-source.html
+    */
+    void addNodeDiagnostics(void);
+
+    // [driver test functions]
+
+   /**
+    * \brief open status driver tests
+    *
+    * In this function tests checking driver's functionallity when driver_base 
+    * status=open can be added. Common use tests for all nodes are already called
+    * from IriBaseNodeDriver tests methods. For more details on how ROS tests work,
+    * please refer to the Self Test example in:
+    * http://www.ros.org/wiki/self_test/
+    */
+    void addNodeOpenedTests(void);
+
+   /**
+    * \brief stop status driver tests
+    *
+    * In this function tests checking driver's functionallity when driver_base 
+    * status=stop can be added. Common use tests for all nodes are already called
+    * from IriBaseNodeDriver tests methods. For more details on how ROS tests work,
+    * please refer to the Self Test example in:
+    * http://www.ros.org/wiki/self_test/
+    */
+    void addNodeStoppedTests(void);
+
+   /**
+    * \brief run status driver tests
+    *
+    * In this function tests checking driver's functionallity when driver_base 
+    * status=run can be added. Common use tests for all nodes are already called
+    * from IriBaseNodeDriver tests methods. For more details on how ROS tests work,
+    * please refer to the Self Test example in:
+    * http://www.ros.org/wiki/self_test/
+    */
+    void addNodeRunningTests(void);
+
+   /**
+    * \brief specific node dynamic reconfigure
+    *
+    * This function is called reconfigureHook()
+    * 
+    * \param level integer
+    */
+    void reconfigureNodeHook(int level);
+
+};
+
+#endif
diff --git a/launch/iri_mvbluefox3_camera.launch b/launch/iri_mvbluefox3_camera.launch
new file mode 100644
index 0000000000000000000000000000000000000000..863a8997e674f64960217031939f033434e60cba
--- /dev/null
+++ b/launch/iri_mvbluefox3_camera.launch
@@ -0,0 +1,54 @@
+<!--DOCTYPE html-->
+<launch>
+
+  <arg name="num_cams" default="1" />
+
+  <arg name="c1_name" default="cam1" />
+  <arg name="c1_serial" default="F0300123" />
+  <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/F0300123_params.xml" />
+  <!--<arg name="c1_params_path" default="$(find iri_mvbluefox3_camera)/params/example_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="F0300141" />
+  <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/F0300141_params.xml" />
+  <arg name="c2_calib_file" default="file://$(find iri_mvbluefox3_camera)/params/F0300123_calib.yaml" />  
+
+  <node pkg="iri_mvbluefox3_camera"
+        name="iri_mvbluefox3_camera"
+        type="iri_mvbluefox3_camera"
+        output="screen">
+    <param name="num_cams" value="$(arg num_cams)"/> 
+
+    <!-- CAMERA 1 -->
+    <param name="c1/name"        value="$(arg c1_name)"/> 
+    <param name="c1/serial"      value="$(arg c1_serial)" /> 
+    <param name="c1/frame_id"    value="$(arg c1_frame_id)"/> 
+    <param name="c1/tf_prefix"   value="$(arg c1_tf_prefix)"/> 
+    <param name="c1/params_path" value="$(arg c1_params_path)"/> 
+    <param name="c1/calib_file"  value="$(arg c1_calib_file)"/> 
+
+    <!-- CAMERA 2 -->
+    <param name="c2/name"        value="$(arg c2_name)"/> 
+    <param name="c2/serial"      value="$(arg c2_serial)" /> 
+    <param name="c2/frame_id"    value="$(arg c2_frame_id)" /> 
+    <param name="c2/tf_prefix"   value="$(arg c2_tf_prefix)" /> 
+    <param name="c2/params_path" value="$(arg c2_params_path)" /> 
+    <param name="c2/calib_file"  value="$(arg c2_calib_file)"/>       
+  </node>
+
+
+  <!-- ########## VISUALIZATION ##########-->
+  <node pkg="image_view" type="image_view" name="image_view_$(arg c1_name)" >
+    <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)" >
+    <remap from="/image" to="/iri_mvbluefox3_camera/$(arg c2_name)/image_raw"/>
+  </node>   -->
+
+</launch>
diff --git a/package.xml b/package.xml
index 251b5950e27079271e060d4e9778be8a0b245764..96b9a3048c2855eccabb1e79443dd52dd8373897 100644
--- a/package.xml
+++ b/package.xml
@@ -40,6 +40,7 @@
   <!-- Use test_depend for packages you need only for testing: -->
   <!--   <test_depend>gtest</test_depend> -->
   <buildtool_depend>catkin</buildtool_depend>
+
   <build_depend>dynamic_reconfigure</build_depend>
   <build_depend>image_transport</build_depend>
   <build_depend>camera_info_manager</build_depend>
@@ -51,7 +52,6 @@
   <run_depend>dynamic_reconfigure</run_depend>
   <run_depend>sensor_msgs</run_depend>
 
-
   <!-- The export tag contains other, unspecified, tags -->
   <export>
     <!-- Other tools can request additional information be placed here -->
diff --git a/params/.F0300141_params.yaml b/params/.F0300141_params.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..1e7e5d8411ddc24fb09c7240f5d8418c1119a9ea
--- /dev/null
+++ b/params/.F0300141_params.yaml
@@ -0,0 +1,44 @@
+serial: F0300141
+frame_id: mvbluefox3_F0300141
+tf_preix: ""
+
+#Image format
+pixel_format: 1 # e.g. mono8 = 1; rgb8 = 3;
+width: 1280
+height: 960
+img_rot_angle: 0.0
+mirror: 0
+set_aoi: false
+aoi_width: 1280
+aoi_height: 960
+aoi_start_x: 0
+aoi_start_y: 0
+h_binning_enbl: false
+h_binning: 1
+v_binning_enbl: false
+v_binning: 1
+  
+# Acquisition 
+frame_rate : 100000
+frate_limit_mode: 0
+pixel_clock: 66000
+req_timeout: 2000
+auto_ctrl_enbl: false
+auto_ctrl_speed: 1
+auto_expose: true
+auto_expose_upperlimit: 32759
+auto_expose_des_grey_val: 50
+expose_us: 10000
+auto_gain: false
+gain_db: 0
+gamma: false   
+
+# Image processing
+whiteblnce_auto_enbl: true
+wb_r_gain: 1.0
+wb_b_gain: 1.0
+auto_blck_level: true
+blck_level: 0
+hdr_enbl: false
+dark_cfilter: 0
+twist_cfilter: false
\ No newline at end of file
diff --git a/params/F0300123_calib.yaml b/params/F0300123_calib.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..514d103b231f2938e1e822b2772927211ad38810
--- /dev/null
+++ b/params/F0300123_calib.yaml
@@ -0,0 +1,20 @@
+image_width: 1280
+image_height: 960
+camera_name: camera
+camera_matrix:
+  rows: 3
+  cols: 3
+  data: [976.915955, 0, 582.117763, 0, 977.821859, 440.568838, 0, 0, 1]
+distortion_model: plumb_bob
+distortion_coefficients:
+  rows: 1
+  cols: 5
+  data: [-0.103886, 0.096744, -0.001615, -0.000599, 0.000000]
+rectification_matrix:
+  rows: 3
+  cols: 3
+  data: [1, 0, 0, 0, 1, 0, 0, 0, 1]
+projection_matrix:
+  rows: 3
+  cols: 4
+  data: [953.288513, 0, 582.082677, 0, 0, 956.783997, 437.916171, 0, 0, 0, 1, 0]
\ No newline at end of file
diff --git a/params/F0300123_params.xml b/params/F0300123_params.xml
new file mode 100644
index 0000000000000000000000000000000000000000..e50c22f4ffc83702ed0e0149baf3380994ac7242
--- /dev/null
+++ b/params/F0300123_params.xml
@@ -0,0 +1,2028 @@
+<?xml version="1.0" encoding="UTF-8" standalone="yes"?>
+<PropList contentDescriptor="mvBlueFOX3-M1012bC data(interface layout: GenICam)" name="DriverData" default="0" flags="3" size="7" parent="none" versionMajor="2" versionMinor="17" versionRelease="0">
+<PropList name="ImagingSubsystem" default="0" position="0" flags="3" size="5" parent="none">
+<PropList name="Setting" default="0" position="0" flags="3" size="1" parent="none">
+<PropList name="Base" default="0" position="0" flags="3" size="6" parent="none">
+<PropList name="Camera" default="0" position="1" flags="3" size="3" parent="none">
+<Property name="GenICamFeatureBag_91473E04-B76B-422d-8F52-A5D5A768C984" default="0" position="0" flags="7" size="1" formatString="%s" valType="4">
+<Value index="0"># {05D8C294-F295-4dfb-9D01-096BD04049F4}
+# GenApi persistence file (version 3.0.1)
+# Device = MATRIX_VISION::mvBlueFOX3 -- MATRIX VISION USB3Vision camera interface -- Device version = 53.0.0 -- Product GUID = 8A5441D1-A059-11E6-A17E-E9D83A4B713F -- Product version GUID = 8A5468E1-A059-11E6-8532-E9D83A4B713F
+DeviceClockSelector	Sensor
+mvDeviceClockFrequency	kHz_66000
+DeviceClockSelector	Sensor
+DeviceScanType	Areascan
+mvDeviceProcessingUnitSelector	0
+mvDeviceProcessingUnit	mvFrameAverage
+mvDeviceProcessingUnitSelector	0
+DeviceLinkSelector	0
+DeviceLinkThroughputLimitMode	Off
+DeviceLinkSelector	0
+Width	1280
+Height	960
+OffsetX	0
+OffsetY	0
+PixelFormat	RGB8
+TestPattern	Off
+BinningHorizontal	1
+DecimationHorizontal	1
+DecimationVertical	1
+ReverseX	0
+ReverseY	0
+AcquisitionMode	Continuous
+ExposureMode	Timed
+ExposureTime	20000
+ExposureAuto	Off
+TriggerSelector	FrameStart
+TriggerMode	Off
+TriggerSelector	AcquisitionStart
+TriggerMode	Off
+TriggerSelector	AcquisitionEnd
+TriggerMode	Off
+TriggerSelector	AcquisitionActive
+TriggerMode	Off
+TriggerSelector	mvTimestampReset
+TriggerMode	Off
+TriggerSelector	FrameBurstStart
+TriggerMode	Off
+TriggerSelector	FrameBurstActive
+TriggerMode	Off
+TriggerSelector	FrameStart
+TriggerSelector	FrameStart
+TriggerSource	Line4
+TriggerSelector	AcquisitionStart
+TriggerSource	Line4
+TriggerSelector	AcquisitionEnd
+TriggerSource	Line4
+TriggerSelector	AcquisitionActive
+TriggerSource	Line4
+TriggerSelector	mvTimestampReset
+TriggerSource	Line4
+TriggerSelector	FrameBurstStart
+TriggerSource	Line4
+TriggerSelector	FrameBurstActive
+TriggerSource	Line4
+TriggerSelector	FrameStart
+TriggerSelector	FrameStart
+TriggerActivation	RisingEdge
+TriggerSelector	AcquisitionStart
+TriggerActivation	RisingEdge
+TriggerSelector	AcquisitionEnd
+TriggerActivation	RisingEdge
+TriggerSelector	AcquisitionActive
+TriggerActivation	LevelHigh
+TriggerSelector	mvTimestampReset
+TriggerActivation	RisingEdge
+TriggerSelector	FrameBurstStart
+TriggerActivation	RisingEdge
+TriggerSelector	FrameBurstActive
+TriggerActivation	LevelHigh
+TriggerSelector	FrameStart
+TriggerSelector	FrameStart
+TriggerDelay	0
+TriggerSelector	AcquisitionStart
+TriggerDelay	0
+TriggerSelector	AcquisitionEnd
+TriggerDelay	0
+TriggerSelector	AcquisitionActive
+TriggerDelay	0
+TriggerSelector	mvTimestampReset
+TriggerDelay	0
+TriggerSelector	FrameBurstStart
+TriggerDelay	0
+TriggerSelector	FrameBurstActive
+TriggerDelay	0
+TriggerSelector	FrameStart
+mvAcquisitionFrameRateLimitMode	mvDeviceLinkThroughput
+AcquisitionFrameRateEnable	0
+mvAcquisitionFrameRateEnable	Off
+AcquisitionFrameCount	1
+mvAcquisitionMemoryMode	Default
+CounterSelector	Counter1
+CounterEventSource	Off
+CounterSelector	Counter2
+CounterEventSource	Off
+CounterSelector	Counter3
+CounterEventSource	Off
+CounterSelector	Counter4
+CounterEventSource	Off
+CounterSelector	Counter1
+CounterSelector	Counter1
+CounterResetSource	Off
+CounterSelector	Counter2
+CounterResetSource	Off
+CounterSelector	Counter3
+CounterResetSource	Off
+CounterSelector	Counter4
+CounterResetSource	Off
+CounterSelector	Counter1
+CounterSelector	Counter1
+CounterTriggerSource	Off
+CounterSelector	Counter2
+CounterTriggerSource	Off
+CounterSelector	Counter3
+CounterTriggerSource	Off
+CounterSelector	Counter4
+CounterTriggerSource	Off
+CounterSelector	Counter1
+CounterSelector	Counter1
+CounterDuration	10000
+CounterSelector	Counter2
+CounterDuration	10000
+CounterSelector	Counter3
+CounterDuration	10000
+CounterSelector	Counter4
+CounterDuration	10000
+CounterSelector	Counter1
+CounterSelector	Counter1
+CounterValue	0
+CounterSelector	Counter2
+CounterValue	0
+CounterSelector	Counter3
+CounterValue	0
+CounterSelector	Counter4
+CounterValue	0
+CounterSelector	Counter1
+TimerSelector	Timer1
+TimerTriggerSource	Timer1End
+TimerSelector	Timer2
+TimerTriggerSource	Timer2End
+TimerSelector	Timer1
+TimerSelector	Timer1
+TimerDuration	20000
+TimerSelector	Timer2
+TimerDuration	20000
+TimerSelector	Timer1
+TimerSelector	Timer1
+TimerDelay	0
+TimerSelector	Timer2
+TimerDelay	0
+TimerSelector	Timer1
+TimerSelector	Timer1
+TimerValue	1128
+TimerSelector	Timer2
+TimerValue	12347
+TimerSelector	Timer1
+GainSelector	AnalogAll
+Gain	0
+GainSelector	DigitalAll
+Gain	0
+GainSelector	AnalogAll
+GainSelector	AnalogAll
+GainAuto	Off
+GainSelector	AnalogAll
+BlackLevelSelector	All
+BlackLevel	0
+BlackLevelSelector	DigitalAll
+BlackLevel	0
+BlackLevelSelector	All
+BlackLevelSelector	All
+BlackLevelAuto	Continuous
+BlackLevelSelector	All
+BalanceRatioSelector	Red
+BalanceRatio	1.21
+BalanceRatioSelector	Blue
+BalanceRatio	1.9
+BalanceRatioSelector	Blue
+BalanceWhiteAuto	Off
+mvLogicGateANDSelector	mvLogicGateAND1
+mvLogicGateANDSource1	Off
+mvLogicGateANDSelector	mvLogicGateAND2
+mvLogicGateANDSource1	Off
+mvLogicGateANDSelector	mvLogicGateAND3
+mvLogicGateANDSource1	Off
+mvLogicGateANDSelector	mvLogicGateAND4
+mvLogicGateANDSource1	Off
+mvLogicGateANDSelector	mvLogicGateAND1
+mvLogicGateANDSelector	mvLogicGateAND1
+mvLogicGateANDSource2	Off
+mvLogicGateANDSelector	mvLogicGateAND2
+mvLogicGateANDSource2	Off
+mvLogicGateANDSelector	mvLogicGateAND3
+mvLogicGateANDSource2	Off
+mvLogicGateANDSelector	mvLogicGateAND4
+mvLogicGateANDSource2	Off
+mvLogicGateANDSelector	mvLogicGateAND1
+mvLogicGateORSelector	mvLogicGateOR1
+mvLogicGateORSource1	mvLogicGateAND1Output
+mvLogicGateORSelector	mvLogicGateOR2
+mvLogicGateORSource1	mvLogicGateAND2Output
+mvLogicGateORSelector	mvLogicGateOR3
+mvLogicGateORSource1	mvLogicGateAND3Output
+mvLogicGateORSelector	mvLogicGateOR4
+mvLogicGateORSource1	mvLogicGateAND4Output
+mvLogicGateORSelector	mvLogicGateOR1
+mvLogicGateORSelector	mvLogicGateOR1
+mvLogicGateORSource2	Off
+mvLogicGateORSelector	mvLogicGateOR2
+mvLogicGateORSource2	Off
+mvLogicGateORSelector	mvLogicGateOR3
+mvLogicGateORSource2	Off
+mvLogicGateORSelector	mvLogicGateOR4
+mvLogicGateORSource2	Off
+mvLogicGateORSelector	mvLogicGateOR1
+mvLogicGateORSelector	mvLogicGateOR1
+mvLogicGateORSource3	Off
+mvLogicGateORSelector	mvLogicGateOR2
+mvLogicGateORSource3	Off
+mvLogicGateORSelector	mvLogicGateOR3
+mvLogicGateORSource3	Off
+mvLogicGateORSelector	mvLogicGateOR4
+mvLogicGateORSource3	Off
+mvLogicGateORSelector	mvLogicGateOR1
+mvLogicGateORSelector	mvLogicGateOR1
+mvLogicGateORSource4	Off
+mvLogicGateORSelector	mvLogicGateOR2
+mvLogicGateORSource4	Off
+mvLogicGateORSelector	mvLogicGateOR3
+mvLogicGateORSource4	Off
+mvLogicGateORSelector	mvLogicGateOR4
+mvLogicGateORSource4	Off
+mvLogicGateORSelector	mvLogicGateOR1
+ChunkModeActive	0
+ChunkSelector	Image
+ChunkEnable	1
+ChunkSelector	OffsetX
+ChunkEnable	1
+ChunkSelector	OffsetY
+ChunkEnable	1
+ChunkSelector	Width
+ChunkEnable	1
+ChunkSelector	Height
+ChunkEnable	1
+ChunkSelector	PixelFormat
+ChunkEnable	1
+ChunkSelector	Timestamp
+ChunkEnable	1
+ChunkSelector	LineStatusAll
+ChunkEnable	1
+ChunkSelector	CounterValue
+ChunkEnable	1
+ChunkSelector	TimerValue
+ChunkEnable	1
+ChunkSelector	ExposureTime
+ChunkEnable	1
+ChunkSelector	Gain
+ChunkEnable	1
+ChunkSelector	mvCustomIdentifier
+ChunkEnable	1
+ChunkSelector	Image
+LineSelector	Line0
+LineSource	Off
+LineSelector	Line1
+LineSource	Off
+LineSelector	Line2
+LineSource	Off
+LineSelector	Line3
+LineSource	Off
+LineSelector	Line0
+LineSelector	Line0
+LineInverter	0
+LineSelector	Line1
+LineInverter	0
+LineSelector	Line2
+LineInverter	0
+LineSelector	Line3
+LineInverter	0
+LineSelector	Line0
+LineSelector	Line4
+mvLineDebounceTimeRisingEdge	0
+LineSelector	Line5
+mvLineDebounceTimeRisingEdge	0
+LineSelector	Line0
+LineSelector	Line4
+mvLineDebounceTimeFallingEdge	0
+LineSelector	Line5
+mvLineDebounceTimeFallingEdge	0
+LineSelector	Line0
+UserOutputSelector	UserOutput0
+UserOutputValue	0
+UserOutputSelector	UserOutput1
+UserOutputValue	0
+UserOutputSelector	UserOutput2
+UserOutputValue	0
+UserOutputSelector	UserOutput3
+UserOutputValue	0
+UserOutputSelector	UserOutput0
+UserOutputValueAll	0
+UserOutputValueAllMask	0
+mvFrameAverageEnable	0
+mvFrameAverageMode	mvNTo1
+mvFrameAverageFrameCount	2
+ColorTransformationSelector	RGBtoRGB
+ColorTransformationEnable	0
+ColorTransformationSelector	RGBtoRGB
+ColorTransformationSelector	RGBtoRGB
+ColorTransformationValueSelector	Gain00
+ColorTransformationValue	1.86334
+ColorTransformationValueSelector	Gain01
+ColorTransformationValue	-0.586815
+ColorTransformationValueSelector	Gain02
+ColorTransformationValue	-0.219307
+ColorTransformationValueSelector	Gain10
+ColorTransformationValue	-0.423441
+ColorTransformationValueSelector	Gain11
+ColorTransformationValue	1.50376
+ColorTransformationValueSelector	Gain12
+ColorTransformationValue	-0.0803193
+ColorTransformationValueSelector	Gain20
+ColorTransformationValue	-0.0407081
+ColorTransformationValueSelector	Gain21
+ColorTransformationValue	-0.856356
+ColorTransformationValueSelector	Gain22
+ColorTransformationValue	2.18277
+ColorTransformationValueSelector	Offset0
+ColorTransformationValue	0
+ColorTransformationValueSelector	Offset1
+ColorTransformationValue	0
+ColorTransformationValueSelector	Offset2
+ColorTransformationValue	0
+ColorTransformationSelector	RGBtoRGB
+ColorTransformationValueSelector	Gain00
+LUTSelector	Red
+LUTEnable	0
+LUTSelector	Green
+LUTEnable	0
+LUTSelector	Blue
+LUTEnable	0
+LUTSelector	Luminance
+LUTEnable	0
+LUTSelector	Luminance
+LUTSelector	Red
+LUTValueAll	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
+LUTSelector	Green
+LUTValueAll	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
+LUTSelector	Blue
+LUTValueAll	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
+LUTSelector	Luminance
+LUTValueAll	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
+LUTSelector	Luminance
+EventSelector	ExposureEnd
+EventNotification	Off
+EventSelector	Line4RisingEdge
+EventNotification	Off
+EventSelector	Line5RisingEdge
+EventNotification	Off
+EventSelector	FrameEnd
+EventNotification	Off
+EventSelector	ExposureEnd
+</Value>
+</Property>
+<Property name="ImageRequestTimeout_ms" default="0" position="2" flags="7" size="1" formatString="%d ms" valType="1">
+<Value index="0" val="2000 ms"></Value>
+</Property>
+</PropList>
+<PropList name="ImageProcessing" default="0" position="3" flags="3" size="24" parent="none">
+<PropList name="FormatReinterpreter" default="0" position="1" flags="3" size="2" parent="none">
+<Property name="FormatReinterpreterEnable" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="FormatReinterpreterMode" default="0" position="1" flags="7" size="1" formatString="0x%08x" valType="1">
+<Value index="0" val="Mono8_To_RGB888Packed"></Value>
+</Property>
+</PropList>
+<PropList name="DefectivePixelsFilter" default="0" position="2" flags="3" size="4" parent="none">
+<Property name="Mode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="LeakyPixelDeviation_ADCLimit" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+<Property name="ColdPixelDeviation_pc" default="0" position="2" flags="7" size="1" formatString="%d %%" valType="1">
+<Value index="0" val="15 %"></Value>
+</Property>
+</PropList>
+<PropList name="DarkCurrentFilter" default="0" position="3" flags="3" size="3" parent="none">
+<Property name="Mode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="CalibrationImageCount" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="5"></Value>
+</Property>
+</PropList>
+<PropList name="FlatFieldFilter" default="0" position="4" flags="3" size="3" parent="none">
+<Property name="Mode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="CorrectionMode" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Default"></Value>
+</Property>
+<Property name="CalibrationImageCount" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="5"></Value>
+</Property>
+</PropList>
+<PropList name="GainOffsetKnee" default="0" position="6" flags="3" size="3" parent="none">
+<Property name="GainOffsetKneeEnable" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="GainOffsetKneeMasterOffset_pc" default="0" position="1" flags="7" size="1" formatString="%.2f %%" valType="2">
+<Value index="0" val="0.00 %"></Value>
+</Property>
+<PropList name="GainOffsetKneeChannels" default="0" position="2" flags="7" size="4" parent="none">
+<PropList name="Channel-0" default="0" position="0" flags="7" size="2" parent="none">
+<Property name="Gain" default="0" position="0" flags="7" size="1" formatString="%.4f" valType="2">
+<Value index="0" val="1.0000"></Value>
+</Property>
+<Property name="Offset_pc" default="0" position="1" flags="7" size="1" formatString="%.2f %%" valType="2">
+<Value index="0" val="0.00 %"></Value>
+</Property>
+</PropList>
+<PropList name="Channel-1" default="0" position="1" flags="7" size="2" parent="none">
+<Property name="Gain" default="0" position="0" flags="7" size="1" formatString="%.4f" valType="2">
+<Value index="0" val="1.0000"></Value>
+</Property>
+<Property name="Offset_pc" default="0" position="1" flags="7" size="1" formatString="%.2f %%" valType="2">
+<Value index="0" val="0.00 %"></Value>
+</Property>
+</PropList>
+<PropList name="Channel-2" default="0" position="2" flags="7" size="2" parent="none">
+<Property name="Gain" default="0" position="0" flags="7" size="1" formatString="%.4f" valType="2">
+<Value index="0" val="1.0000"></Value>
+</Property>
+<Property name="Offset_pc" default="0" position="1" flags="7" size="1" formatString="%.2f %%" valType="2">
+<Value index="0" val="0.00 %"></Value>
+</Property>
+</PropList>
+<PropList name="Channel-3" default="0" position="3" flags="7" size="2" parent="none">
+<Property name="Gain" default="0" position="0" flags="7" size="1" formatString="%.4f" valType="2">
+<Value index="0" val="1.0000"></Value>
+</Property>
+<Property name="Offset_pc" default="0" position="1" flags="7" size="1" formatString="%.2f %%" valType="2">
+<Value index="0" val="0.00 %"></Value>
+</Property>
+</PropList>
+</PropList>
+</PropList>
+<Property name="MirrorMode" default="0" position="7" flags="39" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<PropList name="Mirror" default="0" position="8" flags="3" size="3" parent="none">
+<Property name="MirrorOperationMode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Global"></Value>
+</Property>
+<Property name="MirrorModeGlobal" default="0" position="1" flags="39" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<PropList name="MirrorChannels" default="0" position="2" flags="7" size="3" parent="none">
+<PropList name="Channel-0" default="0" position="0" flags="7" size="1" parent="none">
+<Property name="MirrorMode" default="0" position="0" flags="39" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+</PropList>
+<PropList name="Channel-1" default="0" position="1" flags="7" size="1" parent="none">
+<Property name="MirrorMode" default="0" position="0" flags="39" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+</PropList>
+<PropList name="Channel-2" default="0" position="2" flags="7" size="1" parent="none">
+<Property name="MirrorMode" default="0" position="0" flags="39" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+</PropList>
+</PropList>
+</PropList>
+<Property name="ColorProcessing" default="0" position="9" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Auto"></Value>
+</Property>
+<Property name="BayerConversionMode" default="0" position="10" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Auto"></Value>
+</Property>
+<Property name="WhiteBalance" default="0" position="11" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="User1"></Value>
+</Property>
+<Property name="WhiteBalanceCalibration" default="0" position="12" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<PropList name="WhiteBalanceSettings-1" default="0" position="13" flags="3" size="8" parent="none">
+<Property name="WBAoiMode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Centered"></Value>
+</Property>
+<PropList name="WBAoi" default="0" position="1" flags="3" size="4" parent="none">
+<Property name="X" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="295"></Value>
+</Property>
+<Property name="Y" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="215"></Value>
+</Property>
+<Property name="W" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+<Property name="H" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+</PropList>
+<Property name="TotalGain" default="0" position="2" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="Offset" default="0" position="3" flags="7" size="1" formatString="%.1f" valType="2">
+<Value index="0" val="0.0"></Value>
+</Property>
+<Property name="RedGain" default="0" position="4" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="GreenGain" default="0" position="5" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="BlueGain" default="0" position="6" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+</PropList>
+<PropList name="WhiteBalanceSettings-2" default="0" position="14" flags="3" size="8" parent="none">
+<Property name="WBAoiMode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Centered"></Value>
+</Property>
+<PropList name="WBAoi" default="0" position="1" flags="3" size="4" parent="none">
+<Property name="X" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="295"></Value>
+</Property>
+<Property name="Y" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="215"></Value>
+</Property>
+<Property name="W" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+<Property name="H" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+</PropList>
+<Property name="TotalGain" default="0" position="2" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="Offset" default="0" position="3" flags="7" size="1" formatString="%.1f" valType="2">
+<Value index="0" val="0.0"></Value>
+</Property>
+<Property name="RedGain" default="0" position="4" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="GreenGain" default="0" position="5" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="BlueGain" default="0" position="6" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+</PropList>
+<PropList name="WhiteBalanceSettings-3" default="0" position="15" flags="3" size="8" parent="none">
+<Property name="WBAoiMode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Centered"></Value>
+</Property>
+<PropList name="WBAoi" default="0" position="1" flags="3" size="4" parent="none">
+<Property name="X" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="295"></Value>
+</Property>
+<Property name="Y" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="215"></Value>
+</Property>
+<Property name="W" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+<Property name="H" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+</PropList>
+<Property name="TotalGain" default="0" position="2" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="Offset" default="0" position="3" flags="7" size="1" formatString="%.1f" valType="2">
+<Value index="0" val="0.0"></Value>
+</Property>
+<Property name="RedGain" default="0" position="4" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="GreenGain" default="0" position="5" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="BlueGain" default="0" position="6" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+</PropList>
+<PropList name="WhiteBalanceSettings-4" default="0" position="16" flags="3" size="8" parent="none">
+<Property name="WBAoiMode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Centered"></Value>
+</Property>
+<PropList name="WBAoi" default="0" position="1" flags="3" size="4" parent="none">
+<Property name="X" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="295"></Value>
+</Property>
+<Property name="Y" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="215"></Value>
+</Property>
+<Property name="W" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+<Property name="H" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+</PropList>
+<Property name="TotalGain" default="0" position="2" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="Offset" default="0" position="3" flags="7" size="1" formatString="%.1f" valType="2">
+<Value index="0" val="0.0"></Value>
+</Property>
+<Property name="RedGain" default="0" position="4" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="GreenGain" default="0" position="5" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="BlueGain" default="0" position="6" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+</PropList>
+<Property name="Filter" default="0" position="17" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<PropList name="Saturation" default="0" position="18" flags="3" size="3" parent="none">
+<Property name="Mode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="Saturation_pc" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="100"></Value>
+</Property>
+<Property name="UVWeighting" default="0" position="2" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.400"></Value>
+</Property>
+</PropList>
+<PropList name="ColorTwist" default="0" position="19" flags="3" size="17" parent="none">
+<Property name="ColorTwistInputCorrectionMatrixEnable" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="ColorTwistInputCorrectionMatrixMode" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="DeviceSpecific"></Value>
+</Property>
+<Property name="ColorTwistInputCorrectionMatrixRow0" default="0" position="2" flags="7" size="3" formatString="%8.5f" valType="2">
+<Value index="0" val=" 1.00000"></Value>
+<Value index="1" val=" 0.00000"></Value>
+<Value index="2" val=" 0.00000"></Value>
+</Property>
+<Property name="ColorTwistInputCorrectionMatrixRow1" default="0" position="3" flags="7" size="3" formatString="%8.5f" valType="2">
+<Value index="0" val=" 0.00000"></Value>
+<Value index="1" val=" 1.00000"></Value>
+<Value index="2" val=" 0.00000"></Value>
+</Property>
+<Property name="ColorTwistInputCorrectionMatrixRow2" default="0" position="4" flags="7" size="3" formatString="%8.5f" valType="2">
+<Value index="0" val=" 0.00000"></Value>
+<Value index="1" val=" 0.00000"></Value>
+<Value index="2" val=" 1.00000"></Value>
+</Property>
+<Property name="ColorTwistEnable" default="0" position="5" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="ColorTwistRow0" default="0" position="6" flags="7" size="4" formatString="%8.5f" valType="2">
+<Value index="0" val=" 1.00000"></Value>
+<Value index="1" val=" 0.00000"></Value>
+<Value index="2" val=" 0.00000"></Value>
+<Value index="3" val=" 0.00000"></Value>
+</Property>
+<Property name="ColorTwistRow1" default="0" position="7" flags="7" size="4" formatString="%8.5f" valType="2">
+<Value index="0" val=" 0.00000"></Value>
+<Value index="1" val=" 1.00000"></Value>
+<Value index="2" val=" 0.00000"></Value>
+<Value index="3" val=" 0.00000"></Value>
+</Property>
+<Property name="ColorTwistRow2" default="0" position="8" flags="7" size="4" formatString="%8.5f" valType="2">
+<Value index="0" val=" 0.00000"></Value>
+<Value index="1" val=" 0.00000"></Value>
+<Value index="2" val=" 1.00000"></Value>
+<Value index="3" val=" 0.00000"></Value>
+</Property>
+<Property name="ColorTwistOutputCorrectionMatrixEnable" default="0" position="9" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="ColorTwistOutputCorrectionMatrixMode" default="0" position="10" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="XYZTosRGB_D50"></Value>
+</Property>
+<Property name="ColorTwistOutputCorrectionMatrixRow0" default="0" position="11" flags="7" size="3" formatString="%8.5f" valType="2">
+<Value index="0" val=" 1.00000"></Value>
+<Value index="1" val=" 0.00000"></Value>
+<Value index="2" val=" 0.00000"></Value>
+</Property>
+<Property name="ColorTwistOutputCorrectionMatrixRow1" default="0" position="12" flags="7" size="3" formatString="%8.5f" valType="2">
+<Value index="0" val=" 0.00000"></Value>
+<Value index="1" val=" 1.00000"></Value>
+<Value index="2" val=" 0.00000"></Value>
+</Property>
+<Property name="ColorTwistOutputCorrectionMatrixRow2" default="0" position="13" flags="7" size="3" formatString="%8.5f" valType="2">
+<Value index="0" val=" 0.00000"></Value>
+<Value index="1" val=" 0.00000"></Value>
+<Value index="2" val=" 1.00000"></Value>
+</Property>
+</PropList>
+<PropList name="LUTOperations" default="0" position="20" flags="3" size="7" parent="none">
+<Property name="LUTEnable" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="LUTMode" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Gamma"></Value>
+</Property>
+<Property name="LUTInterpolationMode" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Linear"></Value>
+</Property>
+<Property name="LUTImplementation" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Software"></Value>
+</Property>
+<Property name="LUTMappingHardware" default="0" position="4" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+</Property>
+<Property name="LUTMappingSoftware" default="0" position="5" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="8To8"></Value>
+</Property>
+<PropList name="LUTs" default="0" position="6" flags="7" size="4" parent="none">
+<PropList name="LUT-0" default="0" position="0" flags="7" size="10" parent="none">
+<Property name="Gamma" default="0" position="0" flags="7" size="1" formatString="%f" valType="2">
+<Value index="0" val="1.800000"></Value>
+</Property>
+<Property name="GammaAlpha" default="0" position="1" flags="7" size="1" formatString="%f" valType="2">
+<Value index="0" val="0.000000"></Value>
+</Property>
+<Property name="GammaMode" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="LinearStart"></Value>
+</Property>
+<Property name="GammaStartThreshold" default="0" position="3" flags="263" size="1" formatString="%d" valType="1">
+<Value index="0" val="12"></Value>
+</Property>
+<Property name="ValueCount" default="1" position="4" flags="259" size="1" formatString="%d" valType="1">
+<Value index="0" val="2"></Value>
+</Property>
+<Property name="InputValues" default="0" position="5" flags="263" size="2" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+<Value index="1" val="255"></Value>
+</Property>
+<Property name="OutputValues" default="0" position="6" flags="263" size="2" formatString="%d" valType="1">
+<Value index="0" val="255"></Value>
+<Value index="1" val="0"></Value>
+</Property>
+<Property name="DirectValues" default="0" position="7" flags="263" size="256" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+<Value index="1" val="0"></Value>
+<Value index="2" val="0"></Value>
+<Value index="3" val="0"></Value>
+<Value index="4" val="0"></Value>
+<Value index="5" val="0"></Value>
+<Value index="6" val="0"></Value>
+<Value index="7" val="0"></Value>
+<Value index="8" val="0"></Value>
+<Value index="9" val="0"></Value>
+<Value index="10" val="0"></Value>
+<Value index="11" val="0"></Value>
+<Value index="12" val="0"></Value>
+<Value index="13" val="0"></Value>
+<Value index="14" val="0"></Value>
+<Value index="15" val="0"></Value>
+<Value index="16" val="0"></Value>
+<Value index="17" val="0"></Value>
+<Value index="18" val="0"></Value>
+<Value index="19" val="0"></Value>
+<Value index="20" val="0"></Value>
+<Value index="21" val="0"></Value>
+<Value index="22" val="0"></Value>
+<Value index="23" val="0"></Value>
+<Value index="24" val="0"></Value>
+<Value index="25" val="0"></Value>
+<Value index="26" val="0"></Value>
+<Value index="27" val="0"></Value>
+<Value index="28" val="0"></Value>
+<Value index="29" val="0"></Value>
+<Value index="30" val="0"></Value>
+<Value index="31" val="0"></Value>
+<Value index="32" val="0"></Value>
+<Value index="33" val="0"></Value>
+<Value index="34" val="0"></Value>
+<Value index="35" val="0"></Value>
+<Value index="36" val="0"></Value>
+<Value index="37" val="0"></Value>
+<Value index="38" val="0"></Value>
+<Value index="39" val="0"></Value>
+<Value index="40" val="0"></Value>
+<Value index="41" val="0"></Value>
+<Value index="42" val="0"></Value>
+<Value index="43" val="0"></Value>
+<Value index="44" val="0"></Value>
+<Value index="45" val="0"></Value>
+<Value index="46" val="0"></Value>
+<Value index="47" val="0"></Value>
+<Value index="48" val="0"></Value>
+<Value index="49" val="0"></Value>
+<Value index="50" val="0"></Value>
+<Value index="51" val="0"></Value>
+<Value index="52" val="0"></Value>
+<Value index="53" val="0"></Value>
+<Value index="54" val="0"></Value>
+<Value index="55" val="0"></Value>
+<Value index="56" val="0"></Value>
+<Value index="57" val="0"></Value>
+<Value index="58" val="0"></Value>
+<Value index="59" val="0"></Value>
+<Value index="60" val="0"></Value>
+<Value index="61" val="0"></Value>
+<Value index="62" val="0"></Value>
+<Value index="63" val="0"></Value>
+<Value index="64" val="0"></Value>
+<Value index="65" val="0"></Value>
+<Value index="66" val="0"></Value>
+<Value index="67" val="0"></Value>
+<Value index="68" val="0"></Value>
+<Value index="69" val="0"></Value>
+<Value index="70" val="0"></Value>
+<Value index="71" val="0"></Value>
+<Value index="72" val="0"></Value>
+<Value index="73" val="0"></Value>
+<Value index="74" val="0"></Value>
+<Value index="75" val="0"></Value>
+<Value index="76" val="0"></Value>
+<Value index="77" val="0"></Value>
+<Value index="78" val="0"></Value>
+<Value index="79" val="0"></Value>
+<Value index="80" val="0"></Value>
+<Value index="81" val="0"></Value>
+<Value index="82" val="0"></Value>
+<Value index="83" val="0"></Value>
+<Value index="84" val="0"></Value>
+<Value index="85" val="0"></Value>
+<Value index="86" val="0"></Value>
+<Value index="87" val="0"></Value>
+<Value index="88" val="0"></Value>
+<Value index="89" val="0"></Value>
+<Value index="90" val="0"></Value>
+<Value index="91" val="0"></Value>
+<Value index="92" val="0"></Value>
+<Value index="93" val="0"></Value>
+<Value index="94" val="0"></Value>
+<Value index="95" val="0"></Value>
+<Value index="96" val="0"></Value>
+<Value index="97" val="0"></Value>
+<Value index="98" val="0"></Value>
+<Value index="99" val="0"></Value>
+<Value index="100" val="0"></Value>
+<Value index="101" val="0"></Value>
+<Value index="102" val="0"></Value>
+<Value index="103" val="0"></Value>
+<Value index="104" val="0"></Value>
+<Value index="105" val="0"></Value>
+<Value index="106" val="0"></Value>
+<Value index="107" val="0"></Value>
+<Value index="108" val="0"></Value>
+<Value index="109" val="0"></Value>
+<Value index="110" val="0"></Value>
+<Value index="111" val="0"></Value>
+<Value index="112" val="0"></Value>
+<Value index="113" val="0"></Value>
+<Value index="114" val="0"></Value>
+<Value index="115" val="0"></Value>
+<Value index="116" val="0"></Value>
+<Value index="117" val="0"></Value>
+<Value index="118" val="0"></Value>
+<Value index="119" val="0"></Value>
+<Value index="120" val="0"></Value>
+<Value index="121" val="0"></Value>
+<Value index="122" val="0"></Value>
+<Value index="123" val="0"></Value>
+<Value index="124" val="0"></Value>
+<Value index="125" val="0"></Value>
+<Value index="126" val="0"></Value>
+<Value index="127" val="0"></Value>
+<Value index="128" val="0"></Value>
+<Value index="129" val="0"></Value>
+<Value index="130" val="0"></Value>
+<Value index="131" val="0"></Value>
+<Value index="132" val="0"></Value>
+<Value index="133" val="0"></Value>
+<Value index="134" val="0"></Value>
+<Value index="135" val="0"></Value>
+<Value index="136" val="0"></Value>
+<Value index="137" val="0"></Value>
+<Value index="138" val="0"></Value>
+<Value index="139" val="0"></Value>
+<Value index="140" val="0"></Value>
+<Value index="141" val="0"></Value>
+<Value index="142" val="0"></Value>
+<Value index="143" val="0"></Value>
+<Value index="144" val="0"></Value>
+<Value index="145" val="0"></Value>
+<Value index="146" val="0"></Value>
+<Value index="147" val="0"></Value>
+<Value index="148" val="0"></Value>
+<Value index="149" val="0"></Value>
+<Value index="150" val="0"></Value>
+<Value index="151" val="0"></Value>
+<Value index="152" val="0"></Value>
+<Value index="153" val="0"></Value>
+<Value index="154" val="0"></Value>
+<Value index="155" val="0"></Value>
+<Value index="156" val="0"></Value>
+<Value index="157" val="0"></Value>
+<Value index="158" val="0"></Value>
+<Value index="159" val="0"></Value>
+<Value index="160" val="0"></Value>
+<Value index="161" val="0"></Value>
+<Value index="162" val="0"></Value>
+<Value index="163" val="0"></Value>
+<Value index="164" val="0"></Value>
+<Value index="165" val="0"></Value>
+<Value index="166" val="0"></Value>
+<Value index="167" val="0"></Value>
+<Value index="168" val="0"></Value>
+<Value index="169" val="0"></Value>
+<Value index="170" val="0"></Value>
+<Value index="171" val="0"></Value>
+<Value index="172" val="0"></Value>
+<Value index="173" val="0"></Value>
+<Value index="174" val="0"></Value>
+<Value index="175" val="0"></Value>
+<Value index="176" val="0"></Value>
+<Value index="177" val="0"></Value>
+<Value index="178" val="0"></Value>
+<Value index="179" val="0"></Value>
+<Value index="180" val="0"></Value>
+<Value index="181" val="0"></Value>
+<Value index="182" val="0"></Value>
+<Value index="183" val="0"></Value>
+<Value index="184" val="0"></Value>
+<Value index="185" val="0"></Value>
+<Value index="186" val="0"></Value>
+<Value index="187" val="0"></Value>
+<Value index="188" val="0"></Value>
+<Value index="189" val="0"></Value>
+<Value index="190" val="0"></Value>
+<Value index="191" val="0"></Value>
+<Value index="192" val="0"></Value>
+<Value index="193" val="0"></Value>
+<Value index="194" val="0"></Value>
+<Value index="195" val="0"></Value>
+<Value index="196" val="0"></Value>
+<Value index="197" val="0"></Value>
+<Value index="198" val="0"></Value>
+<Value index="199" val="0"></Value>
+<Value index="200" val="0"></Value>
+<Value index="201" val="0"></Value>
+<Value index="202" val="0"></Value>
+<Value index="203" val="0"></Value>
+<Value index="204" val="0"></Value>
+<Value index="205" val="0"></Value>
+<Value index="206" val="0"></Value>
+<Value index="207" val="0"></Value>
+<Value index="208" val="0"></Value>
+<Value index="209" val="0"></Value>
+<Value index="210" val="0"></Value>
+<Value index="211" val="0"></Value>
+<Value index="212" val="0"></Value>
+<Value index="213" val="0"></Value>
+<Value index="214" val="0"></Value>
+<Value index="215" val="0"></Value>
+<Value index="216" val="0"></Value>
+<Value index="217" val="0"></Value>
+<Value index="218" val="0"></Value>
+<Value index="219" val="0"></Value>
+<Value index="220" val="0"></Value>
+<Value index="221" val="0"></Value>
+<Value index="222" val="0"></Value>
+<Value index="223" val="0"></Value>
+<Value index="224" val="0"></Value>
+<Value index="225" val="0"></Value>
+<Value index="226" val="0"></Value>
+<Value index="227" val="0"></Value>
+<Value index="228" val="0"></Value>
+<Value index="229" val="0"></Value>
+<Value index="230" val="0"></Value>
+<Value index="231" val="0"></Value>
+<Value index="232" val="0"></Value>
+<Value index="233" val="0"></Value>
+<Value index="234" val="0"></Value>
+<Value index="235" val="0"></Value>
+<Value index="236" val="0"></Value>
+<Value index="237" val="0"></Value>
+<Value index="238" val="0"></Value>
+<Value index="239" val="0"></Value>
+<Value index="240" val="0"></Value>
+<Value index="241" val="0"></Value>
+<Value index="242" val="0"></Value>
+<Value index="243" val="0"></Value>
+<Value index="244" val="0"></Value>
+<Value index="245" val="0"></Value>
+<Value index="246" val="0"></Value>
+<Value index="247" val="0"></Value>
+<Value index="248" val="0"></Value>
+<Value index="249" val="0"></Value>
+<Value index="250" val="0"></Value>
+<Value index="251" val="0"></Value>
+<Value index="252" val="0"></Value>
+<Value index="253" val="0"></Value>
+<Value index="254" val="0"></Value>
+<Value index="255" val="0"></Value>
+</Property>
+<Property name="FileName" default="0" position="8" flags="7" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+</PropList>
+<PropList name="LUT-1" default="0" position="1" flags="7" size="10" parent="none">
+<Property name="Gamma" default="0" position="0" flags="7" size="1" formatString="%f" valType="2">
+<Value index="0" val="1.800000"></Value>
+</Property>
+<Property name="GammaAlpha" default="0" position="1" flags="7" size="1" formatString="%f" valType="2">
+<Value index="0" val="0.000000"></Value>
+</Property>
+<Property name="GammaMode" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="LinearStart"></Value>
+</Property>
+<Property name="GammaStartThreshold" default="0" position="3" flags="263" size="1" formatString="%d" valType="1">
+<Value index="0" val="12"></Value>
+</Property>
+<Property name="ValueCount" default="1" position="4" flags="259" size="1" formatString="%d" valType="1">
+<Value index="0" val="2"></Value>
+</Property>
+<Property name="InputValues" default="0" position="5" flags="263" size="2" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+<Value index="1" val="255"></Value>
+</Property>
+<Property name="OutputValues" default="0" position="6" flags="263" size="2" formatString="%d" valType="1">
+<Value index="0" val="255"></Value>
+<Value index="1" val="0"></Value>
+</Property>
+<Property name="DirectValues" default="0" position="7" flags="263" size="256" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+<Value index="1" val="0"></Value>
+<Value index="2" val="0"></Value>
+<Value index="3" val="0"></Value>
+<Value index="4" val="0"></Value>
+<Value index="5" val="0"></Value>
+<Value index="6" val="0"></Value>
+<Value index="7" val="0"></Value>
+<Value index="8" val="0"></Value>
+<Value index="9" val="0"></Value>
+<Value index="10" val="0"></Value>
+<Value index="11" val="0"></Value>
+<Value index="12" val="0"></Value>
+<Value index="13" val="0"></Value>
+<Value index="14" val="0"></Value>
+<Value index="15" val="0"></Value>
+<Value index="16" val="0"></Value>
+<Value index="17" val="0"></Value>
+<Value index="18" val="0"></Value>
+<Value index="19" val="0"></Value>
+<Value index="20" val="0"></Value>
+<Value index="21" val="0"></Value>
+<Value index="22" val="0"></Value>
+<Value index="23" val="0"></Value>
+<Value index="24" val="0"></Value>
+<Value index="25" val="0"></Value>
+<Value index="26" val="0"></Value>
+<Value index="27" val="0"></Value>
+<Value index="28" val="0"></Value>
+<Value index="29" val="0"></Value>
+<Value index="30" val="0"></Value>
+<Value index="31" val="0"></Value>
+<Value index="32" val="0"></Value>
+<Value index="33" val="0"></Value>
+<Value index="34" val="0"></Value>
+<Value index="35" val="0"></Value>
+<Value index="36" val="0"></Value>
+<Value index="37" val="0"></Value>
+<Value index="38" val="0"></Value>
+<Value index="39" val="0"></Value>
+<Value index="40" val="0"></Value>
+<Value index="41" val="0"></Value>
+<Value index="42" val="0"></Value>
+<Value index="43" val="0"></Value>
+<Value index="44" val="0"></Value>
+<Value index="45" val="0"></Value>
+<Value index="46" val="0"></Value>
+<Value index="47" val="0"></Value>
+<Value index="48" val="0"></Value>
+<Value index="49" val="0"></Value>
+<Value index="50" val="0"></Value>
+<Value index="51" val="0"></Value>
+<Value index="52" val="0"></Value>
+<Value index="53" val="0"></Value>
+<Value index="54" val="0"></Value>
+<Value index="55" val="0"></Value>
+<Value index="56" val="0"></Value>
+<Value index="57" val="0"></Value>
+<Value index="58" val="0"></Value>
+<Value index="59" val="0"></Value>
+<Value index="60" val="0"></Value>
+<Value index="61" val="0"></Value>
+<Value index="62" val="0"></Value>
+<Value index="63" val="0"></Value>
+<Value index="64" val="0"></Value>
+<Value index="65" val="0"></Value>
+<Value index="66" val="0"></Value>
+<Value index="67" val="0"></Value>
+<Value index="68" val="0"></Value>
+<Value index="69" val="0"></Value>
+<Value index="70" val="0"></Value>
+<Value index="71" val="0"></Value>
+<Value index="72" val="0"></Value>
+<Value index="73" val="0"></Value>
+<Value index="74" val="0"></Value>
+<Value index="75" val="0"></Value>
+<Value index="76" val="0"></Value>
+<Value index="77" val="0"></Value>
+<Value index="78" val="0"></Value>
+<Value index="79" val="0"></Value>
+<Value index="80" val="0"></Value>
+<Value index="81" val="0"></Value>
+<Value index="82" val="0"></Value>
+<Value index="83" val="0"></Value>
+<Value index="84" val="0"></Value>
+<Value index="85" val="0"></Value>
+<Value index="86" val="0"></Value>
+<Value index="87" val="0"></Value>
+<Value index="88" val="0"></Value>
+<Value index="89" val="0"></Value>
+<Value index="90" val="0"></Value>
+<Value index="91" val="0"></Value>
+<Value index="92" val="0"></Value>
+<Value index="93" val="0"></Value>
+<Value index="94" val="0"></Value>
+<Value index="95" val="0"></Value>
+<Value index="96" val="0"></Value>
+<Value index="97" val="0"></Value>
+<Value index="98" val="0"></Value>
+<Value index="99" val="0"></Value>
+<Value index="100" val="0"></Value>
+<Value index="101" val="0"></Value>
+<Value index="102" val="0"></Value>
+<Value index="103" val="0"></Value>
+<Value index="104" val="0"></Value>
+<Value index="105" val="0"></Value>
+<Value index="106" val="0"></Value>
+<Value index="107" val="0"></Value>
+<Value index="108" val="0"></Value>
+<Value index="109" val="0"></Value>
+<Value index="110" val="0"></Value>
+<Value index="111" val="0"></Value>
+<Value index="112" val="0"></Value>
+<Value index="113" val="0"></Value>
+<Value index="114" val="0"></Value>
+<Value index="115" val="0"></Value>
+<Value index="116" val="0"></Value>
+<Value index="117" val="0"></Value>
+<Value index="118" val="0"></Value>
+<Value index="119" val="0"></Value>
+<Value index="120" val="0"></Value>
+<Value index="121" val="0"></Value>
+<Value index="122" val="0"></Value>
+<Value index="123" val="0"></Value>
+<Value index="124" val="0"></Value>
+<Value index="125" val="0"></Value>
+<Value index="126" val="0"></Value>
+<Value index="127" val="0"></Value>
+<Value index="128" val="0"></Value>
+<Value index="129" val="0"></Value>
+<Value index="130" val="0"></Value>
+<Value index="131" val="0"></Value>
+<Value index="132" val="0"></Value>
+<Value index="133" val="0"></Value>
+<Value index="134" val="0"></Value>
+<Value index="135" val="0"></Value>
+<Value index="136" val="0"></Value>
+<Value index="137" val="0"></Value>
+<Value index="138" val="0"></Value>
+<Value index="139" val="0"></Value>
+<Value index="140" val="0"></Value>
+<Value index="141" val="0"></Value>
+<Value index="142" val="0"></Value>
+<Value index="143" val="0"></Value>
+<Value index="144" val="0"></Value>
+<Value index="145" val="0"></Value>
+<Value index="146" val="0"></Value>
+<Value index="147" val="0"></Value>
+<Value index="148" val="0"></Value>
+<Value index="149" val="0"></Value>
+<Value index="150" val="0"></Value>
+<Value index="151" val="0"></Value>
+<Value index="152" val="0"></Value>
+<Value index="153" val="0"></Value>
+<Value index="154" val="0"></Value>
+<Value index="155" val="0"></Value>
+<Value index="156" val="0"></Value>
+<Value index="157" val="0"></Value>
+<Value index="158" val="0"></Value>
+<Value index="159" val="0"></Value>
+<Value index="160" val="0"></Value>
+<Value index="161" val="0"></Value>
+<Value index="162" val="0"></Value>
+<Value index="163" val="0"></Value>
+<Value index="164" val="0"></Value>
+<Value index="165" val="0"></Value>
+<Value index="166" val="0"></Value>
+<Value index="167" val="0"></Value>
+<Value index="168" val="0"></Value>
+<Value index="169" val="0"></Value>
+<Value index="170" val="0"></Value>
+<Value index="171" val="0"></Value>
+<Value index="172" val="0"></Value>
+<Value index="173" val="0"></Value>
+<Value index="174" val="0"></Value>
+<Value index="175" val="0"></Value>
+<Value index="176" val="0"></Value>
+<Value index="177" val="0"></Value>
+<Value index="178" val="0"></Value>
+<Value index="179" val="0"></Value>
+<Value index="180" val="0"></Value>
+<Value index="181" val="0"></Value>
+<Value index="182" val="0"></Value>
+<Value index="183" val="0"></Value>
+<Value index="184" val="0"></Value>
+<Value index="185" val="0"></Value>
+<Value index="186" val="0"></Value>
+<Value index="187" val="0"></Value>
+<Value index="188" val="0"></Value>
+<Value index="189" val="0"></Value>
+<Value index="190" val="0"></Value>
+<Value index="191" val="0"></Value>
+<Value index="192" val="0"></Value>
+<Value index="193" val="0"></Value>
+<Value index="194" val="0"></Value>
+<Value index="195" val="0"></Value>
+<Value index="196" val="0"></Value>
+<Value index="197" val="0"></Value>
+<Value index="198" val="0"></Value>
+<Value index="199" val="0"></Value>
+<Value index="200" val="0"></Value>
+<Value index="201" val="0"></Value>
+<Value index="202" val="0"></Value>
+<Value index="203" val="0"></Value>
+<Value index="204" val="0"></Value>
+<Value index="205" val="0"></Value>
+<Value index="206" val="0"></Value>
+<Value index="207" val="0"></Value>
+<Value index="208" val="0"></Value>
+<Value index="209" val="0"></Value>
+<Value index="210" val="0"></Value>
+<Value index="211" val="0"></Value>
+<Value index="212" val="0"></Value>
+<Value index="213" val="0"></Value>
+<Value index="214" val="0"></Value>
+<Value index="215" val="0"></Value>
+<Value index="216" val="0"></Value>
+<Value index="217" val="0"></Value>
+<Value index="218" val="0"></Value>
+<Value index="219" val="0"></Value>
+<Value index="220" val="0"></Value>
+<Value index="221" val="0"></Value>
+<Value index="222" val="0"></Value>
+<Value index="223" val="0"></Value>
+<Value index="224" val="0"></Value>
+<Value index="225" val="0"></Value>
+<Value index="226" val="0"></Value>
+<Value index="227" val="0"></Value>
+<Value index="228" val="0"></Value>
+<Value index="229" val="0"></Value>
+<Value index="230" val="0"></Value>
+<Value index="231" val="0"></Value>
+<Value index="232" val="0"></Value>
+<Value index="233" val="0"></Value>
+<Value index="234" val="0"></Value>
+<Value index="235" val="0"></Value>
+<Value index="236" val="0"></Value>
+<Value index="237" val="0"></Value>
+<Value index="238" val="0"></Value>
+<Value index="239" val="0"></Value>
+<Value index="240" val="0"></Value>
+<Value index="241" val="0"></Value>
+<Value index="242" val="0"></Value>
+<Value index="243" val="0"></Value>
+<Value index="244" val="0"></Value>
+<Value index="245" val="0"></Value>
+<Value index="246" val="0"></Value>
+<Value index="247" val="0"></Value>
+<Value index="248" val="0"></Value>
+<Value index="249" val="0"></Value>
+<Value index="250" val="0"></Value>
+<Value index="251" val="0"></Value>
+<Value index="252" val="0"></Value>
+<Value index="253" val="0"></Value>
+<Value index="254" val="0"></Value>
+<Value index="255" val="0"></Value>
+</Property>
+<Property name="FileName" default="0" position="8" flags="7" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+</PropList>
+<PropList name="LUT-2" default="0" position="2" flags="7" size="10" parent="none">
+<Property name="Gamma" default="0" position="0" flags="7" size="1" formatString="%f" valType="2">
+<Value index="0" val="1.800000"></Value>
+</Property>
+<Property name="GammaAlpha" default="0" position="1" flags="7" size="1" formatString="%f" valType="2">
+<Value index="0" val="0.000000"></Value>
+</Property>
+<Property name="GammaMode" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="LinearStart"></Value>
+</Property>
+<Property name="GammaStartThreshold" default="0" position="3" flags="263" size="1" formatString="%d" valType="1">
+<Value index="0" val="12"></Value>
+</Property>
+<Property name="ValueCount" default="1" position="4" flags="259" size="1" formatString="%d" valType="1">
+<Value index="0" val="2"></Value>
+</Property>
+<Property name="InputValues" default="0" position="5" flags="263" size="2" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+<Value index="1" val="255"></Value>
+</Property>
+<Property name="OutputValues" default="0" position="6" flags="263" size="2" formatString="%d" valType="1">
+<Value index="0" val="255"></Value>
+<Value index="1" val="0"></Value>
+</Property>
+<Property name="DirectValues" default="0" position="7" flags="263" size="256" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+<Value index="1" val="0"></Value>
+<Value index="2" val="0"></Value>
+<Value index="3" val="0"></Value>
+<Value index="4" val="0"></Value>
+<Value index="5" val="0"></Value>
+<Value index="6" val="0"></Value>
+<Value index="7" val="0"></Value>
+<Value index="8" val="0"></Value>
+<Value index="9" val="0"></Value>
+<Value index="10" val="0"></Value>
+<Value index="11" val="0"></Value>
+<Value index="12" val="0"></Value>
+<Value index="13" val="0"></Value>
+<Value index="14" val="0"></Value>
+<Value index="15" val="0"></Value>
+<Value index="16" val="0"></Value>
+<Value index="17" val="0"></Value>
+<Value index="18" val="0"></Value>
+<Value index="19" val="0"></Value>
+<Value index="20" val="0"></Value>
+<Value index="21" val="0"></Value>
+<Value index="22" val="0"></Value>
+<Value index="23" val="0"></Value>
+<Value index="24" val="0"></Value>
+<Value index="25" val="0"></Value>
+<Value index="26" val="0"></Value>
+<Value index="27" val="0"></Value>
+<Value index="28" val="0"></Value>
+<Value index="29" val="0"></Value>
+<Value index="30" val="0"></Value>
+<Value index="31" val="0"></Value>
+<Value index="32" val="0"></Value>
+<Value index="33" val="0"></Value>
+<Value index="34" val="0"></Value>
+<Value index="35" val="0"></Value>
+<Value index="36" val="0"></Value>
+<Value index="37" val="0"></Value>
+<Value index="38" val="0"></Value>
+<Value index="39" val="0"></Value>
+<Value index="40" val="0"></Value>
+<Value index="41" val="0"></Value>
+<Value index="42" val="0"></Value>
+<Value index="43" val="0"></Value>
+<Value index="44" val="0"></Value>
+<Value index="45" val="0"></Value>
+<Value index="46" val="0"></Value>
+<Value index="47" val="0"></Value>
+<Value index="48" val="0"></Value>
+<Value index="49" val="0"></Value>
+<Value index="50" val="0"></Value>
+<Value index="51" val="0"></Value>
+<Value index="52" val="0"></Value>
+<Value index="53" val="0"></Value>
+<Value index="54" val="0"></Value>
+<Value index="55" val="0"></Value>
+<Value index="56" val="0"></Value>
+<Value index="57" val="0"></Value>
+<Value index="58" val="0"></Value>
+<Value index="59" val="0"></Value>
+<Value index="60" val="0"></Value>
+<Value index="61" val="0"></Value>
+<Value index="62" val="0"></Value>
+<Value index="63" val="0"></Value>
+<Value index="64" val="0"></Value>
+<Value index="65" val="0"></Value>
+<Value index="66" val="0"></Value>
+<Value index="67" val="0"></Value>
+<Value index="68" val="0"></Value>
+<Value index="69" val="0"></Value>
+<Value index="70" val="0"></Value>
+<Value index="71" val="0"></Value>
+<Value index="72" val="0"></Value>
+<Value index="73" val="0"></Value>
+<Value index="74" val="0"></Value>
+<Value index="75" val="0"></Value>
+<Value index="76" val="0"></Value>
+<Value index="77" val="0"></Value>
+<Value index="78" val="0"></Value>
+<Value index="79" val="0"></Value>
+<Value index="80" val="0"></Value>
+<Value index="81" val="0"></Value>
+<Value index="82" val="0"></Value>
+<Value index="83" val="0"></Value>
+<Value index="84" val="0"></Value>
+<Value index="85" val="0"></Value>
+<Value index="86" val="0"></Value>
+<Value index="87" val="0"></Value>
+<Value index="88" val="0"></Value>
+<Value index="89" val="0"></Value>
+<Value index="90" val="0"></Value>
+<Value index="91" val="0"></Value>
+<Value index="92" val="0"></Value>
+<Value index="93" val="0"></Value>
+<Value index="94" val="0"></Value>
+<Value index="95" val="0"></Value>
+<Value index="96" val="0"></Value>
+<Value index="97" val="0"></Value>
+<Value index="98" val="0"></Value>
+<Value index="99" val="0"></Value>
+<Value index="100" val="0"></Value>
+<Value index="101" val="0"></Value>
+<Value index="102" val="0"></Value>
+<Value index="103" val="0"></Value>
+<Value index="104" val="0"></Value>
+<Value index="105" val="0"></Value>
+<Value index="106" val="0"></Value>
+<Value index="107" val="0"></Value>
+<Value index="108" val="0"></Value>
+<Value index="109" val="0"></Value>
+<Value index="110" val="0"></Value>
+<Value index="111" val="0"></Value>
+<Value index="112" val="0"></Value>
+<Value index="113" val="0"></Value>
+<Value index="114" val="0"></Value>
+<Value index="115" val="0"></Value>
+<Value index="116" val="0"></Value>
+<Value index="117" val="0"></Value>
+<Value index="118" val="0"></Value>
+<Value index="119" val="0"></Value>
+<Value index="120" val="0"></Value>
+<Value index="121" val="0"></Value>
+<Value index="122" val="0"></Value>
+<Value index="123" val="0"></Value>
+<Value index="124" val="0"></Value>
+<Value index="125" val="0"></Value>
+<Value index="126" val="0"></Value>
+<Value index="127" val="0"></Value>
+<Value index="128" val="0"></Value>
+<Value index="129" val="0"></Value>
+<Value index="130" val="0"></Value>
+<Value index="131" val="0"></Value>
+<Value index="132" val="0"></Value>
+<Value index="133" val="0"></Value>
+<Value index="134" val="0"></Value>
+<Value index="135" val="0"></Value>
+<Value index="136" val="0"></Value>
+<Value index="137" val="0"></Value>
+<Value index="138" val="0"></Value>
+<Value index="139" val="0"></Value>
+<Value index="140" val="0"></Value>
+<Value index="141" val="0"></Value>
+<Value index="142" val="0"></Value>
+<Value index="143" val="0"></Value>
+<Value index="144" val="0"></Value>
+<Value index="145" val="0"></Value>
+<Value index="146" val="0"></Value>
+<Value index="147" val="0"></Value>
+<Value index="148" val="0"></Value>
+<Value index="149" val="0"></Value>
+<Value index="150" val="0"></Value>
+<Value index="151" val="0"></Value>
+<Value index="152" val="0"></Value>
+<Value index="153" val="0"></Value>
+<Value index="154" val="0"></Value>
+<Value index="155" val="0"></Value>
+<Value index="156" val="0"></Value>
+<Value index="157" val="0"></Value>
+<Value index="158" val="0"></Value>
+<Value index="159" val="0"></Value>
+<Value index="160" val="0"></Value>
+<Value index="161" val="0"></Value>
+<Value index="162" val="0"></Value>
+<Value index="163" val="0"></Value>
+<Value index="164" val="0"></Value>
+<Value index="165" val="0"></Value>
+<Value index="166" val="0"></Value>
+<Value index="167" val="0"></Value>
+<Value index="168" val="0"></Value>
+<Value index="169" val="0"></Value>
+<Value index="170" val="0"></Value>
+<Value index="171" val="0"></Value>
+<Value index="172" val="0"></Value>
+<Value index="173" val="0"></Value>
+<Value index="174" val="0"></Value>
+<Value index="175" val="0"></Value>
+<Value index="176" val="0"></Value>
+<Value index="177" val="0"></Value>
+<Value index="178" val="0"></Value>
+<Value index="179" val="0"></Value>
+<Value index="180" val="0"></Value>
+<Value index="181" val="0"></Value>
+<Value index="182" val="0"></Value>
+<Value index="183" val="0"></Value>
+<Value index="184" val="0"></Value>
+<Value index="185" val="0"></Value>
+<Value index="186" val="0"></Value>
+<Value index="187" val="0"></Value>
+<Value index="188" val="0"></Value>
+<Value index="189" val="0"></Value>
+<Value index="190" val="0"></Value>
+<Value index="191" val="0"></Value>
+<Value index="192" val="0"></Value>
+<Value index="193" val="0"></Value>
+<Value index="194" val="0"></Value>
+<Value index="195" val="0"></Value>
+<Value index="196" val="0"></Value>
+<Value index="197" val="0"></Value>
+<Value index="198" val="0"></Value>
+<Value index="199" val="0"></Value>
+<Value index="200" val="0"></Value>
+<Value index="201" val="0"></Value>
+<Value index="202" val="0"></Value>
+<Value index="203" val="0"></Value>
+<Value index="204" val="0"></Value>
+<Value index="205" val="0"></Value>
+<Value index="206" val="0"></Value>
+<Value index="207" val="0"></Value>
+<Value index="208" val="0"></Value>
+<Value index="209" val="0"></Value>
+<Value index="210" val="0"></Value>
+<Value index="211" val="0"></Value>
+<Value index="212" val="0"></Value>
+<Value index="213" val="0"></Value>
+<Value index="214" val="0"></Value>
+<Value index="215" val="0"></Value>
+<Value index="216" val="0"></Value>
+<Value index="217" val="0"></Value>
+<Value index="218" val="0"></Value>
+<Value index="219" val="0"></Value>
+<Value index="220" val="0"></Value>
+<Value index="221" val="0"></Value>
+<Value index="222" val="0"></Value>
+<Value index="223" val="0"></Value>
+<Value index="224" val="0"></Value>
+<Value index="225" val="0"></Value>
+<Value index="226" val="0"></Value>
+<Value index="227" val="0"></Value>
+<Value index="228" val="0"></Value>
+<Value index="229" val="0"></Value>
+<Value index="230" val="0"></Value>
+<Value index="231" val="0"></Value>
+<Value index="232" val="0"></Value>
+<Value index="233" val="0"></Value>
+<Value index="234" val="0"></Value>
+<Value index="235" val="0"></Value>
+<Value index="236" val="0"></Value>
+<Value index="237" val="0"></Value>
+<Value index="238" val="0"></Value>
+<Value index="239" val="0"></Value>
+<Value index="240" val="0"></Value>
+<Value index="241" val="0"></Value>
+<Value index="242" val="0"></Value>
+<Value index="243" val="0"></Value>
+<Value index="244" val="0"></Value>
+<Value index="245" val="0"></Value>
+<Value index="246" val="0"></Value>
+<Value index="247" val="0"></Value>
+<Value index="248" val="0"></Value>
+<Value index="249" val="0"></Value>
+<Value index="250" val="0"></Value>
+<Value index="251" val="0"></Value>
+<Value index="252" val="0"></Value>
+<Value index="253" val="0"></Value>
+<Value index="254" val="0"></Value>
+<Value index="255" val="0"></Value>
+</Property>
+<Property name="FileName" default="0" position="8" flags="7" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+</PropList>
+<PropList name="LUT-3" default="0" position="3" flags="7" size="10" parent="none">
+<Property name="Gamma" default="0" position="0" flags="7" size="1" formatString="%f" valType="2">
+<Value index="0" val="1.800000"></Value>
+</Property>
+<Property name="GammaAlpha" default="0" position="1" flags="7" size="1" formatString="%f" valType="2">
+<Value index="0" val="0.000000"></Value>
+</Property>
+<Property name="GammaMode" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="LinearStart"></Value>
+</Property>
+<Property name="GammaStartThreshold" default="0" position="3" flags="263" size="1" formatString="%d" valType="1">
+<Value index="0" val="12"></Value>
+</Property>
+<Property name="ValueCount" default="1" position="4" flags="259" size="1" formatString="%d" valType="1">
+<Value index="0" val="2"></Value>
+</Property>
+<Property name="InputValues" default="0" position="5" flags="263" size="2" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+<Value index="1" val="255"></Value>
+</Property>
+<Property name="OutputValues" default="0" position="6" flags="263" size="2" formatString="%d" valType="1">
+<Value index="0" val="255"></Value>
+<Value index="1" val="0"></Value>
+</Property>
+<Property name="DirectValues" default="0" position="7" flags="263" size="256" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+<Value index="1" val="0"></Value>
+<Value index="2" val="0"></Value>
+<Value index="3" val="0"></Value>
+<Value index="4" val="0"></Value>
+<Value index="5" val="0"></Value>
+<Value index="6" val="0"></Value>
+<Value index="7" val="0"></Value>
+<Value index="8" val="0"></Value>
+<Value index="9" val="0"></Value>
+<Value index="10" val="0"></Value>
+<Value index="11" val="0"></Value>
+<Value index="12" val="0"></Value>
+<Value index="13" val="0"></Value>
+<Value index="14" val="0"></Value>
+<Value index="15" val="0"></Value>
+<Value index="16" val="0"></Value>
+<Value index="17" val="0"></Value>
+<Value index="18" val="0"></Value>
+<Value index="19" val="0"></Value>
+<Value index="20" val="0"></Value>
+<Value index="21" val="0"></Value>
+<Value index="22" val="0"></Value>
+<Value index="23" val="0"></Value>
+<Value index="24" val="0"></Value>
+<Value index="25" val="0"></Value>
+<Value index="26" val="0"></Value>
+<Value index="27" val="0"></Value>
+<Value index="28" val="0"></Value>
+<Value index="29" val="0"></Value>
+<Value index="30" val="0"></Value>
+<Value index="31" val="0"></Value>
+<Value index="32" val="0"></Value>
+<Value index="33" val="0"></Value>
+<Value index="34" val="0"></Value>
+<Value index="35" val="0"></Value>
+<Value index="36" val="0"></Value>
+<Value index="37" val="0"></Value>
+<Value index="38" val="0"></Value>
+<Value index="39" val="0"></Value>
+<Value index="40" val="0"></Value>
+<Value index="41" val="0"></Value>
+<Value index="42" val="0"></Value>
+<Value index="43" val="0"></Value>
+<Value index="44" val="0"></Value>
+<Value index="45" val="0"></Value>
+<Value index="46" val="0"></Value>
+<Value index="47" val="0"></Value>
+<Value index="48" val="0"></Value>
+<Value index="49" val="0"></Value>
+<Value index="50" val="0"></Value>
+<Value index="51" val="0"></Value>
+<Value index="52" val="0"></Value>
+<Value index="53" val="0"></Value>
+<Value index="54" val="0"></Value>
+<Value index="55" val="0"></Value>
+<Value index="56" val="0"></Value>
+<Value index="57" val="0"></Value>
+<Value index="58" val="0"></Value>
+<Value index="59" val="0"></Value>
+<Value index="60" val="0"></Value>
+<Value index="61" val="0"></Value>
+<Value index="62" val="0"></Value>
+<Value index="63" val="0"></Value>
+<Value index="64" val="0"></Value>
+<Value index="65" val="0"></Value>
+<Value index="66" val="0"></Value>
+<Value index="67" val="0"></Value>
+<Value index="68" val="0"></Value>
+<Value index="69" val="0"></Value>
+<Value index="70" val="0"></Value>
+<Value index="71" val="0"></Value>
+<Value index="72" val="0"></Value>
+<Value index="73" val="0"></Value>
+<Value index="74" val="0"></Value>
+<Value index="75" val="0"></Value>
+<Value index="76" val="0"></Value>
+<Value index="77" val="0"></Value>
+<Value index="78" val="0"></Value>
+<Value index="79" val="0"></Value>
+<Value index="80" val="0"></Value>
+<Value index="81" val="0"></Value>
+<Value index="82" val="0"></Value>
+<Value index="83" val="0"></Value>
+<Value index="84" val="0"></Value>
+<Value index="85" val="0"></Value>
+<Value index="86" val="0"></Value>
+<Value index="87" val="0"></Value>
+<Value index="88" val="0"></Value>
+<Value index="89" val="0"></Value>
+<Value index="90" val="0"></Value>
+<Value index="91" val="0"></Value>
+<Value index="92" val="0"></Value>
+<Value index="93" val="0"></Value>
+<Value index="94" val="0"></Value>
+<Value index="95" val="0"></Value>
+<Value index="96" val="0"></Value>
+<Value index="97" val="0"></Value>
+<Value index="98" val="0"></Value>
+<Value index="99" val="0"></Value>
+<Value index="100" val="0"></Value>
+<Value index="101" val="0"></Value>
+<Value index="102" val="0"></Value>
+<Value index="103" val="0"></Value>
+<Value index="104" val="0"></Value>
+<Value index="105" val="0"></Value>
+<Value index="106" val="0"></Value>
+<Value index="107" val="0"></Value>
+<Value index="108" val="0"></Value>
+<Value index="109" val="0"></Value>
+<Value index="110" val="0"></Value>
+<Value index="111" val="0"></Value>
+<Value index="112" val="0"></Value>
+<Value index="113" val="0"></Value>
+<Value index="114" val="0"></Value>
+<Value index="115" val="0"></Value>
+<Value index="116" val="0"></Value>
+<Value index="117" val="0"></Value>
+<Value index="118" val="0"></Value>
+<Value index="119" val="0"></Value>
+<Value index="120" val="0"></Value>
+<Value index="121" val="0"></Value>
+<Value index="122" val="0"></Value>
+<Value index="123" val="0"></Value>
+<Value index="124" val="0"></Value>
+<Value index="125" val="0"></Value>
+<Value index="126" val="0"></Value>
+<Value index="127" val="0"></Value>
+<Value index="128" val="0"></Value>
+<Value index="129" val="0"></Value>
+<Value index="130" val="0"></Value>
+<Value index="131" val="0"></Value>
+<Value index="132" val="0"></Value>
+<Value index="133" val="0"></Value>
+<Value index="134" val="0"></Value>
+<Value index="135" val="0"></Value>
+<Value index="136" val="0"></Value>
+<Value index="137" val="0"></Value>
+<Value index="138" val="0"></Value>
+<Value index="139" val="0"></Value>
+<Value index="140" val="0"></Value>
+<Value index="141" val="0"></Value>
+<Value index="142" val="0"></Value>
+<Value index="143" val="0"></Value>
+<Value index="144" val="0"></Value>
+<Value index="145" val="0"></Value>
+<Value index="146" val="0"></Value>
+<Value index="147" val="0"></Value>
+<Value index="148" val="0"></Value>
+<Value index="149" val="0"></Value>
+<Value index="150" val="0"></Value>
+<Value index="151" val="0"></Value>
+<Value index="152" val="0"></Value>
+<Value index="153" val="0"></Value>
+<Value index="154" val="0"></Value>
+<Value index="155" val="0"></Value>
+<Value index="156" val="0"></Value>
+<Value index="157" val="0"></Value>
+<Value index="158" val="0"></Value>
+<Value index="159" val="0"></Value>
+<Value index="160" val="0"></Value>
+<Value index="161" val="0"></Value>
+<Value index="162" val="0"></Value>
+<Value index="163" val="0"></Value>
+<Value index="164" val="0"></Value>
+<Value index="165" val="0"></Value>
+<Value index="166" val="0"></Value>
+<Value index="167" val="0"></Value>
+<Value index="168" val="0"></Value>
+<Value index="169" val="0"></Value>
+<Value index="170" val="0"></Value>
+<Value index="171" val="0"></Value>
+<Value index="172" val="0"></Value>
+<Value index="173" val="0"></Value>
+<Value index="174" val="0"></Value>
+<Value index="175" val="0"></Value>
+<Value index="176" val="0"></Value>
+<Value index="177" val="0"></Value>
+<Value index="178" val="0"></Value>
+<Value index="179" val="0"></Value>
+<Value index="180" val="0"></Value>
+<Value index="181" val="0"></Value>
+<Value index="182" val="0"></Value>
+<Value index="183" val="0"></Value>
+<Value index="184" val="0"></Value>
+<Value index="185" val="0"></Value>
+<Value index="186" val="0"></Value>
+<Value index="187" val="0"></Value>
+<Value index="188" val="0"></Value>
+<Value index="189" val="0"></Value>
+<Value index="190" val="0"></Value>
+<Value index="191" val="0"></Value>
+<Value index="192" val="0"></Value>
+<Value index="193" val="0"></Value>
+<Value index="194" val="0"></Value>
+<Value index="195" val="0"></Value>
+<Value index="196" val="0"></Value>
+<Value index="197" val="0"></Value>
+<Value index="198" val="0"></Value>
+<Value index="199" val="0"></Value>
+<Value index="200" val="0"></Value>
+<Value index="201" val="0"></Value>
+<Value index="202" val="0"></Value>
+<Value index="203" val="0"></Value>
+<Value index="204" val="0"></Value>
+<Value index="205" val="0"></Value>
+<Value index="206" val="0"></Value>
+<Value index="207" val="0"></Value>
+<Value index="208" val="0"></Value>
+<Value index="209" val="0"></Value>
+<Value index="210" val="0"></Value>
+<Value index="211" val="0"></Value>
+<Value index="212" val="0"></Value>
+<Value index="213" val="0"></Value>
+<Value index="214" val="0"></Value>
+<Value index="215" val="0"></Value>
+<Value index="216" val="0"></Value>
+<Value index="217" val="0"></Value>
+<Value index="218" val="0"></Value>
+<Value index="219" val="0"></Value>
+<Value index="220" val="0"></Value>
+<Value index="221" val="0"></Value>
+<Value index="222" val="0"></Value>
+<Value index="223" val="0"></Value>
+<Value index="224" val="0"></Value>
+<Value index="225" val="0"></Value>
+<Value index="226" val="0"></Value>
+<Value index="227" val="0"></Value>
+<Value index="228" val="0"></Value>
+<Value index="229" val="0"></Value>
+<Value index="230" val="0"></Value>
+<Value index="231" val="0"></Value>
+<Value index="232" val="0"></Value>
+<Value index="233" val="0"></Value>
+<Value index="234" val="0"></Value>
+<Value index="235" val="0"></Value>
+<Value index="236" val="0"></Value>
+<Value index="237" val="0"></Value>
+<Value index="238" val="0"></Value>
+<Value index="239" val="0"></Value>
+<Value index="240" val="0"></Value>
+<Value index="241" val="0"></Value>
+<Value index="242" val="0"></Value>
+<Value index="243" val="0"></Value>
+<Value index="244" val="0"></Value>
+<Value index="245" val="0"></Value>
+<Value index="246" val="0"></Value>
+<Value index="247" val="0"></Value>
+<Value index="248" val="0"></Value>
+<Value index="249" val="0"></Value>
+<Value index="250" val="0"></Value>
+<Value index="251" val="0"></Value>
+<Value index="252" val="0"></Value>
+<Value index="253" val="0"></Value>
+<Value index="254" val="0"></Value>
+<Value index="255" val="0"></Value>
+</Property>
+<Property name="FileName" default="0" position="8" flags="7" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+</PropList>
+</PropList>
+</PropList>
+<PropList name="ChannelSplit" default="0" position="21" flags="3" size="4" parent="none">
+<Property name="ChannelSplitEnable" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="ChannelSplitMode" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Vertical"></Value>
+</Property>
+<Property name="ChannelSplitChannelIndex" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+</Property>
+<Property name="ChannelSplitDeinterlaceEnable" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+</PropList>
+<PropList name="WatermarkGenerator" default="0" position="22" flags="3" size="9" parent="none">
+<Property name="WatermarkEnable" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="WatermarkLayout" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Cross-hair"></Value>
+</Property>
+<Property name="WatermarkPositionMode" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Centered"></Value>
+</Property>
+<Property name="WatermarkPositionUserX" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+</Property>
+<Property name="WatermarkPositionUserY" default="0" position="4" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+</Property>
+<Property name="WatermarkColorMode" default="0" position="5" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Standard"></Value>
+</Property>
+<Property name="WatermarkColorUser" default="0" position="6" flags="7" size="4" formatString="0x%04x" valType="1">
+<Value index="0" val="0x0000"></Value>
+<Value index="1" val="0x0000"></Value>
+<Value index="2" val="0x0000"></Value>
+<Value index="3" val="0x0000"></Value>
+</Property>
+<Property name="WatermarkThicknessMode" default="0" position="7" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Standard"></Value>
+</Property>
+<Property name="WatermarkThicknessUser" default="0" position="8" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="1"></Value>
+</Property>
+</PropList>
+<PropList name="Rotation" default="0" position="23" flags="3" size="2" parent="none">
+<Property name="RotationEnable" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="RotationAngle" default="0" position="1" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="90.000"></Value>
+</Property>
+</PropList>
+</PropList>
+<PropList name="ImageDestination" default="0" position="4" flags="3" size="5" parent="none">
+<Property name="PixelFormat" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Auto"></Value>
+</Property>
+<Property name="ScalerMode" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="ScalerInterpolationMode" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="NearestNeighbor"></Value>
+</Property>
+<Property name="ImageWidth" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="640"></Value>
+</Property>
+<Property name="ImageHeight" default="0" position="4" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="480"></Value>
+</Property>
+</PropList>
+<PropList name="RequestInfo" default="0" position="5" flags="3" size="9" parent="none">
+<Property name="FrameID" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="ExposeStart_us" default="0" position="4" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="ExposeTime_us" default="0" position="5" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="Gain_dB" default="0" position="6" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="VideoChannel" default="0" position="7" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="MissingData_pc" default="0" position="8" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+</PropList>
+</PropList>
+</PropList>
+<PropList name="DeviceSpecificData" default="0" position="4" flags="3" size="3" parent="none">
+<Property name="DefectiveFilterParameter" default="0" position="0" flags="2055" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+<Property name="FlatFieldFilterParameter" default="0" position="1" flags="2055" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+<Property name="DarkCurrentFilterParameter" default="0" position="2" flags="2055" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+</PropList>
+</PropList>
+<PropList name="System" default="0" position="5" flags="3" size="12" parent="none">
+<Property name="WorkerPriority" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="TimeCritical"></Value>
+</Property>
+<Property name="RequestCount" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="10"></Value>
+</Property>
+<PropList name="MemoryInit" default="0" position="2" flags="3" size="6" parent="none">
+<Property name="MemoryInitEnable" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="MemoryInitMode" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="FixedValue"></Value>
+</Property>
+<Property name="MemoryInitValue" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+</Property>
+<Property name="MemoryInitPattern" default="0" position="3" flags="2055" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+<Property name="MemoryInitPatternFileName" default="0" position="4" flags="2055" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+</PropList>
+<PropList name="ImageProcessingControl" default="0" position="3" flags="3" size="1" parent="none">
+<Property name="ImageProcessingOptimization" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="MinimizeMemoryUsage"></Value>
+</Property>
+</PropList>
+<Property name="FeaturePollingEnable" default="0" position="6" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="On"></Value>
+</Property>
+<Property name="FeaturePollingInterval_ms" default="0" position="7" flags="7" size="1" formatString="%d ms" valType="1">
+<Value index="0" val="200 ms"></Value>
+</Property>
+<Property name="MethodPollingInterval_ms" default="0" position="8" flags="7" size="1" formatString="%d ms" valType="1">
+<Value index="0" val="100 ms"></Value>
+</Property>
+<Property name="MethodPollingMaxRetryCount" default="0" position="9" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="5"></Value>
+</Property>
+<Property name="AcquisitionIdleTimeMax_ms" default="0" position="10" flags="7" size="1" formatString="%d ms" valType="1">
+<Value index="0" val="150 ms"></Value>
+</Property>
+</PropList>
+</PropList>
diff --git a/params/F0300141_calib.yaml b/params/F0300141_calib.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..78d36d6720e500783cbf84887b7f017c994ef885
--- /dev/null
+++ b/params/F0300141_calib.yaml
@@ -0,0 +1,20 @@
+image_width: 1280
+image_height: 960
+camera_name: camera
+camera_matrix:
+  rows: 3
+  cols: 3
+  data: [983.3368247116101, 0.0, 663.0390171499093, 0.0, 981.4430850536788, 396.26629958482715, 0.0, 0.0, 1.0]
+distortion_model: plumb_bob
+distortion_coefficients:
+  rows: 1
+  cols: 5
+  data: [-0.1107801575668356, 0.1031381384744468, -0.0020878830811691044, -0.002987672654714989, 0.0]
+rectification_matrix:
+  rows: 3
+  cols: 3
+  data: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
+projection_matrix:
+  rows: 3
+  cols: 4
+  data: [958.0409545898438, 0.0, 656.8482799260782, 0.0, 0.0, 961.90283203125, 393.4869532290468, 0.0, 0.0, 0.0, 1.0, 0.0]
diff --git a/params/F0300141_params.xml b/params/F0300141_params.xml
new file mode 100644
index 0000000000000000000000000000000000000000..c8f8f0d8f4477db96aa087371fdd311a5e5f1a6d
--- /dev/null
+++ b/params/F0300141_params.xml
@@ -0,0 +1,2061 @@
+<?xml version="1.0" encoding="UTF-8" standalone="yes"?>
+<PropList contentDescriptor="mvBlueFOX3-M1012bC data(interface layout: GenICam)" name="DriverData" default="0" flags="3" size="7" parent="none" versionMajor="2" versionMinor="18" versionRelease="0">
+<PropList name="ImagingSubsystem" default="0" position="0" flags="3" size="5" parent="none">
+<PropList name="Setting" default="0" position="0" flags="3" size="1" parent="none">
+<PropList name="Base" default="0" position="0" flags="3" size="6" parent="none">
+<PropList name="Camera" default="0" position="1" flags="3" size="3" parent="none">
+<Property name="GenICamFeatureBag_91473E04-B76B-422d-8F52-A5D5A768C984" default="0" position="0" flags="7" size="1" formatString="%s" valType="4">
+<Value index="0"># {05D8C294-F295-4dfb-9D01-096BD04049F4}
+# GenApi persistence file (version 3.0.0)
+# Device = MATRIX_VISION::mvBlueFOX3 -- MATRIX VISION USB3Vision camera interface -- Device version = 53.0.0 -- Product GUID = 8A5441D1-A059-11E6-A17E-E9D83A4B713F -- Product version GUID = 8A5468E1-A059-11E6-8532-E9D83A4B713F
+DeviceClockSelector	Sensor
+mvDeviceClockFrequency	kHz_66000
+DeviceClockSelector	Sensor
+DeviceScanType	Areascan
+mvDeviceProcessingUnitSelector	0
+mvDeviceProcessingUnit	mvFrameAverage
+mvDeviceProcessingUnitSelector	0
+DeviceLinkSelector	0
+DeviceLinkThroughputLimitMode	Off
+DeviceLinkSelector	0
+Width	1280
+Height	960
+OffsetX	0
+OffsetY	0
+PixelFormat	BayerGR8
+TestPattern	Off
+BinningHorizontal	1
+DecimationHorizontal	1
+DecimationVertical	1
+ReverseX	0
+ReverseY	0
+AcquisitionMode	Continuous
+ExposureMode	Timed
+ExposureTime	23399
+ExposureAuto	Continuous
+mvExposureAutoLowerLimit	74
+mvExposureAutoUpperLimit	23399
+mvExposureAutoAverageGrey	50
+mvExposureAutoHighlightAOI	Off
+mvExposureAutoAOIMode	mvFull
+mvExposureAutoMode	mvDevice
+TriggerSelector	FrameStart
+TriggerMode	Off
+TriggerSelector	AcquisitionStart
+TriggerMode	Off
+TriggerSelector	AcquisitionEnd
+TriggerMode	Off
+TriggerSelector	AcquisitionActive
+TriggerMode	Off
+TriggerSelector	mvTimestampReset
+TriggerMode	Off
+TriggerSelector	FrameBurstStart
+TriggerMode	Off
+TriggerSelector	FrameBurstActive
+TriggerMode	Off
+TriggerSelector	FrameStart
+TriggerSelector	FrameStart
+TriggerSource	Line4
+TriggerSelector	AcquisitionStart
+TriggerSource	Line4
+TriggerSelector	AcquisitionEnd
+TriggerSource	Line4
+TriggerSelector	AcquisitionActive
+TriggerSource	Line4
+TriggerSelector	mvTimestampReset
+TriggerSource	Line4
+TriggerSelector	FrameBurstStart
+TriggerSource	Line4
+TriggerSelector	FrameBurstActive
+TriggerSource	Line4
+TriggerSelector	FrameStart
+TriggerSelector	FrameStart
+TriggerActivation	RisingEdge
+TriggerSelector	AcquisitionStart
+TriggerActivation	RisingEdge
+TriggerSelector	AcquisitionEnd
+TriggerActivation	RisingEdge
+TriggerSelector	AcquisitionActive
+TriggerActivation	LevelHigh
+TriggerSelector	mvTimestampReset
+TriggerActivation	RisingEdge
+TriggerSelector	FrameBurstStart
+TriggerActivation	RisingEdge
+TriggerSelector	FrameBurstActive
+TriggerActivation	LevelHigh
+TriggerSelector	FrameStart
+TriggerSelector	FrameStart
+TriggerDelay	0
+TriggerSelector	AcquisitionStart
+TriggerDelay	0
+TriggerSelector	AcquisitionEnd
+TriggerDelay	0
+TriggerSelector	AcquisitionActive
+TriggerDelay	0
+TriggerSelector	mvTimestampReset
+TriggerDelay	0
+TriggerSelector	FrameBurstStart
+TriggerDelay	0
+TriggerSelector	FrameBurstActive
+TriggerDelay	0
+TriggerSelector	FrameStart
+mvAcquisitionFrameRateLimitMode	mvDeviceLinkThroughput
+AcquisitionFrameRateEnable	1
+mvAcquisitionFrameRateEnable	On
+AcquisitionFrameRate	25.3
+AcquisitionFrameCount	1
+mvAcquisitionMemoryMode	Default
+CounterSelector	Counter1
+CounterEventSource	Off
+CounterSelector	Counter2
+CounterEventSource	Off
+CounterSelector	Counter3
+CounterEventSource	Off
+CounterSelector	Counter4
+CounterEventSource	Off
+CounterSelector	Counter1
+CounterSelector	Counter1
+CounterResetSource	Off
+CounterSelector	Counter2
+CounterResetSource	Off
+CounterSelector	Counter3
+CounterResetSource	Off
+CounterSelector	Counter4
+CounterResetSource	Off
+CounterSelector	Counter1
+CounterSelector	Counter1
+CounterTriggerSource	Off
+CounterSelector	Counter2
+CounterTriggerSource	Off
+CounterSelector	Counter3
+CounterTriggerSource	Off
+CounterSelector	Counter4
+CounterTriggerSource	Off
+CounterSelector	Counter1
+CounterSelector	Counter1
+CounterDuration	10000
+CounterSelector	Counter2
+CounterDuration	10000
+CounterSelector	Counter3
+CounterDuration	10000
+CounterSelector	Counter4
+CounterDuration	10000
+CounterSelector	Counter1
+CounterSelector	Counter1
+CounterValue	0
+CounterSelector	Counter2
+CounterValue	0
+CounterSelector	Counter3
+CounterValue	0
+CounterSelector	Counter4
+CounterValue	0
+CounterSelector	Counter1
+TimerSelector	Timer1
+TimerTriggerSource	Timer1End
+TimerSelector	Timer2
+TimerTriggerSource	Timer2End
+TimerSelector	Timer1
+TimerSelector	Timer1
+TimerDuration	20000
+TimerSelector	Timer2
+TimerDuration	20000
+TimerSelector	Timer1
+TimerSelector	Timer1
+TimerDelay	0
+TimerSelector	Timer2
+TimerDelay	0
+TimerSelector	Timer1
+TimerSelector	Timer1
+TimerValue	17376
+TimerSelector	Timer2
+TimerValue	15776
+TimerSelector	Timer1
+GainSelector	AnalogAll
+Gain	6.209
+GainSelector	DigitalAll
+Gain	0
+GainSelector	AnalogAll
+GainSelector	AnalogAll
+GainAuto	Continuous
+GainSelector	AnalogAll
+GainSelector	AnalogAll
+mvGainAutoUpperLimit	32
+GainSelector	AnalogAll
+GainSelector	AnalogAll
+mvGainAutoLowerLimit	0
+GainSelector	AnalogAll
+GainSelector	AnalogAll
+mvGainAutoAverageGrey	50
+GainSelector	AnalogAll
+GainSelector	AnalogAll
+mvGainAutoHighlightAOI	Off
+GainSelector	AnalogAll
+GainSelector	AnalogAll
+mvGainAutoAOIMode	mvFull
+GainSelector	AnalogAll
+mvGainAutoMode	mvDevice
+BlackLevelSelector	All
+BlackLevel	0
+BlackLevelSelector	DigitalAll
+BlackLevel	0
+BlackLevelSelector	DigitalAll
+BlackLevelSelector	All
+BlackLevelAuto	Continuous
+BlackLevelSelector	DigitalAll
+BalanceRatioSelector	Red
+BalanceRatio	0.800271
+BalanceRatioSelector	Blue
+BalanceRatio	3.30967
+BalanceRatioSelector	Blue
+BalanceWhiteAuto	Continuous
+mvBalanceWhiteAutoAOIMode	mvFull
+mvLogicGateANDSelector	mvLogicGateAND1
+mvLogicGateANDSource1	Off
+mvLogicGateANDSelector	mvLogicGateAND2
+mvLogicGateANDSource1	Off
+mvLogicGateANDSelector	mvLogicGateAND3
+mvLogicGateANDSource1	Off
+mvLogicGateANDSelector	mvLogicGateAND4
+mvLogicGateANDSource1	Off
+mvLogicGateANDSelector	mvLogicGateAND1
+mvLogicGateANDSelector	mvLogicGateAND1
+mvLogicGateANDSource2	Off
+mvLogicGateANDSelector	mvLogicGateAND2
+mvLogicGateANDSource2	Off
+mvLogicGateANDSelector	mvLogicGateAND3
+mvLogicGateANDSource2	Off
+mvLogicGateANDSelector	mvLogicGateAND4
+mvLogicGateANDSource2	Off
+mvLogicGateANDSelector	mvLogicGateAND1
+mvLogicGateORSelector	mvLogicGateOR1
+mvLogicGateORSource1	mvLogicGateAND1Output
+mvLogicGateORSelector	mvLogicGateOR2
+mvLogicGateORSource1	mvLogicGateAND2Output
+mvLogicGateORSelector	mvLogicGateOR3
+mvLogicGateORSource1	mvLogicGateAND3Output
+mvLogicGateORSelector	mvLogicGateOR4
+mvLogicGateORSource1	mvLogicGateAND4Output
+mvLogicGateORSelector	mvLogicGateOR1
+mvLogicGateORSelector	mvLogicGateOR1
+mvLogicGateORSource2	Off
+mvLogicGateORSelector	mvLogicGateOR2
+mvLogicGateORSource2	Off
+mvLogicGateORSelector	mvLogicGateOR3
+mvLogicGateORSource2	Off
+mvLogicGateORSelector	mvLogicGateOR4
+mvLogicGateORSource2	Off
+mvLogicGateORSelector	mvLogicGateOR1
+mvLogicGateORSelector	mvLogicGateOR1
+mvLogicGateORSource3	Off
+mvLogicGateORSelector	mvLogicGateOR2
+mvLogicGateORSource3	Off
+mvLogicGateORSelector	mvLogicGateOR3
+mvLogicGateORSource3	Off
+mvLogicGateORSelector	mvLogicGateOR4
+mvLogicGateORSource3	Off
+mvLogicGateORSelector	mvLogicGateOR1
+mvLogicGateORSelector	mvLogicGateOR1
+mvLogicGateORSource4	Off
+mvLogicGateORSelector	mvLogicGateOR2
+mvLogicGateORSource4	Off
+mvLogicGateORSelector	mvLogicGateOR3
+mvLogicGateORSource4	Off
+mvLogicGateORSelector	mvLogicGateOR4
+mvLogicGateORSource4	Off
+mvLogicGateORSelector	mvLogicGateOR1
+ChunkModeActive	0
+ChunkSelector	Image
+ChunkEnable	1
+ChunkSelector	OffsetX
+ChunkEnable	1
+ChunkSelector	OffsetY
+ChunkEnable	1
+ChunkSelector	Width
+ChunkEnable	1
+ChunkSelector	Height
+ChunkEnable	1
+ChunkSelector	PixelFormat
+ChunkEnable	1
+ChunkSelector	Timestamp
+ChunkEnable	1
+ChunkSelector	LineStatusAll
+ChunkEnable	1
+ChunkSelector	CounterValue
+ChunkEnable	1
+ChunkSelector	TimerValue
+ChunkEnable	1
+ChunkSelector	ExposureTime
+ChunkEnable	1
+ChunkSelector	Gain
+ChunkEnable	1
+ChunkSelector	mvCustomIdentifier
+ChunkEnable	1
+ChunkSelector	Image
+LineSelector	Line0
+LineSource	Off
+LineSelector	Line1
+LineSource	Off
+LineSelector	Line2
+LineSource	Off
+LineSelector	Line3
+LineSource	Off
+LineSelector	Line0
+LineSelector	Line0
+LineInverter	0
+LineSelector	Line1
+LineInverter	0
+LineSelector	Line2
+LineInverter	0
+LineSelector	Line3
+LineInverter	0
+LineSelector	Line0
+LineSelector	Line4
+mvLineDebounceTimeRisingEdge	0
+LineSelector	Line5
+mvLineDebounceTimeRisingEdge	0
+LineSelector	Line0
+LineSelector	Line4
+mvLineDebounceTimeFallingEdge	0
+LineSelector	Line5
+mvLineDebounceTimeFallingEdge	0
+LineSelector	Line0
+UserOutputSelector	UserOutput0
+UserOutputValue	0
+UserOutputSelector	UserOutput1
+UserOutputValue	0
+UserOutputSelector	UserOutput2
+UserOutputValue	0
+UserOutputSelector	UserOutput3
+UserOutputValue	0
+UserOutputSelector	UserOutput0
+UserOutputValueAll	0
+UserOutputValueAllMask	0
+mvFrameAverageEnable	0
+mvFrameAverageMode	mvNTo1
+mvFrameAverageFrameCount	2
+ColorTransformationSelector	RGBtoRGB
+ColorTransformationEnable	0
+ColorTransformationSelector	RGBtoRGB
+ColorTransformationSelector	RGBtoRGB
+ColorTransformationValueSelector	Gain00
+ColorTransformationValue	1.86334
+ColorTransformationValueSelector	Gain01
+ColorTransformationValue	-0.586815
+ColorTransformationValueSelector	Gain02
+ColorTransformationValue	-0.219307
+ColorTransformationValueSelector	Gain10
+ColorTransformationValue	-0.423441
+ColorTransformationValueSelector	Gain11
+ColorTransformationValue	1.50376
+ColorTransformationValueSelector	Gain12
+ColorTransformationValue	-0.0803193
+ColorTransformationValueSelector	Gain20
+ColorTransformationValue	-0.0407081
+ColorTransformationValueSelector	Gain21
+ColorTransformationValue	-0.856356
+ColorTransformationValueSelector	Gain22
+ColorTransformationValue	2.18277
+ColorTransformationValueSelector	Offset0
+ColorTransformationValue	0
+ColorTransformationValueSelector	Offset1
+ColorTransformationValue	0
+ColorTransformationValueSelector	Offset2
+ColorTransformationValue	0
+ColorTransformationSelector	RGBtoRGB
+ColorTransformationValueSelector	Gain00
+LUTSelector	Red
+LUTEnable	0
+LUTSelector	Green
+LUTEnable	0
+LUTSelector	Blue
+LUTEnable	0
+LUTSelector	Luminance
+LUTEnable	0
+LUTSelector	Luminance
+LUTSelector	Red
+LUTValueAll	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
+LUTSelector	Green
+LUTValueAll	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
+LUTSelector	Blue
+LUTValueAll	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
+LUTSelector	Luminance
+LUTValueAll	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
+LUTSelector	Luminance
+EventSelector	ExposureEnd
+EventNotification	Off
+EventSelector	Line4RisingEdge
+EventNotification	Off
+EventSelector	Line5RisingEdge
+EventNotification	Off
+EventSelector	FrameEnd
+EventNotification	Off
+EventSelector	ExposureEnd
+</Value>
+</Property>
+<Property name="ImageRequestTimeout_ms" default="0" position="2" flags="7" size="1" formatString="%d ms" valType="1">
+<Value index="0" val="2000 ms"></Value>
+</Property>
+</PropList>
+<PropList name="ImageProcessing" default="0" position="3" flags="3" size="24" parent="none">
+<PropList name="FormatReinterpreter" default="0" position="1" flags="3" size="2" parent="none">
+<Property name="FormatReinterpreterEnable" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="FormatReinterpreterMode" default="0" position="1" flags="7" size="1" formatString="0x%08x" valType="1">
+<Value index="0" val="Mono8_To_RGB888Packed"></Value>
+</Property>
+</PropList>
+<PropList name="DefectivePixelsFilter" default="0" position="2" flags="3" size="8" parent="none">
+<Property name="Mode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="LeakyPixelDeviation_ADCLimit" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+<Property name="ColdPixelDeviation_pc" default="0" position="2" flags="7" size="1" formatString="%d %%" valType="1">
+<Value index="0" val="15 %"></Value>
+</Property>
+<Property name="DefectivePixelOffsetX" default="0" position="4" flags="3" size="1" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+</Property>
+<Property name="DefectivePixelOffsetY" default="0" position="5" flags="3" size="1" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+</Property>
+</PropList>
+<PropList name="DarkCurrentFilter" default="0" position="3" flags="3" size="3" parent="none">
+<Property name="Mode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="CalibrationImageCount" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="5"></Value>
+</Property>
+</PropList>
+<PropList name="FlatFieldFilter" default="0" position="4" flags="3" size="3" parent="none">
+<Property name="Mode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="CorrectionMode" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Default"></Value>
+</Property>
+<Property name="CalibrationImageCount" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="5"></Value>
+</Property>
+</PropList>
+<PropList name="GainOffsetKnee" default="0" position="6" flags="3" size="3" parent="none">
+<Property name="GainOffsetKneeEnable" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="GainOffsetKneeMasterOffset_pc" default="0" position="1" flags="7" size="1" formatString="%.2f %%" valType="2">
+<Value index="0" val="0.00 %"></Value>
+</Property>
+<PropList name="GainOffsetKneeChannels" default="0" position="2" flags="7" size="4" parent="none">
+<PropList name="Channel-0" default="0" position="0" flags="7" size="2" parent="none">
+<Property name="Gain" default="0" position="0" flags="7" size="1" formatString="%.4f" valType="2">
+<Value index="0" val="1.0000"></Value>
+</Property>
+<Property name="Offset_pc" default="0" position="1" flags="7" size="1" formatString="%.2f %%" valType="2">
+<Value index="0" val="0.00 %"></Value>
+</Property>
+</PropList>
+<PropList name="Channel-1" default="0" position="1" flags="7" size="2" parent="none">
+<Property name="Gain" default="0" position="0" flags="7" size="1" formatString="%.4f" valType="2">
+<Value index="0" val="1.0000"></Value>
+</Property>
+<Property name="Offset_pc" default="0" position="1" flags="7" size="1" formatString="%.2f %%" valType="2">
+<Value index="0" val="0.00 %"></Value>
+</Property>
+</PropList>
+<PropList name="Channel-2" default="0" position="2" flags="7" size="2" parent="none">
+<Property name="Gain" default="0" position="0" flags="7" size="1" formatString="%.4f" valType="2">
+<Value index="0" val="1.0000"></Value>
+</Property>
+<Property name="Offset_pc" default="0" position="1" flags="7" size="1" formatString="%.2f %%" valType="2">
+<Value index="0" val="0.00 %"></Value>
+</Property>
+</PropList>
+<PropList name="Channel-3" default="0" position="3" flags="7" size="2" parent="none">
+<Property name="Gain" default="0" position="0" flags="7" size="1" formatString="%.4f" valType="2">
+<Value index="0" val="1.0000"></Value>
+</Property>
+<Property name="Offset_pc" default="0" position="1" flags="7" size="1" formatString="%.2f %%" valType="2">
+<Value index="0" val="0.00 %"></Value>
+</Property>
+</PropList>
+</PropList>
+</PropList>
+<Property name="MirrorMode" default="0" position="7" flags="39" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<PropList name="Mirror" default="0" position="8" flags="3" size="3" parent="none">
+<Property name="MirrorOperationMode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Global"></Value>
+</Property>
+<Property name="MirrorModeGlobal" default="0" position="1" flags="39" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<PropList name="MirrorChannels" default="0" position="2" flags="7" size="3" parent="none">
+<PropList name="Channel-0" default="0" position="0" flags="7" size="1" parent="none">
+<Property name="MirrorMode" default="0" position="0" flags="39" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+</PropList>
+<PropList name="Channel-1" default="0" position="1" flags="7" size="1" parent="none">
+<Property name="MirrorMode" default="0" position="0" flags="39" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+</PropList>
+<PropList name="Channel-2" default="0" position="2" flags="7" size="1" parent="none">
+<Property name="MirrorMode" default="0" position="0" flags="39" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+</PropList>
+</PropList>
+</PropList>
+<Property name="ColorProcessing" default="0" position="9" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Auto"></Value>
+</Property>
+<Property name="BayerConversionMode" default="0" position="10" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Auto"></Value>
+</Property>
+<Property name="WhiteBalance" default="0" position="11" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="User1"></Value>
+</Property>
+<Property name="WhiteBalanceCalibration" default="0" position="12" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<PropList name="WhiteBalanceSettings-1" default="0" position="13" flags="3" size="8" parent="none">
+<Property name="WBAoiMode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Centered"></Value>
+</Property>
+<PropList name="WBAoi" default="0" position="1" flags="3" size="4" parent="none">
+<Property name="X" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="295"></Value>
+</Property>
+<Property name="Y" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="215"></Value>
+</Property>
+<Property name="W" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+<Property name="H" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+</PropList>
+<Property name="TotalGain" default="0" position="2" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="Offset" default="0" position="3" flags="7" size="1" formatString="%.1f" valType="2">
+<Value index="0" val="0.0"></Value>
+</Property>
+<Property name="RedGain" default="0" position="4" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="GreenGain" default="0" position="5" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="BlueGain" default="0" position="6" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+</PropList>
+<PropList name="WhiteBalanceSettings-2" default="0" position="14" flags="3" size="8" parent="none">
+<Property name="WBAoiMode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Centered"></Value>
+</Property>
+<PropList name="WBAoi" default="0" position="1" flags="3" size="4" parent="none">
+<Property name="X" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="295"></Value>
+</Property>
+<Property name="Y" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="215"></Value>
+</Property>
+<Property name="W" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+<Property name="H" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+</PropList>
+<Property name="TotalGain" default="0" position="2" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="Offset" default="0" position="3" flags="7" size="1" formatString="%.1f" valType="2">
+<Value index="0" val="0.0"></Value>
+</Property>
+<Property name="RedGain" default="0" position="4" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="GreenGain" default="0" position="5" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="BlueGain" default="0" position="6" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+</PropList>
+<PropList name="WhiteBalanceSettings-3" default="0" position="15" flags="3" size="8" parent="none">
+<Property name="WBAoiMode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Centered"></Value>
+</Property>
+<PropList name="WBAoi" default="0" position="1" flags="3" size="4" parent="none">
+<Property name="X" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="295"></Value>
+</Property>
+<Property name="Y" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="215"></Value>
+</Property>
+<Property name="W" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+<Property name="H" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+</PropList>
+<Property name="TotalGain" default="0" position="2" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="Offset" default="0" position="3" flags="7" size="1" formatString="%.1f" valType="2">
+<Value index="0" val="0.0"></Value>
+</Property>
+<Property name="RedGain" default="0" position="4" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="GreenGain" default="0" position="5" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="BlueGain" default="0" position="6" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+</PropList>
+<PropList name="WhiteBalanceSettings-4" default="0" position="16" flags="3" size="8" parent="none">
+<Property name="WBAoiMode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Centered"></Value>
+</Property>
+<PropList name="WBAoi" default="0" position="1" flags="3" size="4" parent="none">
+<Property name="X" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="295"></Value>
+</Property>
+<Property name="Y" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="215"></Value>
+</Property>
+<Property name="W" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+<Property name="H" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="50"></Value>
+</Property>
+</PropList>
+<Property name="TotalGain" default="0" position="2" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="Offset" default="0" position="3" flags="7" size="1" formatString="%.1f" valType="2">
+<Value index="0" val="0.0"></Value>
+</Property>
+<Property name="RedGain" default="0" position="4" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="GreenGain" default="0" position="5" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+<Property name="BlueGain" default="0" position="6" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.000"></Value>
+</Property>
+</PropList>
+<Property name="Filter" default="0" position="17" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<PropList name="Saturation" default="0" position="18" flags="3" size="3" parent="none">
+<Property name="Mode" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="Saturation_pc" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="100"></Value>
+</Property>
+<Property name="UVWeighting" default="0" position="2" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="1.400"></Value>
+</Property>
+</PropList>
+<PropList name="ColorTwist" default="0" position="19" flags="3" size="17" parent="none">
+<Property name="ColorTwistInputCorrectionMatrixEnable" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="ColorTwistInputCorrectionMatrixMode" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="DeviceSpecific"></Value>
+</Property>
+<Property name="ColorTwistInputCorrectionMatrixRow0" default="0" position="2" flags="7" size="3" formatString="%8.5f" valType="2">
+<Value index="0" val=" 1.00000"></Value>
+<Value index="1" val=" 0.00000"></Value>
+<Value index="2" val=" 0.00000"></Value>
+</Property>
+<Property name="ColorTwistInputCorrectionMatrixRow1" default="0" position="3" flags="7" size="3" formatString="%8.5f" valType="2">
+<Value index="0" val=" 0.00000"></Value>
+<Value index="1" val=" 1.00000"></Value>
+<Value index="2" val=" 0.00000"></Value>
+</Property>
+<Property name="ColorTwistInputCorrectionMatrixRow2" default="0" position="4" flags="7" size="3" formatString="%8.5f" valType="2">
+<Value index="0" val=" 0.00000"></Value>
+<Value index="1" val=" 0.00000"></Value>
+<Value index="2" val=" 1.00000"></Value>
+</Property>
+<Property name="ColorTwistEnable" default="0" position="5" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="ColorTwistRow0" default="0" position="6" flags="7" size="4" formatString="%8.5f" valType="2">
+<Value index="0" val=" 1.00000"></Value>
+<Value index="1" val=" 0.00000"></Value>
+<Value index="2" val=" 0.00000"></Value>
+<Value index="3" val=" 0.00000"></Value>
+</Property>
+<Property name="ColorTwistRow1" default="0" position="7" flags="7" size="4" formatString="%8.5f" valType="2">
+<Value index="0" val=" 0.00000"></Value>
+<Value index="1" val=" 1.00000"></Value>
+<Value index="2" val=" 0.00000"></Value>
+<Value index="3" val=" 0.00000"></Value>
+</Property>
+<Property name="ColorTwistRow2" default="0" position="8" flags="7" size="4" formatString="%8.5f" valType="2">
+<Value index="0" val=" 0.00000"></Value>
+<Value index="1" val=" 0.00000"></Value>
+<Value index="2" val=" 1.00000"></Value>
+<Value index="3" val=" 0.00000"></Value>
+</Property>
+<Property name="ColorTwistOutputCorrectionMatrixEnable" default="0" position="9" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="ColorTwistOutputCorrectionMatrixMode" default="0" position="10" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="XYZTosRGB_D50"></Value>
+</Property>
+<Property name="ColorTwistOutputCorrectionMatrixRow0" default="0" position="11" flags="7" size="3" formatString="%8.5f" valType="2">
+<Value index="0" val=" 1.00000"></Value>
+<Value index="1" val=" 0.00000"></Value>
+<Value index="2" val=" 0.00000"></Value>
+</Property>
+<Property name="ColorTwistOutputCorrectionMatrixRow1" default="0" position="12" flags="7" size="3" formatString="%8.5f" valType="2">
+<Value index="0" val=" 0.00000"></Value>
+<Value index="1" val=" 1.00000"></Value>
+<Value index="2" val=" 0.00000"></Value>
+</Property>
+<Property name="ColorTwistOutputCorrectionMatrixRow2" default="0" position="13" flags="7" size="3" formatString="%8.5f" valType="2">
+<Value index="0" val=" 0.00000"></Value>
+<Value index="1" val=" 0.00000"></Value>
+<Value index="2" val=" 1.00000"></Value>
+</Property>
+</PropList>
+<PropList name="LUTOperations" default="0" position="20" flags="3" size="7" parent="none">
+<Property name="LUTEnable" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="LUTMode" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Gamma"></Value>
+</Property>
+<Property name="LUTInterpolationMode" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Linear"></Value>
+</Property>
+<Property name="LUTImplementation" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Software"></Value>
+</Property>
+<Property name="LUTMappingHardware" default="0" position="4" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+</Property>
+<Property name="LUTMappingSoftware" default="0" position="5" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="8To8"></Value>
+</Property>
+<PropList name="LUTs" default="0" position="6" flags="7" size="4" parent="none">
+<PropList name="LUT-0" default="0" position="0" flags="7" size="10" parent="none">
+<Property name="Gamma" default="0" position="0" flags="7" size="1" formatString="%f" valType="2">
+<Value index="0" val="1.800000"></Value>
+</Property>
+<Property name="GammaAlpha" default="0" position="1" flags="7" size="1" formatString="%f" valType="2">
+<Value index="0" val="0.000000"></Value>
+</Property>
+<Property name="GammaMode" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="LinearStart"></Value>
+</Property>
+<Property name="GammaStartThreshold" default="0" position="3" flags="263" size="1" formatString="%d" valType="1">
+<Value index="0" val="12"></Value>
+</Property>
+<Property name="ValueCount" default="1" position="4" flags="259" size="1" formatString="%d" valType="1">
+<Value index="0" val="2"></Value>
+</Property>
+<Property name="InputValues" default="0" position="5" flags="263" size="2" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+<Value index="1" val="255"></Value>
+</Property>
+<Property name="OutputValues" default="0" position="6" flags="263" size="2" formatString="%d" valType="1">
+<Value index="0" val="255"></Value>
+<Value index="1" val="0"></Value>
+</Property>
+<Property name="DirectValues" default="0" position="7" flags="263" size="256" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+<Value index="1" val="0"></Value>
+<Value index="2" val="0"></Value>
+<Value index="3" val="0"></Value>
+<Value index="4" val="0"></Value>
+<Value index="5" val="0"></Value>
+<Value index="6" val="0"></Value>
+<Value index="7" val="0"></Value>
+<Value index="8" val="0"></Value>
+<Value index="9" val="0"></Value>
+<Value index="10" val="0"></Value>
+<Value index="11" val="0"></Value>
+<Value index="12" val="0"></Value>
+<Value index="13" val="0"></Value>
+<Value index="14" val="0"></Value>
+<Value index="15" val="0"></Value>
+<Value index="16" val="0"></Value>
+<Value index="17" val="0"></Value>
+<Value index="18" val="0"></Value>
+<Value index="19" val="0"></Value>
+<Value index="20" val="0"></Value>
+<Value index="21" val="0"></Value>
+<Value index="22" val="0"></Value>
+<Value index="23" val="0"></Value>
+<Value index="24" val="0"></Value>
+<Value index="25" val="0"></Value>
+<Value index="26" val="0"></Value>
+<Value index="27" val="0"></Value>
+<Value index="28" val="0"></Value>
+<Value index="29" val="0"></Value>
+<Value index="30" val="0"></Value>
+<Value index="31" val="0"></Value>
+<Value index="32" val="0"></Value>
+<Value index="33" val="0"></Value>
+<Value index="34" val="0"></Value>
+<Value index="35" val="0"></Value>
+<Value index="36" val="0"></Value>
+<Value index="37" val="0"></Value>
+<Value index="38" val="0"></Value>
+<Value index="39" val="0"></Value>
+<Value index="40" val="0"></Value>
+<Value index="41" val="0"></Value>
+<Value index="42" val="0"></Value>
+<Value index="43" val="0"></Value>
+<Value index="44" val="0"></Value>
+<Value index="45" val="0"></Value>
+<Value index="46" val="0"></Value>
+<Value index="47" val="0"></Value>
+<Value index="48" val="0"></Value>
+<Value index="49" val="0"></Value>
+<Value index="50" val="0"></Value>
+<Value index="51" val="0"></Value>
+<Value index="52" val="0"></Value>
+<Value index="53" val="0"></Value>
+<Value index="54" val="0"></Value>
+<Value index="55" val="0"></Value>
+<Value index="56" val="0"></Value>
+<Value index="57" val="0"></Value>
+<Value index="58" val="0"></Value>
+<Value index="59" val="0"></Value>
+<Value index="60" val="0"></Value>
+<Value index="61" val="0"></Value>
+<Value index="62" val="0"></Value>
+<Value index="63" val="0"></Value>
+<Value index="64" val="0"></Value>
+<Value index="65" val="0"></Value>
+<Value index="66" val="0"></Value>
+<Value index="67" val="0"></Value>
+<Value index="68" val="0"></Value>
+<Value index="69" val="0"></Value>
+<Value index="70" val="0"></Value>
+<Value index="71" val="0"></Value>
+<Value index="72" val="0"></Value>
+<Value index="73" val="0"></Value>
+<Value index="74" val="0"></Value>
+<Value index="75" val="0"></Value>
+<Value index="76" val="0"></Value>
+<Value index="77" val="0"></Value>
+<Value index="78" val="0"></Value>
+<Value index="79" val="0"></Value>
+<Value index="80" val="0"></Value>
+<Value index="81" val="0"></Value>
+<Value index="82" val="0"></Value>
+<Value index="83" val="0"></Value>
+<Value index="84" val="0"></Value>
+<Value index="85" val="0"></Value>
+<Value index="86" val="0"></Value>
+<Value index="87" val="0"></Value>
+<Value index="88" val="0"></Value>
+<Value index="89" val="0"></Value>
+<Value index="90" val="0"></Value>
+<Value index="91" val="0"></Value>
+<Value index="92" val="0"></Value>
+<Value index="93" val="0"></Value>
+<Value index="94" val="0"></Value>
+<Value index="95" val="0"></Value>
+<Value index="96" val="0"></Value>
+<Value index="97" val="0"></Value>
+<Value index="98" val="0"></Value>
+<Value index="99" val="0"></Value>
+<Value index="100" val="0"></Value>
+<Value index="101" val="0"></Value>
+<Value index="102" val="0"></Value>
+<Value index="103" val="0"></Value>
+<Value index="104" val="0"></Value>
+<Value index="105" val="0"></Value>
+<Value index="106" val="0"></Value>
+<Value index="107" val="0"></Value>
+<Value index="108" val="0"></Value>
+<Value index="109" val="0"></Value>
+<Value index="110" val="0"></Value>
+<Value index="111" val="0"></Value>
+<Value index="112" val="0"></Value>
+<Value index="113" val="0"></Value>
+<Value index="114" val="0"></Value>
+<Value index="115" val="0"></Value>
+<Value index="116" val="0"></Value>
+<Value index="117" val="0"></Value>
+<Value index="118" val="0"></Value>
+<Value index="119" val="0"></Value>
+<Value index="120" val="0"></Value>
+<Value index="121" val="0"></Value>
+<Value index="122" val="0"></Value>
+<Value index="123" val="0"></Value>
+<Value index="124" val="0"></Value>
+<Value index="125" val="0"></Value>
+<Value index="126" val="0"></Value>
+<Value index="127" val="0"></Value>
+<Value index="128" val="0"></Value>
+<Value index="129" val="0"></Value>
+<Value index="130" val="0"></Value>
+<Value index="131" val="0"></Value>
+<Value index="132" val="0"></Value>
+<Value index="133" val="0"></Value>
+<Value index="134" val="0"></Value>
+<Value index="135" val="0"></Value>
+<Value index="136" val="0"></Value>
+<Value index="137" val="0"></Value>
+<Value index="138" val="0"></Value>
+<Value index="139" val="0"></Value>
+<Value index="140" val="0"></Value>
+<Value index="141" val="0"></Value>
+<Value index="142" val="0"></Value>
+<Value index="143" val="0"></Value>
+<Value index="144" val="0"></Value>
+<Value index="145" val="0"></Value>
+<Value index="146" val="0"></Value>
+<Value index="147" val="0"></Value>
+<Value index="148" val="0"></Value>
+<Value index="149" val="0"></Value>
+<Value index="150" val="0"></Value>
+<Value index="151" val="0"></Value>
+<Value index="152" val="0"></Value>
+<Value index="153" val="0"></Value>
+<Value index="154" val="0"></Value>
+<Value index="155" val="0"></Value>
+<Value index="156" val="0"></Value>
+<Value index="157" val="0"></Value>
+<Value index="158" val="0"></Value>
+<Value index="159" val="0"></Value>
+<Value index="160" val="0"></Value>
+<Value index="161" val="0"></Value>
+<Value index="162" val="0"></Value>
+<Value index="163" val="0"></Value>
+<Value index="164" val="0"></Value>
+<Value index="165" val="0"></Value>
+<Value index="166" val="0"></Value>
+<Value index="167" val="0"></Value>
+<Value index="168" val="0"></Value>
+<Value index="169" val="0"></Value>
+<Value index="170" val="0"></Value>
+<Value index="171" val="0"></Value>
+<Value index="172" val="0"></Value>
+<Value index="173" val="0"></Value>
+<Value index="174" val="0"></Value>
+<Value index="175" val="0"></Value>
+<Value index="176" val="0"></Value>
+<Value index="177" val="0"></Value>
+<Value index="178" val="0"></Value>
+<Value index="179" val="0"></Value>
+<Value index="180" val="0"></Value>
+<Value index="181" val="0"></Value>
+<Value index="182" val="0"></Value>
+<Value index="183" val="0"></Value>
+<Value index="184" val="0"></Value>
+<Value index="185" val="0"></Value>
+<Value index="186" val="0"></Value>
+<Value index="187" val="0"></Value>
+<Value index="188" val="0"></Value>
+<Value index="189" val="0"></Value>
+<Value index="190" val="0"></Value>
+<Value index="191" val="0"></Value>
+<Value index="192" val="0"></Value>
+<Value index="193" val="0"></Value>
+<Value index="194" val="0"></Value>
+<Value index="195" val="0"></Value>
+<Value index="196" val="0"></Value>
+<Value index="197" val="0"></Value>
+<Value index="198" val="0"></Value>
+<Value index="199" val="0"></Value>
+<Value index="200" val="0"></Value>
+<Value index="201" val="0"></Value>
+<Value index="202" val="0"></Value>
+<Value index="203" val="0"></Value>
+<Value index="204" val="0"></Value>
+<Value index="205" val="0"></Value>
+<Value index="206" val="0"></Value>
+<Value index="207" val="0"></Value>
+<Value index="208" val="0"></Value>
+<Value index="209" val="0"></Value>
+<Value index="210" val="0"></Value>
+<Value index="211" val="0"></Value>
+<Value index="212" val="0"></Value>
+<Value index="213" val="0"></Value>
+<Value index="214" val="0"></Value>
+<Value index="215" val="0"></Value>
+<Value index="216" val="0"></Value>
+<Value index="217" val="0"></Value>
+<Value index="218" val="0"></Value>
+<Value index="219" val="0"></Value>
+<Value index="220" val="0"></Value>
+<Value index="221" val="0"></Value>
+<Value index="222" val="0"></Value>
+<Value index="223" val="0"></Value>
+<Value index="224" val="0"></Value>
+<Value index="225" val="0"></Value>
+<Value index="226" val="0"></Value>
+<Value index="227" val="0"></Value>
+<Value index="228" val="0"></Value>
+<Value index="229" val="0"></Value>
+<Value index="230" val="0"></Value>
+<Value index="231" val="0"></Value>
+<Value index="232" val="0"></Value>
+<Value index="233" val="0"></Value>
+<Value index="234" val="0"></Value>
+<Value index="235" val="0"></Value>
+<Value index="236" val="0"></Value>
+<Value index="237" val="0"></Value>
+<Value index="238" val="0"></Value>
+<Value index="239" val="0"></Value>
+<Value index="240" val="0"></Value>
+<Value index="241" val="0"></Value>
+<Value index="242" val="0"></Value>
+<Value index="243" val="0"></Value>
+<Value index="244" val="0"></Value>
+<Value index="245" val="0"></Value>
+<Value index="246" val="0"></Value>
+<Value index="247" val="0"></Value>
+<Value index="248" val="0"></Value>
+<Value index="249" val="0"></Value>
+<Value index="250" val="0"></Value>
+<Value index="251" val="0"></Value>
+<Value index="252" val="0"></Value>
+<Value index="253" val="0"></Value>
+<Value index="254" val="0"></Value>
+<Value index="255" val="0"></Value>
+</Property>
+<Property name="FileName" default="0" position="8" flags="7" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+</PropList>
+<PropList name="LUT-1" default="0" position="1" flags="7" size="10" parent="none">
+<Property name="Gamma" default="0" position="0" flags="7" size="1" formatString="%f" valType="2">
+<Value index="0" val="1.800000"></Value>
+</Property>
+<Property name="GammaAlpha" default="0" position="1" flags="7" size="1" formatString="%f" valType="2">
+<Value index="0" val="0.000000"></Value>
+</Property>
+<Property name="GammaMode" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="LinearStart"></Value>
+</Property>
+<Property name="GammaStartThreshold" default="0" position="3" flags="263" size="1" formatString="%d" valType="1">
+<Value index="0" val="12"></Value>
+</Property>
+<Property name="ValueCount" default="1" position="4" flags="259" size="1" formatString="%d" valType="1">
+<Value index="0" val="2"></Value>
+</Property>
+<Property name="InputValues" default="0" position="5" flags="263" size="2" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+<Value index="1" val="255"></Value>
+</Property>
+<Property name="OutputValues" default="0" position="6" flags="263" size="2" formatString="%d" valType="1">
+<Value index="0" val="255"></Value>
+<Value index="1" val="0"></Value>
+</Property>
+<Property name="DirectValues" default="0" position="7" flags="263" size="256" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+<Value index="1" val="0"></Value>
+<Value index="2" val="0"></Value>
+<Value index="3" val="0"></Value>
+<Value index="4" val="0"></Value>
+<Value index="5" val="0"></Value>
+<Value index="6" val="0"></Value>
+<Value index="7" val="0"></Value>
+<Value index="8" val="0"></Value>
+<Value index="9" val="0"></Value>
+<Value index="10" val="0"></Value>
+<Value index="11" val="0"></Value>
+<Value index="12" val="0"></Value>
+<Value index="13" val="0"></Value>
+<Value index="14" val="0"></Value>
+<Value index="15" val="0"></Value>
+<Value index="16" val="0"></Value>
+<Value index="17" val="0"></Value>
+<Value index="18" val="0"></Value>
+<Value index="19" val="0"></Value>
+<Value index="20" val="0"></Value>
+<Value index="21" val="0"></Value>
+<Value index="22" val="0"></Value>
+<Value index="23" val="0"></Value>
+<Value index="24" val="0"></Value>
+<Value index="25" val="0"></Value>
+<Value index="26" val="0"></Value>
+<Value index="27" val="0"></Value>
+<Value index="28" val="0"></Value>
+<Value index="29" val="0"></Value>
+<Value index="30" val="0"></Value>
+<Value index="31" val="0"></Value>
+<Value index="32" val="0"></Value>
+<Value index="33" val="0"></Value>
+<Value index="34" val="0"></Value>
+<Value index="35" val="0"></Value>
+<Value index="36" val="0"></Value>
+<Value index="37" val="0"></Value>
+<Value index="38" val="0"></Value>
+<Value index="39" val="0"></Value>
+<Value index="40" val="0"></Value>
+<Value index="41" val="0"></Value>
+<Value index="42" val="0"></Value>
+<Value index="43" val="0"></Value>
+<Value index="44" val="0"></Value>
+<Value index="45" val="0"></Value>
+<Value index="46" val="0"></Value>
+<Value index="47" val="0"></Value>
+<Value index="48" val="0"></Value>
+<Value index="49" val="0"></Value>
+<Value index="50" val="0"></Value>
+<Value index="51" val="0"></Value>
+<Value index="52" val="0"></Value>
+<Value index="53" val="0"></Value>
+<Value index="54" val="0"></Value>
+<Value index="55" val="0"></Value>
+<Value index="56" val="0"></Value>
+<Value index="57" val="0"></Value>
+<Value index="58" val="0"></Value>
+<Value index="59" val="0"></Value>
+<Value index="60" val="0"></Value>
+<Value index="61" val="0"></Value>
+<Value index="62" val="0"></Value>
+<Value index="63" val="0"></Value>
+<Value index="64" val="0"></Value>
+<Value index="65" val="0"></Value>
+<Value index="66" val="0"></Value>
+<Value index="67" val="0"></Value>
+<Value index="68" val="0"></Value>
+<Value index="69" val="0"></Value>
+<Value index="70" val="0"></Value>
+<Value index="71" val="0"></Value>
+<Value index="72" val="0"></Value>
+<Value index="73" val="0"></Value>
+<Value index="74" val="0"></Value>
+<Value index="75" val="0"></Value>
+<Value index="76" val="0"></Value>
+<Value index="77" val="0"></Value>
+<Value index="78" val="0"></Value>
+<Value index="79" val="0"></Value>
+<Value index="80" val="0"></Value>
+<Value index="81" val="0"></Value>
+<Value index="82" val="0"></Value>
+<Value index="83" val="0"></Value>
+<Value index="84" val="0"></Value>
+<Value index="85" val="0"></Value>
+<Value index="86" val="0"></Value>
+<Value index="87" val="0"></Value>
+<Value index="88" val="0"></Value>
+<Value index="89" val="0"></Value>
+<Value index="90" val="0"></Value>
+<Value index="91" val="0"></Value>
+<Value index="92" val="0"></Value>
+<Value index="93" val="0"></Value>
+<Value index="94" val="0"></Value>
+<Value index="95" val="0"></Value>
+<Value index="96" val="0"></Value>
+<Value index="97" val="0"></Value>
+<Value index="98" val="0"></Value>
+<Value index="99" val="0"></Value>
+<Value index="100" val="0"></Value>
+<Value index="101" val="0"></Value>
+<Value index="102" val="0"></Value>
+<Value index="103" val="0"></Value>
+<Value index="104" val="0"></Value>
+<Value index="105" val="0"></Value>
+<Value index="106" val="0"></Value>
+<Value index="107" val="0"></Value>
+<Value index="108" val="0"></Value>
+<Value index="109" val="0"></Value>
+<Value index="110" val="0"></Value>
+<Value index="111" val="0"></Value>
+<Value index="112" val="0"></Value>
+<Value index="113" val="0"></Value>
+<Value index="114" val="0"></Value>
+<Value index="115" val="0"></Value>
+<Value index="116" val="0"></Value>
+<Value index="117" val="0"></Value>
+<Value index="118" val="0"></Value>
+<Value index="119" val="0"></Value>
+<Value index="120" val="0"></Value>
+<Value index="121" val="0"></Value>
+<Value index="122" val="0"></Value>
+<Value index="123" val="0"></Value>
+<Value index="124" val="0"></Value>
+<Value index="125" val="0"></Value>
+<Value index="126" val="0"></Value>
+<Value index="127" val="0"></Value>
+<Value index="128" val="0"></Value>
+<Value index="129" val="0"></Value>
+<Value index="130" val="0"></Value>
+<Value index="131" val="0"></Value>
+<Value index="132" val="0"></Value>
+<Value index="133" val="0"></Value>
+<Value index="134" val="0"></Value>
+<Value index="135" val="0"></Value>
+<Value index="136" val="0"></Value>
+<Value index="137" val="0"></Value>
+<Value index="138" val="0"></Value>
+<Value index="139" val="0"></Value>
+<Value index="140" val="0"></Value>
+<Value index="141" val="0"></Value>
+<Value index="142" val="0"></Value>
+<Value index="143" val="0"></Value>
+<Value index="144" val="0"></Value>
+<Value index="145" val="0"></Value>
+<Value index="146" val="0"></Value>
+<Value index="147" val="0"></Value>
+<Value index="148" val="0"></Value>
+<Value index="149" val="0"></Value>
+<Value index="150" val="0"></Value>
+<Value index="151" val="0"></Value>
+<Value index="152" val="0"></Value>
+<Value index="153" val="0"></Value>
+<Value index="154" val="0"></Value>
+<Value index="155" val="0"></Value>
+<Value index="156" val="0"></Value>
+<Value index="157" val="0"></Value>
+<Value index="158" val="0"></Value>
+<Value index="159" val="0"></Value>
+<Value index="160" val="0"></Value>
+<Value index="161" val="0"></Value>
+<Value index="162" val="0"></Value>
+<Value index="163" val="0"></Value>
+<Value index="164" val="0"></Value>
+<Value index="165" val="0"></Value>
+<Value index="166" val="0"></Value>
+<Value index="167" val="0"></Value>
+<Value index="168" val="0"></Value>
+<Value index="169" val="0"></Value>
+<Value index="170" val="0"></Value>
+<Value index="171" val="0"></Value>
+<Value index="172" val="0"></Value>
+<Value index="173" val="0"></Value>
+<Value index="174" val="0"></Value>
+<Value index="175" val="0"></Value>
+<Value index="176" val="0"></Value>
+<Value index="177" val="0"></Value>
+<Value index="178" val="0"></Value>
+<Value index="179" val="0"></Value>
+<Value index="180" val="0"></Value>
+<Value index="181" val="0"></Value>
+<Value index="182" val="0"></Value>
+<Value index="183" val="0"></Value>
+<Value index="184" val="0"></Value>
+<Value index="185" val="0"></Value>
+<Value index="186" val="0"></Value>
+<Value index="187" val="0"></Value>
+<Value index="188" val="0"></Value>
+<Value index="189" val="0"></Value>
+<Value index="190" val="0"></Value>
+<Value index="191" val="0"></Value>
+<Value index="192" val="0"></Value>
+<Value index="193" val="0"></Value>
+<Value index="194" val="0"></Value>
+<Value index="195" val="0"></Value>
+<Value index="196" val="0"></Value>
+<Value index="197" val="0"></Value>
+<Value index="198" val="0"></Value>
+<Value index="199" val="0"></Value>
+<Value index="200" val="0"></Value>
+<Value index="201" val="0"></Value>
+<Value index="202" val="0"></Value>
+<Value index="203" val="0"></Value>
+<Value index="204" val="0"></Value>
+<Value index="205" val="0"></Value>
+<Value index="206" val="0"></Value>
+<Value index="207" val="0"></Value>
+<Value index="208" val="0"></Value>
+<Value index="209" val="0"></Value>
+<Value index="210" val="0"></Value>
+<Value index="211" val="0"></Value>
+<Value index="212" val="0"></Value>
+<Value index="213" val="0"></Value>
+<Value index="214" val="0"></Value>
+<Value index="215" val="0"></Value>
+<Value index="216" val="0"></Value>
+<Value index="217" val="0"></Value>
+<Value index="218" val="0"></Value>
+<Value index="219" val="0"></Value>
+<Value index="220" val="0"></Value>
+<Value index="221" val="0"></Value>
+<Value index="222" val="0"></Value>
+<Value index="223" val="0"></Value>
+<Value index="224" val="0"></Value>
+<Value index="225" val="0"></Value>
+<Value index="226" val="0"></Value>
+<Value index="227" val="0"></Value>
+<Value index="228" val="0"></Value>
+<Value index="229" val="0"></Value>
+<Value index="230" val="0"></Value>
+<Value index="231" val="0"></Value>
+<Value index="232" val="0"></Value>
+<Value index="233" val="0"></Value>
+<Value index="234" val="0"></Value>
+<Value index="235" val="0"></Value>
+<Value index="236" val="0"></Value>
+<Value index="237" val="0"></Value>
+<Value index="238" val="0"></Value>
+<Value index="239" val="0"></Value>
+<Value index="240" val="0"></Value>
+<Value index="241" val="0"></Value>
+<Value index="242" val="0"></Value>
+<Value index="243" val="0"></Value>
+<Value index="244" val="0"></Value>
+<Value index="245" val="0"></Value>
+<Value index="246" val="0"></Value>
+<Value index="247" val="0"></Value>
+<Value index="248" val="0"></Value>
+<Value index="249" val="0"></Value>
+<Value index="250" val="0"></Value>
+<Value index="251" val="0"></Value>
+<Value index="252" val="0"></Value>
+<Value index="253" val="0"></Value>
+<Value index="254" val="0"></Value>
+<Value index="255" val="0"></Value>
+</Property>
+<Property name="FileName" default="0" position="8" flags="7" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+</PropList>
+<PropList name="LUT-2" default="0" position="2" flags="7" size="10" parent="none">
+<Property name="Gamma" default="0" position="0" flags="7" size="1" formatString="%f" valType="2">
+<Value index="0" val="1.800000"></Value>
+</Property>
+<Property name="GammaAlpha" default="0" position="1" flags="7" size="1" formatString="%f" valType="2">
+<Value index="0" val="0.000000"></Value>
+</Property>
+<Property name="GammaMode" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="LinearStart"></Value>
+</Property>
+<Property name="GammaStartThreshold" default="0" position="3" flags="263" size="1" formatString="%d" valType="1">
+<Value index="0" val="12"></Value>
+</Property>
+<Property name="ValueCount" default="1" position="4" flags="259" size="1" formatString="%d" valType="1">
+<Value index="0" val="2"></Value>
+</Property>
+<Property name="InputValues" default="0" position="5" flags="263" size="2" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+<Value index="1" val="255"></Value>
+</Property>
+<Property name="OutputValues" default="0" position="6" flags="263" size="2" formatString="%d" valType="1">
+<Value index="0" val="255"></Value>
+<Value index="1" val="0"></Value>
+</Property>
+<Property name="DirectValues" default="0" position="7" flags="263" size="256" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+<Value index="1" val="0"></Value>
+<Value index="2" val="0"></Value>
+<Value index="3" val="0"></Value>
+<Value index="4" val="0"></Value>
+<Value index="5" val="0"></Value>
+<Value index="6" val="0"></Value>
+<Value index="7" val="0"></Value>
+<Value index="8" val="0"></Value>
+<Value index="9" val="0"></Value>
+<Value index="10" val="0"></Value>
+<Value index="11" val="0"></Value>
+<Value index="12" val="0"></Value>
+<Value index="13" val="0"></Value>
+<Value index="14" val="0"></Value>
+<Value index="15" val="0"></Value>
+<Value index="16" val="0"></Value>
+<Value index="17" val="0"></Value>
+<Value index="18" val="0"></Value>
+<Value index="19" val="0"></Value>
+<Value index="20" val="0"></Value>
+<Value index="21" val="0"></Value>
+<Value index="22" val="0"></Value>
+<Value index="23" val="0"></Value>
+<Value index="24" val="0"></Value>
+<Value index="25" val="0"></Value>
+<Value index="26" val="0"></Value>
+<Value index="27" val="0"></Value>
+<Value index="28" val="0"></Value>
+<Value index="29" val="0"></Value>
+<Value index="30" val="0"></Value>
+<Value index="31" val="0"></Value>
+<Value index="32" val="0"></Value>
+<Value index="33" val="0"></Value>
+<Value index="34" val="0"></Value>
+<Value index="35" val="0"></Value>
+<Value index="36" val="0"></Value>
+<Value index="37" val="0"></Value>
+<Value index="38" val="0"></Value>
+<Value index="39" val="0"></Value>
+<Value index="40" val="0"></Value>
+<Value index="41" val="0"></Value>
+<Value index="42" val="0"></Value>
+<Value index="43" val="0"></Value>
+<Value index="44" val="0"></Value>
+<Value index="45" val="0"></Value>
+<Value index="46" val="0"></Value>
+<Value index="47" val="0"></Value>
+<Value index="48" val="0"></Value>
+<Value index="49" val="0"></Value>
+<Value index="50" val="0"></Value>
+<Value index="51" val="0"></Value>
+<Value index="52" val="0"></Value>
+<Value index="53" val="0"></Value>
+<Value index="54" val="0"></Value>
+<Value index="55" val="0"></Value>
+<Value index="56" val="0"></Value>
+<Value index="57" val="0"></Value>
+<Value index="58" val="0"></Value>
+<Value index="59" val="0"></Value>
+<Value index="60" val="0"></Value>
+<Value index="61" val="0"></Value>
+<Value index="62" val="0"></Value>
+<Value index="63" val="0"></Value>
+<Value index="64" val="0"></Value>
+<Value index="65" val="0"></Value>
+<Value index="66" val="0"></Value>
+<Value index="67" val="0"></Value>
+<Value index="68" val="0"></Value>
+<Value index="69" val="0"></Value>
+<Value index="70" val="0"></Value>
+<Value index="71" val="0"></Value>
+<Value index="72" val="0"></Value>
+<Value index="73" val="0"></Value>
+<Value index="74" val="0"></Value>
+<Value index="75" val="0"></Value>
+<Value index="76" val="0"></Value>
+<Value index="77" val="0"></Value>
+<Value index="78" val="0"></Value>
+<Value index="79" val="0"></Value>
+<Value index="80" val="0"></Value>
+<Value index="81" val="0"></Value>
+<Value index="82" val="0"></Value>
+<Value index="83" val="0"></Value>
+<Value index="84" val="0"></Value>
+<Value index="85" val="0"></Value>
+<Value index="86" val="0"></Value>
+<Value index="87" val="0"></Value>
+<Value index="88" val="0"></Value>
+<Value index="89" val="0"></Value>
+<Value index="90" val="0"></Value>
+<Value index="91" val="0"></Value>
+<Value index="92" val="0"></Value>
+<Value index="93" val="0"></Value>
+<Value index="94" val="0"></Value>
+<Value index="95" val="0"></Value>
+<Value index="96" val="0"></Value>
+<Value index="97" val="0"></Value>
+<Value index="98" val="0"></Value>
+<Value index="99" val="0"></Value>
+<Value index="100" val="0"></Value>
+<Value index="101" val="0"></Value>
+<Value index="102" val="0"></Value>
+<Value index="103" val="0"></Value>
+<Value index="104" val="0"></Value>
+<Value index="105" val="0"></Value>
+<Value index="106" val="0"></Value>
+<Value index="107" val="0"></Value>
+<Value index="108" val="0"></Value>
+<Value index="109" val="0"></Value>
+<Value index="110" val="0"></Value>
+<Value index="111" val="0"></Value>
+<Value index="112" val="0"></Value>
+<Value index="113" val="0"></Value>
+<Value index="114" val="0"></Value>
+<Value index="115" val="0"></Value>
+<Value index="116" val="0"></Value>
+<Value index="117" val="0"></Value>
+<Value index="118" val="0"></Value>
+<Value index="119" val="0"></Value>
+<Value index="120" val="0"></Value>
+<Value index="121" val="0"></Value>
+<Value index="122" val="0"></Value>
+<Value index="123" val="0"></Value>
+<Value index="124" val="0"></Value>
+<Value index="125" val="0"></Value>
+<Value index="126" val="0"></Value>
+<Value index="127" val="0"></Value>
+<Value index="128" val="0"></Value>
+<Value index="129" val="0"></Value>
+<Value index="130" val="0"></Value>
+<Value index="131" val="0"></Value>
+<Value index="132" val="0"></Value>
+<Value index="133" val="0"></Value>
+<Value index="134" val="0"></Value>
+<Value index="135" val="0"></Value>
+<Value index="136" val="0"></Value>
+<Value index="137" val="0"></Value>
+<Value index="138" val="0"></Value>
+<Value index="139" val="0"></Value>
+<Value index="140" val="0"></Value>
+<Value index="141" val="0"></Value>
+<Value index="142" val="0"></Value>
+<Value index="143" val="0"></Value>
+<Value index="144" val="0"></Value>
+<Value index="145" val="0"></Value>
+<Value index="146" val="0"></Value>
+<Value index="147" val="0"></Value>
+<Value index="148" val="0"></Value>
+<Value index="149" val="0"></Value>
+<Value index="150" val="0"></Value>
+<Value index="151" val="0"></Value>
+<Value index="152" val="0"></Value>
+<Value index="153" val="0"></Value>
+<Value index="154" val="0"></Value>
+<Value index="155" val="0"></Value>
+<Value index="156" val="0"></Value>
+<Value index="157" val="0"></Value>
+<Value index="158" val="0"></Value>
+<Value index="159" val="0"></Value>
+<Value index="160" val="0"></Value>
+<Value index="161" val="0"></Value>
+<Value index="162" val="0"></Value>
+<Value index="163" val="0"></Value>
+<Value index="164" val="0"></Value>
+<Value index="165" val="0"></Value>
+<Value index="166" val="0"></Value>
+<Value index="167" val="0"></Value>
+<Value index="168" val="0"></Value>
+<Value index="169" val="0"></Value>
+<Value index="170" val="0"></Value>
+<Value index="171" val="0"></Value>
+<Value index="172" val="0"></Value>
+<Value index="173" val="0"></Value>
+<Value index="174" val="0"></Value>
+<Value index="175" val="0"></Value>
+<Value index="176" val="0"></Value>
+<Value index="177" val="0"></Value>
+<Value index="178" val="0"></Value>
+<Value index="179" val="0"></Value>
+<Value index="180" val="0"></Value>
+<Value index="181" val="0"></Value>
+<Value index="182" val="0"></Value>
+<Value index="183" val="0"></Value>
+<Value index="184" val="0"></Value>
+<Value index="185" val="0"></Value>
+<Value index="186" val="0"></Value>
+<Value index="187" val="0"></Value>
+<Value index="188" val="0"></Value>
+<Value index="189" val="0"></Value>
+<Value index="190" val="0"></Value>
+<Value index="191" val="0"></Value>
+<Value index="192" val="0"></Value>
+<Value index="193" val="0"></Value>
+<Value index="194" val="0"></Value>
+<Value index="195" val="0"></Value>
+<Value index="196" val="0"></Value>
+<Value index="197" val="0"></Value>
+<Value index="198" val="0"></Value>
+<Value index="199" val="0"></Value>
+<Value index="200" val="0"></Value>
+<Value index="201" val="0"></Value>
+<Value index="202" val="0"></Value>
+<Value index="203" val="0"></Value>
+<Value index="204" val="0"></Value>
+<Value index="205" val="0"></Value>
+<Value index="206" val="0"></Value>
+<Value index="207" val="0"></Value>
+<Value index="208" val="0"></Value>
+<Value index="209" val="0"></Value>
+<Value index="210" val="0"></Value>
+<Value index="211" val="0"></Value>
+<Value index="212" val="0"></Value>
+<Value index="213" val="0"></Value>
+<Value index="214" val="0"></Value>
+<Value index="215" val="0"></Value>
+<Value index="216" val="0"></Value>
+<Value index="217" val="0"></Value>
+<Value index="218" val="0"></Value>
+<Value index="219" val="0"></Value>
+<Value index="220" val="0"></Value>
+<Value index="221" val="0"></Value>
+<Value index="222" val="0"></Value>
+<Value index="223" val="0"></Value>
+<Value index="224" val="0"></Value>
+<Value index="225" val="0"></Value>
+<Value index="226" val="0"></Value>
+<Value index="227" val="0"></Value>
+<Value index="228" val="0"></Value>
+<Value index="229" val="0"></Value>
+<Value index="230" val="0"></Value>
+<Value index="231" val="0"></Value>
+<Value index="232" val="0"></Value>
+<Value index="233" val="0"></Value>
+<Value index="234" val="0"></Value>
+<Value index="235" val="0"></Value>
+<Value index="236" val="0"></Value>
+<Value index="237" val="0"></Value>
+<Value index="238" val="0"></Value>
+<Value index="239" val="0"></Value>
+<Value index="240" val="0"></Value>
+<Value index="241" val="0"></Value>
+<Value index="242" val="0"></Value>
+<Value index="243" val="0"></Value>
+<Value index="244" val="0"></Value>
+<Value index="245" val="0"></Value>
+<Value index="246" val="0"></Value>
+<Value index="247" val="0"></Value>
+<Value index="248" val="0"></Value>
+<Value index="249" val="0"></Value>
+<Value index="250" val="0"></Value>
+<Value index="251" val="0"></Value>
+<Value index="252" val="0"></Value>
+<Value index="253" val="0"></Value>
+<Value index="254" val="0"></Value>
+<Value index="255" val="0"></Value>
+</Property>
+<Property name="FileName" default="0" position="8" flags="7" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+</PropList>
+<PropList name="LUT-3" default="0" position="3" flags="7" size="10" parent="none">
+<Property name="Gamma" default="0" position="0" flags="7" size="1" formatString="%f" valType="2">
+<Value index="0" val="1.800000"></Value>
+</Property>
+<Property name="GammaAlpha" default="0" position="1" flags="7" size="1" formatString="%f" valType="2">
+<Value index="0" val="0.000000"></Value>
+</Property>
+<Property name="GammaMode" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="LinearStart"></Value>
+</Property>
+<Property name="GammaStartThreshold" default="0" position="3" flags="263" size="1" formatString="%d" valType="1">
+<Value index="0" val="12"></Value>
+</Property>
+<Property name="ValueCount" default="1" position="4" flags="259" size="1" formatString="%d" valType="1">
+<Value index="0" val="2"></Value>
+</Property>
+<Property name="InputValues" default="0" position="5" flags="263" size="2" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+<Value index="1" val="255"></Value>
+</Property>
+<Property name="OutputValues" default="0" position="6" flags="263" size="2" formatString="%d" valType="1">
+<Value index="0" val="255"></Value>
+<Value index="1" val="0"></Value>
+</Property>
+<Property name="DirectValues" default="0" position="7" flags="263" size="256" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+<Value index="1" val="0"></Value>
+<Value index="2" val="0"></Value>
+<Value index="3" val="0"></Value>
+<Value index="4" val="0"></Value>
+<Value index="5" val="0"></Value>
+<Value index="6" val="0"></Value>
+<Value index="7" val="0"></Value>
+<Value index="8" val="0"></Value>
+<Value index="9" val="0"></Value>
+<Value index="10" val="0"></Value>
+<Value index="11" val="0"></Value>
+<Value index="12" val="0"></Value>
+<Value index="13" val="0"></Value>
+<Value index="14" val="0"></Value>
+<Value index="15" val="0"></Value>
+<Value index="16" val="0"></Value>
+<Value index="17" val="0"></Value>
+<Value index="18" val="0"></Value>
+<Value index="19" val="0"></Value>
+<Value index="20" val="0"></Value>
+<Value index="21" val="0"></Value>
+<Value index="22" val="0"></Value>
+<Value index="23" val="0"></Value>
+<Value index="24" val="0"></Value>
+<Value index="25" val="0"></Value>
+<Value index="26" val="0"></Value>
+<Value index="27" val="0"></Value>
+<Value index="28" val="0"></Value>
+<Value index="29" val="0"></Value>
+<Value index="30" val="0"></Value>
+<Value index="31" val="0"></Value>
+<Value index="32" val="0"></Value>
+<Value index="33" val="0"></Value>
+<Value index="34" val="0"></Value>
+<Value index="35" val="0"></Value>
+<Value index="36" val="0"></Value>
+<Value index="37" val="0"></Value>
+<Value index="38" val="0"></Value>
+<Value index="39" val="0"></Value>
+<Value index="40" val="0"></Value>
+<Value index="41" val="0"></Value>
+<Value index="42" val="0"></Value>
+<Value index="43" val="0"></Value>
+<Value index="44" val="0"></Value>
+<Value index="45" val="0"></Value>
+<Value index="46" val="0"></Value>
+<Value index="47" val="0"></Value>
+<Value index="48" val="0"></Value>
+<Value index="49" val="0"></Value>
+<Value index="50" val="0"></Value>
+<Value index="51" val="0"></Value>
+<Value index="52" val="0"></Value>
+<Value index="53" val="0"></Value>
+<Value index="54" val="0"></Value>
+<Value index="55" val="0"></Value>
+<Value index="56" val="0"></Value>
+<Value index="57" val="0"></Value>
+<Value index="58" val="0"></Value>
+<Value index="59" val="0"></Value>
+<Value index="60" val="0"></Value>
+<Value index="61" val="0"></Value>
+<Value index="62" val="0"></Value>
+<Value index="63" val="0"></Value>
+<Value index="64" val="0"></Value>
+<Value index="65" val="0"></Value>
+<Value index="66" val="0"></Value>
+<Value index="67" val="0"></Value>
+<Value index="68" val="0"></Value>
+<Value index="69" val="0"></Value>
+<Value index="70" val="0"></Value>
+<Value index="71" val="0"></Value>
+<Value index="72" val="0"></Value>
+<Value index="73" val="0"></Value>
+<Value index="74" val="0"></Value>
+<Value index="75" val="0"></Value>
+<Value index="76" val="0"></Value>
+<Value index="77" val="0"></Value>
+<Value index="78" val="0"></Value>
+<Value index="79" val="0"></Value>
+<Value index="80" val="0"></Value>
+<Value index="81" val="0"></Value>
+<Value index="82" val="0"></Value>
+<Value index="83" val="0"></Value>
+<Value index="84" val="0"></Value>
+<Value index="85" val="0"></Value>
+<Value index="86" val="0"></Value>
+<Value index="87" val="0"></Value>
+<Value index="88" val="0"></Value>
+<Value index="89" val="0"></Value>
+<Value index="90" val="0"></Value>
+<Value index="91" val="0"></Value>
+<Value index="92" val="0"></Value>
+<Value index="93" val="0"></Value>
+<Value index="94" val="0"></Value>
+<Value index="95" val="0"></Value>
+<Value index="96" val="0"></Value>
+<Value index="97" val="0"></Value>
+<Value index="98" val="0"></Value>
+<Value index="99" val="0"></Value>
+<Value index="100" val="0"></Value>
+<Value index="101" val="0"></Value>
+<Value index="102" val="0"></Value>
+<Value index="103" val="0"></Value>
+<Value index="104" val="0"></Value>
+<Value index="105" val="0"></Value>
+<Value index="106" val="0"></Value>
+<Value index="107" val="0"></Value>
+<Value index="108" val="0"></Value>
+<Value index="109" val="0"></Value>
+<Value index="110" val="0"></Value>
+<Value index="111" val="0"></Value>
+<Value index="112" val="0"></Value>
+<Value index="113" val="0"></Value>
+<Value index="114" val="0"></Value>
+<Value index="115" val="0"></Value>
+<Value index="116" val="0"></Value>
+<Value index="117" val="0"></Value>
+<Value index="118" val="0"></Value>
+<Value index="119" val="0"></Value>
+<Value index="120" val="0"></Value>
+<Value index="121" val="0"></Value>
+<Value index="122" val="0"></Value>
+<Value index="123" val="0"></Value>
+<Value index="124" val="0"></Value>
+<Value index="125" val="0"></Value>
+<Value index="126" val="0"></Value>
+<Value index="127" val="0"></Value>
+<Value index="128" val="0"></Value>
+<Value index="129" val="0"></Value>
+<Value index="130" val="0"></Value>
+<Value index="131" val="0"></Value>
+<Value index="132" val="0"></Value>
+<Value index="133" val="0"></Value>
+<Value index="134" val="0"></Value>
+<Value index="135" val="0"></Value>
+<Value index="136" val="0"></Value>
+<Value index="137" val="0"></Value>
+<Value index="138" val="0"></Value>
+<Value index="139" val="0"></Value>
+<Value index="140" val="0"></Value>
+<Value index="141" val="0"></Value>
+<Value index="142" val="0"></Value>
+<Value index="143" val="0"></Value>
+<Value index="144" val="0"></Value>
+<Value index="145" val="0"></Value>
+<Value index="146" val="0"></Value>
+<Value index="147" val="0"></Value>
+<Value index="148" val="0"></Value>
+<Value index="149" val="0"></Value>
+<Value index="150" val="0"></Value>
+<Value index="151" val="0"></Value>
+<Value index="152" val="0"></Value>
+<Value index="153" val="0"></Value>
+<Value index="154" val="0"></Value>
+<Value index="155" val="0"></Value>
+<Value index="156" val="0"></Value>
+<Value index="157" val="0"></Value>
+<Value index="158" val="0"></Value>
+<Value index="159" val="0"></Value>
+<Value index="160" val="0"></Value>
+<Value index="161" val="0"></Value>
+<Value index="162" val="0"></Value>
+<Value index="163" val="0"></Value>
+<Value index="164" val="0"></Value>
+<Value index="165" val="0"></Value>
+<Value index="166" val="0"></Value>
+<Value index="167" val="0"></Value>
+<Value index="168" val="0"></Value>
+<Value index="169" val="0"></Value>
+<Value index="170" val="0"></Value>
+<Value index="171" val="0"></Value>
+<Value index="172" val="0"></Value>
+<Value index="173" val="0"></Value>
+<Value index="174" val="0"></Value>
+<Value index="175" val="0"></Value>
+<Value index="176" val="0"></Value>
+<Value index="177" val="0"></Value>
+<Value index="178" val="0"></Value>
+<Value index="179" val="0"></Value>
+<Value index="180" val="0"></Value>
+<Value index="181" val="0"></Value>
+<Value index="182" val="0"></Value>
+<Value index="183" val="0"></Value>
+<Value index="184" val="0"></Value>
+<Value index="185" val="0"></Value>
+<Value index="186" val="0"></Value>
+<Value index="187" val="0"></Value>
+<Value index="188" val="0"></Value>
+<Value index="189" val="0"></Value>
+<Value index="190" val="0"></Value>
+<Value index="191" val="0"></Value>
+<Value index="192" val="0"></Value>
+<Value index="193" val="0"></Value>
+<Value index="194" val="0"></Value>
+<Value index="195" val="0"></Value>
+<Value index="196" val="0"></Value>
+<Value index="197" val="0"></Value>
+<Value index="198" val="0"></Value>
+<Value index="199" val="0"></Value>
+<Value index="200" val="0"></Value>
+<Value index="201" val="0"></Value>
+<Value index="202" val="0"></Value>
+<Value index="203" val="0"></Value>
+<Value index="204" val="0"></Value>
+<Value index="205" val="0"></Value>
+<Value index="206" val="0"></Value>
+<Value index="207" val="0"></Value>
+<Value index="208" val="0"></Value>
+<Value index="209" val="0"></Value>
+<Value index="210" val="0"></Value>
+<Value index="211" val="0"></Value>
+<Value index="212" val="0"></Value>
+<Value index="213" val="0"></Value>
+<Value index="214" val="0"></Value>
+<Value index="215" val="0"></Value>
+<Value index="216" val="0"></Value>
+<Value index="217" val="0"></Value>
+<Value index="218" val="0"></Value>
+<Value index="219" val="0"></Value>
+<Value index="220" val="0"></Value>
+<Value index="221" val="0"></Value>
+<Value index="222" val="0"></Value>
+<Value index="223" val="0"></Value>
+<Value index="224" val="0"></Value>
+<Value index="225" val="0"></Value>
+<Value index="226" val="0"></Value>
+<Value index="227" val="0"></Value>
+<Value index="228" val="0"></Value>
+<Value index="229" val="0"></Value>
+<Value index="230" val="0"></Value>
+<Value index="231" val="0"></Value>
+<Value index="232" val="0"></Value>
+<Value index="233" val="0"></Value>
+<Value index="234" val="0"></Value>
+<Value index="235" val="0"></Value>
+<Value index="236" val="0"></Value>
+<Value index="237" val="0"></Value>
+<Value index="238" val="0"></Value>
+<Value index="239" val="0"></Value>
+<Value index="240" val="0"></Value>
+<Value index="241" val="0"></Value>
+<Value index="242" val="0"></Value>
+<Value index="243" val="0"></Value>
+<Value index="244" val="0"></Value>
+<Value index="245" val="0"></Value>
+<Value index="246" val="0"></Value>
+<Value index="247" val="0"></Value>
+<Value index="248" val="0"></Value>
+<Value index="249" val="0"></Value>
+<Value index="250" val="0"></Value>
+<Value index="251" val="0"></Value>
+<Value index="252" val="0"></Value>
+<Value index="253" val="0"></Value>
+<Value index="254" val="0"></Value>
+<Value index="255" val="0"></Value>
+</Property>
+<Property name="FileName" default="0" position="8" flags="7" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+</PropList>
+</PropList>
+</PropList>
+<PropList name="ChannelSplit" default="0" position="21" flags="3" size="4" parent="none">
+<Property name="ChannelSplitEnable" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="ChannelSplitMode" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Vertical"></Value>
+</Property>
+<Property name="ChannelSplitChannelIndex" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+</Property>
+<Property name="ChannelSplitDeinterlaceEnable" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+</PropList>
+<PropList name="WatermarkGenerator" default="0" position="22" flags="3" size="9" parent="none">
+<Property name="WatermarkEnable" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="WatermarkLayout" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Cross-hair"></Value>
+</Property>
+<Property name="WatermarkPositionMode" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Centered"></Value>
+</Property>
+<Property name="WatermarkPositionUserX" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+</Property>
+<Property name="WatermarkPositionUserY" default="0" position="4" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+</Property>
+<Property name="WatermarkColorMode" default="0" position="5" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Standard"></Value>
+</Property>
+<Property name="WatermarkColorUser" default="0" position="6" flags="7" size="4" formatString="0x%04x" valType="1">
+<Value index="0" val="0x0000"></Value>
+<Value index="1" val="0x0000"></Value>
+<Value index="2" val="0x0000"></Value>
+<Value index="3" val="0x0000"></Value>
+</Property>
+<Property name="WatermarkThicknessMode" default="0" position="7" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Standard"></Value>
+</Property>
+<Property name="WatermarkThicknessUser" default="0" position="8" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="1"></Value>
+</Property>
+</PropList>
+<PropList name="Rotation" default="0" position="23" flags="3" size="2" parent="none">
+<Property name="RotationEnable" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="RotationAngle" default="0" position="1" flags="7" size="1" formatString="%.3f" valType="2">
+<Value index="0" val="90.000"></Value>
+</Property>
+</PropList>
+</PropList>
+<PropList name="ImageDestination" default="0" position="4" flags="3" size="5" parent="none">
+<Property name="PixelFormat" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Mono8"></Value>
+</Property>
+<Property name="ScalerMode" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="ScalerInterpolationMode" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="NearestNeighbor"></Value>
+</Property>
+<Property name="ImageWidth" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="640"></Value>
+</Property>
+<Property name="ImageHeight" default="0" position="4" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="480"></Value>
+</Property>
+</PropList>
+<PropList name="RequestInfo" default="0" position="5" flags="3" size="9" parent="none">
+<Property name="FrameID" default="0" position="3" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="ExposeStart_us" default="0" position="4" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="ExposeTime_us" default="0" position="5" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="Gain_dB" default="0" position="6" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="VideoChannel" default="0" position="7" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="MissingData_pc" default="0" position="8" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+</PropList>
+</PropList>
+</PropList>
+<PropList name="DeviceSpecificData" default="0" position="4" flags="3" size="3" parent="none">
+<Property name="DefectiveFilterParameter" default="0" position="0" flags="2055" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+<Property name="FlatFieldFilterParameter" default="0" position="1" flags="2055" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+<Property name="DarkCurrentFilterParameter" default="0" position="2" flags="2055" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+</PropList>
+</PropList>
+<PropList name="System" default="0" position="5" flags="3" size="12" parent="none">
+<Property name="WorkerPriority" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="TimeCritical"></Value>
+</Property>
+<Property name="RequestCount" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="10"></Value>
+</Property>
+<PropList name="MemoryInit" default="0" position="2" flags="3" size="6" parent="none">
+<Property name="MemoryInitEnable" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="Off"></Value>
+</Property>
+<Property name="MemoryInitMode" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="FixedValue"></Value>
+</Property>
+<Property name="MemoryInitValue" default="0" position="2" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="0"></Value>
+</Property>
+<Property name="MemoryInitPattern" default="0" position="3" flags="2055" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+<Property name="MemoryInitPatternFileName" default="0" position="4" flags="2055" size="1" formatString="%s" valType="4">
+<Value index="0" val=""></Value>
+</Property>
+</PropList>
+<PropList name="ImageProcessingControl" default="0" position="3" flags="3" size="2" parent="none">
+<Property name="ImageProcessingOptimization" default="0" position="0" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="MinimizeMemoryUsage"></Value>
+</Property>
+<Property name="ImageProcessingMode" default="0" position="1" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="ProcessLatestOnly"></Value>
+</Property>
+</PropList>
+<Property name="FeaturePollingEnable" default="0" position="6" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="On"></Value>
+</Property>
+<Property name="FeaturePollingInterval_ms" default="0" position="7" flags="7" size="1" formatString="%d ms" valType="1">
+<Value index="0" val="200 ms"></Value>
+</Property>
+<Property name="MethodPollingInterval_ms" default="0" position="8" flags="7" size="1" formatString="%d ms" valType="1">
+<Value index="0" val="100 ms"></Value>
+</Property>
+<Property name="MethodPollingMaxRetryCount" default="0" position="9" flags="7" size="1" formatString="%d" valType="1">
+<Value index="0" val="5"></Value>
+</Property>
+<Property name="AcquisitionIdleTimeMax_ms" default="0" position="10" flags="7" size="1" formatString="%d ms" valType="1">
+<Value index="0" val="150 ms"></Value>
+</Property>
+</PropList>
+</PropList>
diff --git a/src/mvbluefox3_camera_driver.cpp b/src/mvbluefox3_camera_driver.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..eaedd591b9621bc226283dd44ae9dc0b7d95e638
--- /dev/null
+++ b/src/mvbluefox3_camera_driver.cpp
@@ -0,0 +1,372 @@
+#include "mvbluefox3_camera_driver.h"
+
+Mvbluefox3CameraDriver::Mvbluefox3CameraDriver(void)
+{
+  this->num_cams = 1;
+  this->ini_user_params = false;
+  this->ini_dynrec = true;
+}
+
+Mvbluefox3CameraDriver::~Mvbluefox3CameraDriver(void)
+{
+  for (int ii = 0; ii < this->num_cams; ++ii)
+    DelPtr(this->vcam_ptr[ii]);
+}
+
+void Mvbluefox3CameraDriver::ResizeObjs(void)
+{
+  this->vcam_ptr.resize(this->num_cams);  // Camera pointers. 
+  this->vparams.resize(this->num_cams);   // Camera parameters.
+  this->vserial.resize(this->num_cams);   // Serial numbers.
+  this->vframe_id.resize(this->num_cams); // Frame ids. 
+  this->vcam_name.resize(this->num_cams); // Camera names.
+  this->vparams_path.resize(this->num_cams); // Parameters' paths.
+}
+
+bool Mvbluefox3CameraDriver::openDriver(void)
+{
+  try 
+  {
+    for (int ii = 0; ii < this->num_cams; ++ii)
+    {
+      this->vcam_ptr[ii] = NULL;
+
+      if( !this->vserial[ii].empty() )
+      {
+        std::cout << "[mvBlueFOX3]: Trying to open device with serial: " << this->vserial[ii] << std::endl;
+
+        if (devMgr.getDeviceBySerial(this->vserial[ii]) == 0)
+        {
+          std::cerr <<  this->vcam_name[ii] << " not found! Unable to continue. " << std::endl;
+          return true;
+        }
+        else
+        {
+          this->vcam_ptr[ii] = new CMvbluefox3::CMvbluefox3(devMgr.getDeviceBySerial(this->vserial[ii]),this->vparams_path[ii]);
+        }
+      }
+      else
+      {
+        std::cerr << this->vcam_name[ii] << " not found because serial number is not specified!" << std::endl;
+        return true;
+      }
+    }
+  }catch (CMvbluefox3::CmvBlueFOX3Exception& e) 
+  {
+    std::cerr << e.what() << std::endl;
+    return false;
+  }   
+  std::cout << "[mvBlueFOX3]: All cameras successfully opened." << std::endl;  
+
+  // Initialize parameters set from ROS node.
+  if (this->ini_user_params)
+  {
+    for (int ii = 0; ii < this->num_cams; ++ii)
+      SetConfig(ii);
+    this->ini_user_params = false;
+  }
+  return true;
+}
+
+bool Mvbluefox3CameraDriver::closeDriver(void)
+{
+  try 
+  {
+    for (int ii = 0; ii < this->num_cams; ++ii)
+      this->vcam_ptr[ii]->CloseDevice();
+    std::cout << "[mvBlueFOX3]: Driver closed." << std::endl;
+  }catch (CMvbluefox3::CmvBlueFOX3Exception& e) 
+  {
+    std::cerr << e.what() << std::endl;
+  }   
+  return true;
+}
+
+bool Mvbluefox3CameraDriver::startDriver(void)
+{
+  return true;
+}
+
+bool Mvbluefox3CameraDriver::stopDriver(void)
+{
+  return true;
+}
+
+void Mvbluefox3CameraDriver::config_update(Config& new_cfg, uint32_t level)
+{
+  this->lock();
+  
+  switch(this->getState())
+  {
+    case Mvbluefox3CameraDriver::CLOSED: 
+      break;
+
+    case Mvbluefox3CameraDriver::OPENED:
+
+      // Initialize dynamic reconfigure with first camera
+      if (this->ini_dynrec && this->num_cams > 0)
+      {
+        GetConfig(0);
+        new_cfg = ParamsToDynRec(0,this->vparams[0]);
+        this->ini_dynrec = false;
+      }
+
+      // Set new config is requested
+      if (new_cfg.apply_cfg)
+      { 
+        for (int ii = 0; ii < this->num_cams; ++ii)
+        {
+          if (this->vcam_name[ii].compare(new_cfg.cam_name) == 0)
+          {
+            // Fill parameters
+            this->vparams[ii] = DynRecToParams(new_cfg);
+            SetConfig(ii);
+            GetConfig(ii);
+            new_cfg = ParamsToDynRec(ii,this->vparams[ii]);
+          }
+        }
+        new_cfg.apply_cfg = false;
+      }
+      break;
+
+    case Mvbluefox3CameraDriver::RUNNING:
+      break;
+  }
+
+  // save the current configuration
+  this->config_=new_cfg;
+
+  this->unlock();
+}
+
+CMvbluefox3::CParams Mvbluefox3CameraDriver::DynRecToParams(iri_mvbluefox3_camera::Mvbluefox3CameraConfig &cfg)
+{
+  CMvbluefox3::CParams p;
+
+  p.pixel_format = PfToCodes(cfg.pixel_format);
+  p.width = cfg.width;
+  p.height = cfg.height;
+  p.img_rot_angle = cfg.img_rot_angle;
+  p.mirror = cfg.mirror;
+  p.set_aoi = cfg.set_aoi;
+  p.aoi_width = cfg.aoi_width;
+  p.aoi_height = cfg.aoi_height;
+  p.aoi_start_x = cfg.aoi_start_x;
+  p.aoi_start_y = cfg.aoi_start_y;
+  p.h_binning_enbl = cfg.h_binning_enbl;
+  p.h_binning = cfg.h_binning;
+  p.v_binning_enbl = cfg.v_binning_enbl;
+  p.v_binning = cfg.v_binning;
+  p.frame_rate  = cfg.frame_rate;
+  p.pixel_clock = cfg.pixel_clock;
+  p.req_timeout = cfg.req_timeout;
+  p.auto_ctrl_enbl = cfg.auto_ctrl_enbl;
+  p.auto_ctrl_speed = cfg.auto_ctrl_speed;
+  p.auto_expose = cfg.auto_expose;
+  p.auto_expose_upperlimit = cfg.auto_expose_upperlimit;
+  p.auto_expose_des_grey_val = cfg.auto_expose_des_grey_val;
+  p.expose_us = cfg.expose_us;
+  p.auto_gain = cfg.auto_gain;
+  p.gain_db = cfg.gain_db;
+  p.gamma = cfg.gamma;
+  p.whiteblnce_auto_enbl = cfg.whiteblnce_auto_enbl;
+  p.wb_r_gain = cfg.wb_r_gain;
+  p.wb_b_gain = cfg.wb_b_gain;
+  p.auto_blck_level = cfg.auto_blck_level;
+  p.blck_level = cfg.blck_level;
+  p.hdr_enbl = cfg.hdr_enbl;
+  p.dark_cfilter = cfg.dark_cfilter;
+  p.twist_cfilter = cfg.twist_cfilter;
+
+  return p;
+}
+
+iri_mvbluefox3_camera::Mvbluefox3CameraConfig Mvbluefox3CameraDriver::ParamsToDynRec(const int &cam_num, const CMvbluefox3::CParams &p)
+{
+  iri_mvbluefox3_camera::Mvbluefox3CameraConfig cfg;
+
+  cfg.apply_cfg = false;
+  cfg.cam_name = this->vcam_name[cam_num];
+  cfg.pixel_format = CodesToPf(p.pixel_format);
+  cfg.width = p.width;
+  cfg.height = p.height;
+  cfg.img_rot_angle = p.img_rot_angle;
+  cfg.mirror = p.mirror;
+  cfg.set_aoi = p.set_aoi;
+  cfg.aoi_width = p.aoi_width;
+  cfg.aoi_height = p.aoi_height;
+  cfg.aoi_start_x = p.aoi_start_x;
+  cfg.aoi_start_y = p.aoi_start_y;
+  cfg.h_binning_enbl = p.h_binning_enbl;
+  cfg.h_binning = p.h_binning;
+  cfg.v_binning_enbl = p.v_binning_enbl;
+  cfg.v_binning = p.v_binning;
+  cfg.frame_rate = p.frame_rate;
+  cfg.pixel_clock = p.pixel_clock;
+  cfg.req_timeout = p.req_timeout;
+  cfg.auto_ctrl_enbl = p.auto_ctrl_enbl;
+  cfg.auto_ctrl_speed = p.auto_ctrl_speed;
+  cfg.auto_expose = p.auto_expose;
+  cfg.auto_expose_upperlimit = p.auto_expose_upperlimit;
+  cfg.auto_expose_des_grey_val = p.auto_expose_des_grey_val;
+  cfg.expose_us = p.expose_us;
+  cfg.auto_gain = p.auto_gain;
+  cfg.gain_db = p.gain_db;
+  cfg.gamma = p.gamma;
+  cfg.whiteblnce_auto_enbl = p.whiteblnce_auto_enbl;
+  cfg.wb_r_gain = p.wb_r_gain;
+  cfg.wb_b_gain = p.wb_b_gain;
+  cfg.auto_blck_level = p.auto_blck_level;
+  cfg.blck_level = p.blck_level;
+  cfg.hdr_enbl = p.hdr_enbl;
+  cfg.dark_cfilter = p.dark_cfilter;
+  cfg.twist_cfilter = p.twist_cfilter;
+
+  return cfg;  
+}
+
+
+CMvbluefox3::codings_t Mvbluefox3CameraDriver::PfToCodes(int &pf)
+{
+  CMvbluefox3::codings_t ct;
+  switch (pf)
+  {
+    case 0: ct = CMvbluefox3::raw; break;
+    case 1: ct = CMvbluefox3::mono8; break;
+    case 2: ct = CMvbluefox3::mono16; break;
+    case 3: ct = CMvbluefox3::bgr8; break;
+    case 4: ct = CMvbluefox3::bgr16; break;
+    case 5: ct = CMvbluefox3::rgb8; break;
+    case 6: ct = CMvbluefox3::yuv422; break;
+    case 7: ct = CMvbluefox3::yuv444; break;
+  }
+  return ct;
+}
+
+int Mvbluefox3CameraDriver::CodesToPf(CMvbluefox3::codings_t ct)
+{
+  int pf;
+  switch (ct)
+  {
+    case CMvbluefox3::raw: pf = 0; break;
+    case CMvbluefox3::mono8: pf = 1; break;
+    case CMvbluefox3::mono16: pf = 2; break;
+    case CMvbluefox3::bgr8: pf = 3; break;
+    case CMvbluefox3::bgr16: pf = 4; break;
+    case CMvbluefox3::rgb8: pf = 5; break;
+    case CMvbluefox3::yuv422: pf = 6; break;
+    case CMvbluefox3::yuv444: pf = 7; break;
+  }
+  return pf;
+}
+
+
+void Mvbluefox3CameraDriver::SetConfig(const int &ncam)
+{
+  try 
+  {
+    this->vcam_ptr[ncam]->SetConfig(this->vparams[ncam]);
+    std::cout << "[mvBlueFOX3]: New configuration set for " << this->vcam_name[ncam] << "." << std::endl;
+  }catch (CMvbluefox3::CmvBlueFOX3Exception& e) 
+  {
+    std::cerr << e.what() << std::endl;
+  }   
+}
+
+void Mvbluefox3CameraDriver::GetConfig(const int &ncam)
+{
+  this->vparams[ncam] = this->vcam_ptr[ncam]->GetConfig();
+}
+
+void Mvbluefox3CameraDriver::GetROSImage(const int &ncam, sensor_msgs::Image &img_msg)
+{
+  ros::Time start_time = ros::Time::now();
+
+  char *image = NULL;
+  this->vcam_ptr[ncam]->GetImage(&image);
+  GetConfig(ncam);
+  
+  std::string encoding;
+  encoding = CMvbluefox3::codings_str[this->vparams[ncam].pixel_format];
+
+  int bp = this->vcam_ptr[ncam]->GetBytesPixel();
+  int depth = this->vcam_ptr[ncam]->GetDepth();
+
+  bool ROSvalid = true;
+  switch (this->vparams[ncam].pixel_format)
+  {
+    case CMvbluefox3::raw: 
+
+      if (depth/8 == 1)
+      {
+        encoding = "8UC1";
+        switch (bp) 
+        {
+          case 1: encoding = "mono8"; break; // FIX: Should be 8UC1 but changed because cv_bridge cannot convert formats
+          case 2: encoding = "8UC2"; break;
+          case 3: encoding = "rgb8"; break;  // FIX: Should be 8UC3 but changed because cv_bridge cannot convert formats
+          case 4: encoding = "rgba8"; break; // FIX: Should be 8UC4 but changed because cv_bridge cannot convert formats
+          default: ROS_WARN("Invalid depth. Depth not implemented here."); break;
+        }
+      }
+      else if (depth/8 == 2)
+      {
+        encoding = "16UC1";
+        switch (bp) 
+        {
+          case 1: encoding = "mono16"; break; // FIX: Should be 16UC1 but changed because cv_bridge cannot convert formats
+          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; 
+    case CMvbluefox3::mono12: ROSvalid = false; break; 
+    case CMvbluefox3::mono12v1: ROSvalid = false; break; 
+    case CMvbluefox3::mono12v2: ROSvalid = false; break; 
+    case CMvbluefox3::mono14: ROSvalid = false; break; 
+    case CMvbluefox3::mono16: encoding = "16UC1"; break;
+    case CMvbluefox3::rgb8: break; 
+    case CMvbluefox3::bgr8: break; 
+    case CMvbluefox3::bgr8p: ROSvalid = false; break; 
+    case CMvbluefox3::bgra8p: ROSvalid = false; break; 
+    case CMvbluefox3::bgr10: ROSvalid = false; break; 
+    case CMvbluefox3::bgr12: ROSvalid = false; break; 
+    case CMvbluefox3::bgr14: ROSvalid = false; break; 
+    case CMvbluefox3::bgr16: encoding = "16UC3"; break; 
+    case CMvbluefox3::bgra8: ROSvalid = false; break; 
+    case CMvbluefox3::yuv411uyyvyy: ROSvalid = false; break; 
+    case CMvbluefox3::yuv422: break; 
+    case CMvbluefox3::yuv422p: ROSvalid = false; break; 
+    case CMvbluefox3::yuv42210: ROSvalid = false; break; 
+    case CMvbluefox3::yuv422uyvy: ROSvalid = false; break; 
+    case CMvbluefox3::yuv422uyvy10: ROSvalid = false; break; 
+    case CMvbluefox3::yuv444: ROSvalid = false; break; 
+    case CMvbluefox3::yuv44410p: ROSvalid = false; break; 
+    case CMvbluefox3::yuv444uyv: ROSvalid = false; break; 
+    case CMvbluefox3::yuv444uyv10: ROSvalid = false; break; 
+  }
+
+  if (!ROSvalid)
+    ROS_WARN("mvBlueFOX3 pixel format %s no valid within ROS messages.",encoding.c_str());
+
+  sensor_msgs::fillImage(img_msg, 
+    encoding, 
+    this->vparams[ncam].height,
+    this->vparams[ncam].width,
+    this->vcam_ptr[ncam]->GetImgLinePitch(),
+    image);
+
+  double req_dur_sec = (double)(this->vcam_ptr[ncam]->ReqExposeUs())*1e-6;
+  img_msg.header.stamp = start_time + ros::Duration(req_dur_sec/2.0);
+  img_msg.header.frame_id = this->vframe_id[ncam];
+
+  delete [] image;
+}
+
+
diff --git a/src/mvbluefox3_camera_driver_node.cpp b/src/mvbluefox3_camera_driver_node.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..7ad5ae4bdfc5682a35c9e1dfbc20451e6514e014
--- /dev/null
+++ b/src/mvbluefox3_camera_driver_node.cpp
@@ -0,0 +1,212 @@
+#include "mvbluefox3_camera_driver_node.h"
+
+Mvbluefox3CameraDriverNode::Mvbluefox3CameraDriverNode(ros::NodeHandle &nh) : 
+  iri_base_driver::IriBaseNodeDriver<Mvbluefox3CameraDriver>(nh),
+  it(this->public_node_handle_)
+{
+  //init class attributes if necessary
+  this->loop_rate_ = 50;//in [Hz]
+
+  // [init publishers]
+
+  this->driver_.lock();
+  this->public_node_handle_.param<int>("num_cams", this->driver_.num_cams, 1);
+
+  // Resize all objects
+  this->driver_.ResizeObjs();
+  this->camera_manager.resize(this->driver_.num_cams);
+  this->image_publisher_.resize(this->driver_.num_cams);
+  this->image_msg_.resize(this->driver_.num_cams);
+
+  for (int ii = 0; ii < this->driver_.num_cams; ++ii)
+  {
+    // Generate camera name
+    std::stringstream cn;
+    cn << "c" << ii+1;
+
+    // get camera name
+    std::string cam_name = cn.str() + "/name";
+    this->public_node_handle_.param<std::string>(cam_name, this->driver_.vcam_name[ii], "c1aa");
+
+    // generate camera manager
+    std::string cam_mgr_name = "~" + this->driver_.vcam_name[ii] + std::string("/image_raw");
+    this->camera_manager[ii] = new camera_info_manager::CameraInfoManager(cam_mgr_name);
+   
+    // get topic name adn advertise publisher
+    std::string img_name = this->driver_.vcam_name[ii] + "/image_raw";
+    this->image_publisher_[ii] = this->it.advertiseCamera(img_name, 1);
+
+    // Constant parameters
+    std::string frame_id, tf_prefix, image_cal_file;
+    std::string frame_id_name = cn.str() + "/frame_id";
+    std::string tf_prefix_name = cn.str() + "/tf_prefix";
+    std::string serial_name = cn.str() + "/serial";
+    std::string params_path_name = cn.str() + "/params_path";
+    std::string image_cal_file_name = cn.str() + "/calib_file";
+    this->public_node_handle_.param<std::string>(frame_id_name, frame_id, "");
+    this->public_node_handle_.param<std::string>(tf_prefix_name, tf_prefix, "");
+    this->driver_.vframe_id[ii] = tf_prefix + "/" + frame_id;
+    this->public_node_handle_.param<std::string>(serial_name, this->driver_.vserial[ii], "");
+    this->public_node_handle_.param<std::string>(params_path_name, this->driver_.vparams_path[ii], "");    
+    this->public_node_handle_.param<std::string>(image_cal_file_name,image_cal_file,"");
+
+    // Get calibration file
+    std::stringstream err_msg;
+    err_msg << "Invalid calibration file for " << this->driver_.vcam_name[ii];
+    if(this->camera_manager[ii]->validateURL(image_cal_file))
+    {
+      if(!this->camera_manager[ii]->loadCameraInfo(image_cal_file))
+        ROS_WARN("%s", err_msg.str().c_str());
+    }
+    else
+      ROS_WARN("%s", err_msg.str().c_str());
+
+    // Get and Set camera parameters.
+    // this function is not used here because loading parameters 
+    // from an XML file is a preferred method 
+    // (e.g. use wxPropView to store it and specify its path 
+    // in the launch file). 
+    // However in case of preferring to configure only main settings 
+    // with a simpler file, uncomment the following function (see 1) and load a YAML file in the launch file (see step 2). 
+    // An example of YAML file is added in the /params folder but hidden
+    // (.F0300141_params.yaml)
+
+    // 1) UNCOMMENT: 
+    // SetParams(this->public_node_handle_, this->driver_.vcam_name[ii]);
+    // 2) Add in the node section of launch file (example): <rosparam ns="c1"  file="$(find iri_mvbluefox3_camera)/params/F0300141_params.yaml" command="load"/>
+  }
+
+  this->driver_.unlock();
+
+  // [init subscribers]
+  
+  // [init services]
+  
+  // [init clients]
+  
+  // [init action servers]
+  
+  // [init action clients]
+}
+
+void Mvbluefox3CameraDriverNode::mainNodeThread(void)
+{
+  // [fill msg Header if necessary]
+
+  // [fill msg structures]
+
+  // Image
+  for (int ii = 0; ii < this->driver_.num_cams; ++ii)
+  {
+    this->driver_.lock();
+    this->driver_.GetROSImage(ii,this->image_msg_[ii]);
+    this->driver_.unlock();
+
+    // Camera info
+    sensor_msgs::CameraInfo camera_info = this->camera_manager[ii]->getCameraInfo();
+    camera_info.header = this->image_msg_[ii].header;
+    this->image_publisher_[ii].publish(this->image_msg_[ii],camera_info);
+  }
+
+  // [fill srv structure and make request to the server]
+  
+  // [fill action structure and make request to the action server]
+
+  // [publish messages]
+
+}
+
+/*  [subscriber callbacks] */
+
+/*  [service callbacks] */
+
+/*  [action callbacks] */
+
+/*  [action requests] */
+
+void Mvbluefox3CameraDriverNode::postNodeOpenHook(void)
+{
+}
+
+void Mvbluefox3CameraDriverNode::addNodeDiagnostics(void)
+{
+}
+
+void Mvbluefox3CameraDriverNode::addNodeOpenedTests(void)
+{
+}
+
+void Mvbluefox3CameraDriverNode::addNodeStoppedTests(void)
+{
+}
+
+void Mvbluefox3CameraDriverNode::addNodeRunningTests(void)
+{
+}
+
+void Mvbluefox3CameraDriverNode::reconfigureNodeHook(int level)
+{
+}
+
+Mvbluefox3CameraDriverNode::~Mvbluefox3CameraDriverNode(void)
+{
+  for (int ii = 0; ii < this->driver_.num_cams; ++ii)
+    this->driver_.DelPtr(this->camera_manager[ii]);
+  // [free dynamic memory]
+}
+
+// Optional function. See Class constructor.
+void Mvbluefox3CameraDriverNode::SetParams(const ros::NodeHandle &nh, const std::string &cam_name)
+{
+  std::string node_str;
+
+  for (int ii = 0; ii < this->driver_.num_cams; ++ii)
+  {
+    node_str = ros::this_node::getName() + "/" + this->driver_.vcam_name[ii] + "/";
+   
+    int pf;
+    nh.getParam(node_str + "pixel_format", pf);
+    this->driver_.vparams[ii].pixel_format = this->driver_.PfToCodes(pf);
+    nh.getParam(node_str + "width", this->driver_.vparams[ii].width);
+    nh.getParam(node_str + "height", this->driver_.vparams[ii].height);
+    nh.getParam(node_str + "img_rot_angle", this->driver_.vparams[ii].img_rot_angle);
+    nh.getParam(node_str + "mirror", this->driver_.vparams[ii].mirror);
+    nh.getParam(node_str + "set_aoi", this->driver_.vparams[ii].set_aoi);
+    nh.getParam(node_str + "aoi_width", this->driver_.vparams[ii].aoi_width);
+    nh.getParam(node_str + "aoi_height", this->driver_.vparams[ii].aoi_height);
+    nh.getParam(node_str + "aoi_start_x", this->driver_.vparams[ii].aoi_start_x);
+    nh.getParam(node_str + "aoi_start_y", this->driver_.vparams[ii].aoi_start_y);
+    nh.getParam(node_str + "h_binning_enbl", this->driver_.vparams[ii].h_binning_enbl);
+    nh.getParam(node_str + "h_binning", this->driver_.vparams[ii].h_binning);
+    nh.getParam(node_str + "v_binning_enbl", this->driver_.vparams[ii].v_binning_enbl);
+    nh.getParam(node_str + "v_binning", this->driver_.vparams[ii].v_binning);
+    nh.getParam(node_str + "frame_rate", this->driver_.vparams[ii].frame_rate);
+    nh.getParam(node_str + "pixel_clock", this->driver_.vparams[ii].pixel_clock);
+    nh.getParam(node_str + "req_timeout", this->driver_.vparams[ii].req_timeout);
+    nh.getParam(node_str + "auto_ctrl_enbl", this->driver_.vparams[ii].auto_ctrl_enbl);
+    nh.getParam(node_str + "auto_ctrl_speed", this->driver_.vparams[ii].auto_ctrl_speed);
+    nh.getParam(node_str + "auto_expose", this->driver_.vparams[ii].auto_expose);
+    nh.getParam(node_str + "auto_expose_upperlimit", this->driver_.vparams[ii].auto_expose_upperlimit);
+    nh.getParam(node_str + "auto_expose_des_grey_val", this->driver_.vparams[ii].auto_expose_des_grey_val);
+    nh.getParam(node_str + "expose_us", this->driver_.vparams[ii].expose_us);
+    nh.getParam(node_str + "auto_gain", this->driver_.vparams[ii].auto_gain);
+    nh.getParam(node_str + "gain_db", this->driver_.vparams[ii].gain_db);
+    nh.getParam(node_str + "gamma", this->driver_.vparams[ii].gamma);
+    nh.getParam(node_str + "whiteblnce_auto_enbl", this->driver_.vparams[ii].whiteblnce_auto_enbl);
+    nh.getParam(node_str + "wb_r_gain", this->driver_.vparams[ii].wb_r_gain);
+    nh.getParam(node_str + "wb_b_gain", this->driver_.vparams[ii].wb_b_gain);
+    nh.getParam(node_str + "blck_level", this->driver_.vparams[ii].blck_level);
+    nh.getParam(node_str + "auto_blck_level", this->driver_.vparams[ii].auto_blck_level);
+    nh.getParam(node_str + "hdr_enbl", this->driver_.vparams[ii].hdr_enbl);
+    nh.getParam(node_str + "dark_cfilter", this->driver_.vparams[ii].dark_cfilter);
+    nh.getParam(node_str + "twist_cfilter", this->driver_.vparams[ii].twist_cfilter);
+  }
+
+  this->driver_.ini_user_params = true;
+}
+
+/* main function */
+int main(int argc,char *argv[])
+{
+  return driver_base::main<Mvbluefox3CameraDriverNode>(argc, argv, "mvbluefox3_camera_driver_node");
+}