sr300_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 #include <realsense_camera/sr300_nodelet.h>
00034 
00035 PLUGINLIB_EXPORT_CLASS(realsense_camera::SR300Nodelet, nodelet::Nodelet)
00036 
00037 namespace realsense_camera
00038 {
00039   /*
00040    * Initialize the nodelet.
00041    */
00042   void SR300Nodelet::onInit()
00043   {
00044     format_[RS_STREAM_COLOR] = RS_FORMAT_RGB8;
00045     encoding_[RS_STREAM_COLOR] = sensor_msgs::image_encodings::RGB8;
00046     cv_type_[RS_STREAM_COLOR] = CV_8UC3;
00047     unit_step_size_[RS_STREAM_COLOR] = sizeof(unsigned char) * 3;
00048 
00049     format_[RS_STREAM_DEPTH] = RS_FORMAT_Z16;
00050     encoding_[RS_STREAM_DEPTH] = sensor_msgs::image_encodings::TYPE_16UC1;
00051     cv_type_[RS_STREAM_DEPTH] = CV_16UC1;
00052     unit_step_size_[RS_STREAM_DEPTH] = sizeof(uint16_t);
00053 
00054     format_[RS_STREAM_INFRARED] = RS_FORMAT_Y16;
00055     encoding_[RS_STREAM_INFRARED] = sensor_msgs::image_encodings::TYPE_16UC1;
00056     cv_type_[RS_STREAM_INFRARED] = CV_16UC1;
00057     unit_step_size_[RS_STREAM_INFRARED] = sizeof(uint16_t);
00058 
00059     max_z_ = SR300_MAX_Z;
00060 
00061     SyncNodelet::onInit();
00062   }
00063 
00064   /*
00065    * Determine fastest stream -- overrides base class
00066    */
00067   void SR300Nodelet::setStreams()
00068   {
00069     // enable camera streams
00070     BaseNodelet::setStreams();
00071 
00072     // Find the fastest updating, enabled stream
00073     fastest_stream_ = RS_STREAM_DEPTH;  // default to depth
00074 
00075     if (fps_[RS_STREAM_COLOR] > fps_[RS_STREAM_DEPTH])
00076     {
00077       if (enable_[RS_STREAM_COLOR])
00078       {
00079         fastest_stream_ = RS_STREAM_COLOR;
00080       }
00081     }
00082   }
00083 
00084   /*
00085    * Set Dynamic Reconfigure Server and return the dynamic params.
00086    */
00087   std::vector<std::string> SR300Nodelet::setDynamicReconfServer()
00088   {
00089     dynamic_reconf_server_.reset(new dynamic_reconfigure::Server<realsense_camera::sr300_paramsConfig>(pnh_));
00090 
00091     // Get dynamic options from the dynamic reconfigure server.
00092     realsense_camera::sr300_paramsConfig params_config;
00093     dynamic_reconf_server_->getConfigDefault(params_config);
00094     std::vector<realsense_camera::sr300_paramsConfig::AbstractParamDescriptionConstPtr> param_desc =
00095         params_config.__getParamDescriptions__();
00096     std::vector<std::string> dynamic_params;
00097     for (realsense_camera::sr300_paramsConfig::AbstractParamDescriptionConstPtr param_desc_ptr : param_desc)
00098     {
00099       dynamic_params.push_back((* param_desc_ptr).name);
00100     }
00101 
00102     return dynamic_params;
00103   }
00104 
00105   /*
00106    * Start Dynamic Reconfigure Callback.
00107    */
00108   void SR300Nodelet::startDynamicReconfCallback()
00109   {
00110     dynamic_reconf_server_->setCallback(boost::bind(&SR300Nodelet::configCallback, this, _1, _2));
00111   }
00112 
00113   /*
00114    * Get the dynamic param values.
00115    */
00116   void SR300Nodelet::configCallback(realsense_camera::sr300_paramsConfig &config, uint32_t level)
00117   {
00118     ROS_INFO_STREAM(nodelet_name_ << " - Setting dynamic camera options");
00119 
00120     // set the depth enable
00121     BaseNodelet::setDepthEnable(config.enable_depth);
00122 
00123     // Set common options
00124     rs_set_device_option(rs_device_, RS_OPTION_COLOR_BACKLIGHT_COMPENSATION, config.color_backlight_compensation, 0);
00125     rs_set_device_option(rs_device_, RS_OPTION_COLOR_BRIGHTNESS, config.color_brightness, 0);
00126     rs_set_device_option(rs_device_, RS_OPTION_COLOR_CONTRAST, config.color_contrast, 0);
00127     rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAIN, config.color_gain, 0);
00128     rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAMMA, config.color_gamma, 0);
00129     rs_set_device_option(rs_device_, RS_OPTION_COLOR_HUE, config.color_hue, 0);
00130     rs_set_device_option(rs_device_, RS_OPTION_COLOR_SATURATION, config.color_saturation, 0);
00131     rs_set_device_option(rs_device_, RS_OPTION_COLOR_SHARPNESS, config.color_sharpness, 0);
00132     rs_set_device_option(rs_device_, RS_OPTION_COLOR_ENABLE_AUTO_EXPOSURE,
00133         config.color_enable_auto_exposure, 0);
00134     if (config.color_enable_auto_exposure == 0)
00135     {
00136       rs_set_device_option(rs_device_, RS_OPTION_COLOR_EXPOSURE, config.color_exposure, 0);
00137     }
00138     rs_set_device_option(rs_device_, RS_OPTION_COLOR_ENABLE_AUTO_WHITE_BALANCE,
00139         config.color_enable_auto_white_balance, 0);
00140     if (config.color_enable_auto_white_balance == 0)
00141     {
00142       rs_set_device_option(rs_device_, RS_OPTION_COLOR_WHITE_BALANCE, config.color_white_balance, 0);
00143     }
00144 
00145     // Set SR300 options that are common with F200
00146     rs_set_device_option(rs_device_, RS_OPTION_F200_LASER_POWER, config.f200_laser_power, 0);
00147     rs_set_device_option(rs_device_, RS_OPTION_F200_ACCURACY, config.f200_accuracy, 0);
00148     rs_set_device_option(rs_device_, RS_OPTION_F200_MOTION_RANGE, config.f200_motion_range, 0);
00149     rs_set_device_option(rs_device_, RS_OPTION_F200_FILTER_OPTION, config.f200_filter_option, 0);
00150     rs_set_device_option(rs_device_, RS_OPTION_F200_CONFIDENCE_THRESHOLD, config.f200_confidence_threshold, 0);
00151 
00152     // Set SR300 specific options
00153     rs_set_device_option(rs_device_, RS_OPTION_SR300_AUTO_RANGE_ENABLE_MOTION_VERSUS_RANGE,
00154         config.sr300_auto_range_enable_motion_versus_range, 0);
00155     if (config.sr300_auto_range_enable_motion_versus_range == 1)
00156     {
00157       rs_set_device_option(rs_device_, RS_OPTION_SR300_AUTO_RANGE_MIN_MOTION_VERSUS_RANGE,
00158           config.sr300_auto_range_min_motion_versus_range, 0);
00159       rs_set_device_option(rs_device_, RS_OPTION_SR300_AUTO_RANGE_MAX_MOTION_VERSUS_RANGE,
00160           config.sr300_auto_range_max_motion_versus_range, 0);
00161       rs_set_device_option(rs_device_, RS_OPTION_SR300_AUTO_RANGE_START_MOTION_VERSUS_RANGE,
00162           config.sr300_auto_range_start_motion_versus_range, 0);
00163     }
00164     rs_set_device_option(rs_device_, RS_OPTION_SR300_AUTO_RANGE_ENABLE_LASER,
00165         config.sr300_auto_range_enable_laser, 0);
00166     if (config.sr300_auto_range_enable_laser == 1)
00167     {
00168       rs_set_device_option(rs_device_, RS_OPTION_SR300_AUTO_RANGE_MIN_LASER,
00169           config.sr300_auto_range_min_laser, 0);
00170       rs_set_device_option(rs_device_, RS_OPTION_SR300_AUTO_RANGE_MAX_LASER,
00171           config.sr300_auto_range_max_laser, 0);
00172       rs_set_device_option(rs_device_, RS_OPTION_SR300_AUTO_RANGE_START_LASER,
00173           config.sr300_auto_range_start_laser, 0);
00174     }
00175     rs_set_device_option(rs_device_, RS_OPTION_SR300_AUTO_RANGE_UPPER_THRESHOLD,
00176         config.sr300_auto_range_upper_threshold, 0);
00177     rs_set_device_option(rs_device_, RS_OPTION_SR300_AUTO_RANGE_LOWER_THRESHOLD,
00178         config.sr300_auto_range_lower_threshold, 0);
00179 /*
00180     rs_set_device_option(rs_device_, RS_OPTION_SR300_WAKEUP_DEV_PHASE1_PERIOD, config.sr300_wakeup_dev_phase1_period, 0);
00181     rs_set_device_option(rs_device_, RS_OPTION_SR300_WAKEUP_DEV_PHASE1_FPS, config.sr300_wakeup_dev_phase1_fps, 0);
00182     rs_set_device_option(rs_device_, RS_OPTION_SR300_WAKEUP_DEV_PHASE2_PERIOD, config.sr300_wakeup_dev_phase2_period, 0);
00183     rs_set_device_option(rs_device_, RS_OPTION_SR300_WAKEUP_DEV_PHASE2_FPS, config.sr300_wakeup_dev_phase2_fps, 0);
00184     rs_set_device_option(rs_device_, RS_OPTION_SR300_WAKEUP_DEV_RESET, config.sr300_wakeup_dev_reset, 0);
00185     rs_set_device_option(rs_device_, RS_OPTION_SR300_WAKE_ON_USB_REASON, config.sr300_wake_on_usb_reason, 0);
00186     rs_set_device_option(rs_device_, RS_OPTION_SR300_WAKE_ON_USB_CONFIDENCE, config.sr300_wake_on_usb_confidence, 0);
00187 */
00188   }
00189 }  // namespace realsense_camera


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