From 1de50a48031c33d404174b56100f11a65d4a1a07 Mon Sep 17 00:00:00 2001 From: Angel Santamaria-Navarro <asantamaria@iri.upc.edu> Date: Thu, 15 Dec 2016 17:20:52 +0100 Subject: [PATCH] almost working. to be solved naming in launch and verify parameters --- cfg/Mvbluefox3Camera.cfg | 16 +---- include/mvbluefox3_camera_driver.h | 71 ++++++++++---------- include/mvbluefox3_camera_driver_node.h | 12 ++-- launch/iri_mvbluefox3_camera.launch | 28 ++++---- params/F0300123_calib.yaml | 21 ++++++ params/F0300123_params.yaml | 45 +++++++++++++ params/F0300141_calib.yaml | 2 +- params/F0300141_params.yaml | 86 +++++++++++++------------ src/mvbluefox3_camera_driver.cpp | 50 +++++++++----- src/mvbluefox3_camera_driver_node.cpp | 71 ++++++++++++++++++-- 10 files changed, 268 insertions(+), 134 deletions(-) create mode 100644 params/F0300123_calib.yaml create mode 100644 params/F0300123_params.yaml diff --git a/cfg/Mvbluefox3Camera.cfg b/cfg/Mvbluefox3Camera.cfg index 0dc19fe..ac3bd02 100755 --- a/cfg/Mvbluefox3Camera.cfg +++ b/cfg/Mvbluefox3Camera.cfg @@ -68,7 +68,7 @@ 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", "cam1") +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) @@ -121,18 +121,4 @@ gen.add("dark_cfilter", int_t, SensorLevels.RECONFIGURE_STOP, "Da 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 index 41a6ee1..1d07318 100644 --- a/include/mvbluefox3_camera_driver.h +++ b/include/mvbluefox3_camera_driver.h @@ -61,21 +61,7 @@ class Mvbluefox3CameraDriver : public iri_base_driver::IriBaseDriver std::vector<CMvbluefox3::CMvbluefox3*> vcam_ptr; // Camera pointer. - std::vector<CMvbluefox3::CParams> vparams; // Camera parameters. - - /** - * \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); + bool ini_dynrec; // To control parameters initialization after device is found. /** * \brief Dynamic reconfigure to camera parameters @@ -89,28 +75,17 @@ class Mvbluefox3CameraDriver : public iri_base_driver::IriBaseDriver * * Camera parameters to dynamic reconfigure. */ - iri_mvbluefox3_camera::Mvbluefox3CameraConfig ParamsToDynRec(CMvbluefox3::CParams ¶ms); - - /** - * \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); + 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. + 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<CMvbluefox3::CParams> vparams; // Camera parameters. + + bool initialize; // To control parameters initialization after device is found. /** * \brief define config type @@ -215,6 +190,34 @@ class Mvbluefox3CameraDriver : public iri_base_driver::IriBaseDriver */ 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 * diff --git a/include/mvbluefox3_camera_driver_node.h b/include/mvbluefox3_camera_driver_node.h index 7019523..d84d3be 100644 --- a/include/mvbluefox3_camera_driver_node.h +++ b/include/mvbluefox3_camera_driver_node.h @@ -33,9 +33,6 @@ // [publisher subscriber headers] #include <camera_info_manager/camera_info_manager.h> #include <image_transport/image_transport.h> -// // Uncomment to use the openCV <-> ROS bridge -// //#include <cv_bridge/cv_bridge.h> -// #include <sensor_msgs/Image.h> // [service client headers] @@ -64,14 +61,19 @@ class Mvbluefox3CameraDriverNode : public iri_base_driver::IriBaseNodeDriver<Mvb // [publisher attributes] - // Uncomment to use the openCV <-> ROS bridge - //cv_bridge::CvImagePtr cv_image_; 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] diff --git a/launch/iri_mvbluefox3_camera.launch b/launch/iri_mvbluefox3_camera.launch index e0f4b27..bc58d84 100644 --- a/launch/iri_mvbluefox3_camera.launch +++ b/launch/iri_mvbluefox3_camera.launch @@ -1,6 +1,7 @@ <!DOCTYPE html> <launch> + <arg name="num_cams" default="1" /> <arg name="cam1_name" default="cam1" /> <arg name="cam2_name" default="cam2" /> @@ -9,26 +10,25 @@ type="iri_mvbluefox3_camera" output="screen"> - <param name="num_cams" value="2"/> + <param name="num_cams" value="$(arg num_cams)"/> <param name="cam1_name" value="$(arg cam1_name)"/> - <param name="$(arg cam1_name)/serial" value="F0300141"/> - <param name="$(arg cam1_name)/frame_id" value="mvBlueFOX3_camera"/> - <param name="$(arg cam1_name)/tf_preix" value=""/> - <param name="$(arg cam1_name)/calibration_file" value="$(find iri_mvbluefox3_camera)/params/F0300141_calib.yaml"/> + <param name="$(arg cam1_name)/calibration_file" value="file://$(find iri_mvbluefox3_camera)/params/F0300141_calib.yaml"/> <rosparam command="load" file="$(find iri_mvbluefox3_camera)/params/F0300141_params.yaml" /> <param name="cam2_name" value="$(arg cam2_name)"/> - <param name="$(arg cam2_name)/serial" value="F0300123"/> - <param name="$(arg cam2_name)/frame_id" value="mvBlueFOX3_camera"/> - <param name="$(arg cam2_name)/tf_preix" value=""/> - <param name="$(arg cam2_name)/calibration_file" value="$(find iri_mvbluefox3_camera)/params/F0300141_calib.yaml"/> + <param name="$(arg cam2_name)/calibration_file" value="file://$(find iri_mvbluefox3_camera)/params/F0300123_calib.yaml"/> + <rosparam command="load" file="$(find iri_mvbluefox3_camera)/params/F0300123_params.yaml" /> </node> -<!-- <node pkg="image_view" - type="image_view" - name="image_view" > - <remap from="/image" to="/iri_mvbluefox3_camera/image_raw"/> - </node>--> + <!-- ########## VISUALIZATION ##########--> + <node pkg="image_view" type="image_view" name="image_view_$(arg cam1_name)" > + <remap from="/image" to="/iri_mvbluefox3_camera/$(arg cam1_name)/image_raw"/> + </node> + +<!-- <node pkg="image_view" type="image_view" name="image_view_$(arg cam2_name)" > + <remap from="/image" to="/iri_mvbluefox3_camera/$(arg cam2_name)/image_raw"/> + </node> + --> </launch> diff --git a/params/F0300123_calib.yaml b/params/F0300123_calib.yaml new file mode 100644 index 0000000..f233f44 --- /dev/null +++ b/params/F0300123_calib.yaml @@ -0,0 +1,21 @@ +image_width: 1280 +image_height: 960 +camera_name: camera +camera_matrix: + rows: 3 + cols: 3 + data: [1280, 0, 960, 0, 1280, 960, 0, 0, 1] +distortion_model: plumb_bob +distortion_coefficients: + rows: 1 + cols: 5 + data: [0, 0, 0, 0, 0] +rectification_matrix: + rows: 3 + cols: 3 + data: [1, 0, 0, 0, 1, 0, 0, 0, 1] +projection_matrix: + rows: 3 + cols: 4 + data: [1280, 0, 960, 0, 0, 1280, 960, 0, 0, 0, 1, 0] + \ No newline at end of file diff --git a/params/F0300123_params.yaml b/params/F0300123_params.yaml new file mode 100644 index 0000000..4751bd3 --- /dev/null +++ b/params/F0300123_params.yaml @@ -0,0 +1,45 @@ +cam2: + serial: F0300123 + frame_id: mvbluefox3_F0300123 + 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/F0300141_calib.yaml b/params/F0300141_calib.yaml index af01efb..f233f44 100644 --- a/params/F0300141_calib.yaml +++ b/params/F0300141_calib.yaml @@ -1,6 +1,6 @@ image_width: 1280 image_height: 960 -camera_name: mvBlueFOX3_F0300141 +camera_name: camera camera_matrix: rows: 3 cols: 3 diff --git a/params/F0300141_params.yaml b/params/F0300141_params.yaml index dbca35b..ebc49a6 100644 --- a/params/F0300141_params.yaml +++ b/params/F0300141_params.yaml @@ -1,43 +1,45 @@ -serial: F0300141 -frame_id: mvbluefox3_camera +cam1: + serial: F0300141 + frame_id: mvbluefox3_F0300141 + tf_preix: "" -#Image format -pixel_format: mono8 -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 + #Image format + pixel_format: 3 # 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/src/mvbluefox3_camera_driver.cpp b/src/mvbluefox3_camera_driver.cpp index c80012b..5c57a20 100644 --- a/src/mvbluefox3_camera_driver.cpp +++ b/src/mvbluefox3_camera_driver.cpp @@ -3,6 +3,8 @@ Mvbluefox3CameraDriver::Mvbluefox3CameraDriver(void) { this->num_cams = 1; + this->initialize = true; + this->ini_dynrec = true; } Mvbluefox3CameraDriver::~Mvbluefox3CameraDriver(void) @@ -34,7 +36,8 @@ bool Mvbluefox3CameraDriver::openDriver(void) if (devMgr.getDeviceBySerial(this->vserial[ii]) == 0) { - std::cerr << "No device found! Unable to continue. " << std::endl; + std::cerr << this->vcam_name[ii] << " not found! Unable to continue. " << std::endl; + return true; } else { @@ -42,13 +45,25 @@ bool Mvbluefox3CameraDriver::openDriver(void) } } else - std::cerr << "Device cannot be found because serial number is not specified." << std::endl; + { + std::cerr << this->vcam_name[ii] << " not found because serial number is not specified!" << std::endl; + return true; + } } - std::cout << "[mvBlueFOX3]: All cameras opened successfully." << std::endl; }catch (CMvbluefox3::CmvBlueFOX3Exception& e) { - std::cout << e.what() << std::endl; + 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->initialize) + { + for (int ii = 0; ii < this->num_cams; ++ii) + SetConfig(ii); + this->initialize = false; + } return true; } @@ -58,11 +73,10 @@ bool Mvbluefox3CameraDriver::closeDriver(void) { for (int ii = 0; ii < this->num_cams; ++ii) this->vcam_ptr[ii]->CloseDevice(); - // this->vcam_ptr->CloseDevice(); std::cout << "[mvBlueFOX3]: Driver closed." << std::endl; }catch (CMvbluefox3::CmvBlueFOX3Exception& e) { - std::cout << e.what() << std::endl; + std::cerr << e.what() << std::endl; } return true; } @@ -81,19 +95,21 @@ void Mvbluefox3CameraDriver::config_update(Config& new_cfg, uint32_t level) { this->lock(); - // TODO: - - // depending on current state - // update driver with new_cfg data switch(this->getState()) { case Mvbluefox3CameraDriver::CLOSED: - // // Fill initial parameters - for (int ii = 0; ii < this->num_cams; ++ii) - this->vparams[ii] = DynRecToParams(new_cfg); 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) { @@ -105,7 +121,7 @@ void Mvbluefox3CameraDriver::config_update(Config& new_cfg, uint32_t level) this->vparams[ii] = DynRecToParams(new_cfg); SetConfig(ii); GetConfig(ii); - new_cfg = ParamsToDynRec(this->vparams[ii]); + new_cfg = ParamsToDynRec(ii,this->vparams[ii]); } } new_cfg.apply_cfg = false; @@ -164,10 +180,12 @@ CMvbluefox3::CParams Mvbluefox3CameraDriver::DynRecToParams(iri_mvbluefox3_camer return p; } -iri_mvbluefox3_camera::Mvbluefox3CameraConfig Mvbluefox3CameraDriver::ParamsToDynRec(CMvbluefox3::CParams &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; @@ -250,7 +268,7 @@ void Mvbluefox3CameraDriver::SetConfig(const int &ncam) std::cout << "[mvBlueFOX3]: New configuration set for " << this->vcam_name[ncam] << "." << std::endl; }catch (CMvbluefox3::CmvBlueFOX3Exception& e) { - std::cout << e.what() << std::endl; + std::cerr << e.what() << std::endl; } } diff --git a/src/mvbluefox3_camera_driver_node.cpp b/src/mvbluefox3_camera_driver_node.cpp index 5e14d86..1633def 100644 --- a/src/mvbluefox3_camera_driver_node.cpp +++ b/src/mvbluefox3_camera_driver_node.cpp @@ -2,7 +2,6 @@ Mvbluefox3CameraDriverNode::Mvbluefox3CameraDriverNode(ros::NodeHandle &nh) : iri_base_driver::IriBaseNodeDriver<Mvbluefox3CameraDriver>(nh), - // camera_manager(ros::NodeHandle("~image_raw")), it(this->public_node_handle_) { //init class attributes if necessary @@ -15,24 +14,28 @@ Mvbluefox3CameraDriverNode::Mvbluefox3CameraDriverNode(ros::NodeHandle &nh) : // 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 ss; ss << "cam" << ii+1 << "_name"; + // get camera name this->public_node_handle_.param<std::string>(ss.str(), this->driver_.vcam_name[ii], "cam1"); + // 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; std::string frame_id_name = this->driver_.vcam_name[ii] + "/frame_id"; std::string tf_prefix_name = this->driver_.vcam_name[ii] + "/tf_prefix"; @@ -42,21 +45,26 @@ Mvbluefox3CameraDriverNode::Mvbluefox3CameraDriverNode(ros::NodeHandle &nh) : this->driver_.vframe_id[ii] = tf_prefix + "/" + frame_id; this->public_node_handle_.param<std::string>(serial_name, this->driver_.vserial[ii], ""); - this->driver_.unlock(); - + // Get calibration file std::string image_cal_file; std::string image_cal_file_name = this->driver_.vcam_name[ii] + "/calibration_file"; public_node_handle_.param<std::string>(image_cal_file_name,image_cal_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_INFO("Invalid calibration file for CAM:%d",ii+1); + ROS_WARN("%s", err_msg.str().c_str()); } else - ROS_INFO("Invalid calibration file for CAM:%d",ii+1); + ROS_WARN("%s", err_msg.str().c_str()); + + // Get and Set camera parameters + SetParams(this->public_node_handle_, this->driver_.vcam_name[ii]); } + this->driver_.unlock(); + // [init subscribers] // [init services] @@ -68,6 +76,55 @@ Mvbluefox3CameraDriverNode::Mvbluefox3CameraDriverNode(ros::NodeHandle &nh) : // [init action clients] } +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_.initialize = true; +} + void Mvbluefox3CameraDriverNode::mainNodeThread(void) { // [fill msg Header if necessary] -- GitLab