f200_nodelet.cpp
Go to the documentation of this file.
00001 /******************************************************************************
00002  Copyright (c) 2017, Intel Corporation
00003  All rights reserved.
00004 
00005  Redistribution and use in source and binary forms, with or without
00006  modification, are permitted provided that the following conditions are met:
00007 
00008  1. Redistributions of source code must retain the above copyright notice, this
00009  list of conditions and the following disclaimer.
00010 
00011  2. Redistributions in binary form must reproduce the above copyright notice,
00012  this list of conditions and the following disclaimer in the documentation
00013  and/or other materials provided with the distribution.
00014 
00015  3. Neither the name of the copyright holder nor the names of its contributors
00016  may be used to endorse or promote products derived from this software without
00017  specific prior written permission.
00018 
00019  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00022  DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00023  FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00024  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00025  SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00026  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00027  OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00028  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00029  *******************************************************************************/
00030 
00031 #include <string>
00032 #include <vector>
00033 
00034 #include <realsense_camera/f200_nodelet.h>
00035 
00036 PLUGINLIB_EXPORT_CLASS(realsense_camera::F200Nodelet, nodelet::Nodelet)
00037 
00038 namespace realsense_camera
00039 {
00040   /*
00041    * Initialize the nodelet.
00042    */
00043   void F200Nodelet::onInit()
00044   {
00045     format_[RS_STREAM_COLOR] = RS_FORMAT_RGB8;
00046     encoding_[RS_STREAM_COLOR] = sensor_msgs::image_encodings::RGB8;
00047     cv_type_[RS_STREAM_COLOR] = CV_8UC3;
00048     unit_step_size_[RS_STREAM_COLOR] = sizeof(unsigned char) * 3;
00049 
00050     format_[RS_STREAM_DEPTH] = RS_FORMAT_Z16;
00051     encoding_[RS_STREAM_DEPTH] = sensor_msgs::image_encodings::TYPE_16UC1;
00052     cv_type_[RS_STREAM_DEPTH] = CV_16UC1;
00053     unit_step_size_[RS_STREAM_DEPTH] = sizeof(uint16_t);
00054 
00055     format_[RS_STREAM_INFRARED] = RS_FORMAT_Y8;
00056     encoding_[RS_STREAM_INFRARED] = sensor_msgs::image_encodings::TYPE_8UC1;
00057     cv_type_[RS_STREAM_INFRARED] = CV_8UC1;
00058     unit_step_size_[RS_STREAM_INFRARED] = sizeof(unsigned char);
00059 
00060     max_z_ = F200_MAX_Z;
00061 
00062     SyncNodelet::onInit();
00063   }
00064 
00065   /*
00066    * Determine fastest stream -- overrides base class
00067    */
00068   void F200Nodelet::setStreams()
00069   {
00070     // enable camera streams
00071     BaseNodelet::setStreams();
00072 
00073     // Find the fastest updating, enabled stream
00074     fastest_stream_ = RS_STREAM_DEPTH;  // default to depth
00075 
00076     if (fps_[RS_STREAM_COLOR] > fps_[RS_STREAM_DEPTH])
00077     {
00078       if (enable_[RS_STREAM_COLOR])
00079       {
00080         fastest_stream_ = RS_STREAM_COLOR;
00081       }
00082     }
00083   }
00084 
00085   /*
00086    * Set Dynamic Reconfigure Server and return the dynamic params.
00087    */
00088   std::vector<std::string> F200Nodelet::setDynamicReconfServer()
00089   {
00090     dynamic_reconf_server_.reset(new dynamic_reconfigure::Server<realsense_camera::f200_paramsConfig>(pnh_));
00091 
00092     // Get dynamic options from the dynamic reconfigure server.
00093     realsense_camera::f200_paramsConfig params_config;
00094     dynamic_reconf_server_->getConfigDefault(params_config);
00095     std::vector<realsense_camera::f200_paramsConfig::AbstractParamDescriptionConstPtr> param_desc =
00096         params_config.__getParamDescriptions__();
00097     std::vector<std::string> dynamic_params;
00098     for (realsense_camera::f200_paramsConfig::AbstractParamDescriptionConstPtr param_desc_ptr : param_desc)
00099     {
00100       dynamic_params.push_back((* param_desc_ptr).name);
00101     }
00102 
00103     return dynamic_params;
00104   }
00105 
00106   /*
00107    * Start Dynamic Reconfigure Callback.
00108    */
00109   void F200Nodelet::startDynamicReconfCallback()
00110   {
00111     dynamic_reconf_server_->setCallback(boost::bind(&F200Nodelet::configCallback, this, _1, _2));
00112   }
00113 
00114   /*
00115    * Get the dynamic param values.
00116    */
00117   void F200Nodelet::configCallback(realsense_camera::f200_paramsConfig &config, uint32_t level)
00118   {
00119     ROS_INFO_STREAM(nodelet_name_ << " - Setting dynamic camera options");
00120 
00121     // set the depth enable
00122     BaseNodelet::setDepthEnable(config.enable_depth);
00123 
00124     // Set common options
00125     rs_set_device_option(rs_device_, RS_OPTION_COLOR_BACKLIGHT_COMPENSATION, config.color_backlight_compensation, 0);
00126     rs_set_device_option(rs_device_, RS_OPTION_COLOR_BRIGHTNESS, config.color_brightness, 0);
00127     rs_set_device_option(rs_device_, RS_OPTION_COLOR_CONTRAST, config.color_contrast, 0);
00128     rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAIN, config.color_gain, 0);
00129     rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAMMA, config.color_gamma, 0);
00130     rs_set_device_option(rs_device_, RS_OPTION_COLOR_HUE, config.color_hue, 0);
00131     rs_set_device_option(rs_device_, RS_OPTION_COLOR_SATURATION, config.color_saturation, 0);
00132     rs_set_device_option(rs_device_, RS_OPTION_COLOR_SHARPNESS, config.color_sharpness, 0);
00133     rs_set_device_option(rs_device_, RS_OPTION_COLOR_ENABLE_AUTO_EXPOSURE,
00134     config.color_enable_auto_exposure, 0);
00135     if (config.color_enable_auto_exposure == 0)
00136     {
00137       rs_set_device_option(rs_device_, RS_OPTION_COLOR_EXPOSURE, config.color_exposure, 0);
00138     }
00139     rs_set_device_option(rs_device_, RS_OPTION_COLOR_ENABLE_AUTO_WHITE_BALANCE,
00140         config.color_enable_auto_white_balance, 0);
00141     if (config.color_enable_auto_white_balance == 0)
00142     {
00143       rs_set_device_option(rs_device_, RS_OPTION_COLOR_WHITE_BALANCE, config.color_white_balance, 0);
00144     }
00145 
00146     // Set F200 specific options
00147     rs_set_device_option(rs_device_, RS_OPTION_F200_LASER_POWER, config.f200_laser_power, 0);
00148     rs_set_device_option(rs_device_, RS_OPTION_F200_ACCURACY, config.f200_accuracy, 0);
00149     rs_set_device_option(rs_device_, RS_OPTION_F200_MOTION_RANGE, config.f200_motion_range, 0);
00150     rs_set_device_option(rs_device_, RS_OPTION_F200_FILTER_OPTION, config.f200_filter_option, 0);
00151     rs_set_device_option(rs_device_, RS_OPTION_F200_CONFIDENCE_THRESHOLD, config.f200_confidence_threshold, 0);
00152   }
00153 }  // namespace realsense_camera


realsense_camera
Author(s): Rajvi Jingar , Reagan Lopez , Matt Hansen , Mark Horn
autogenerated on Thu Jun 6 2019 21:15:58