00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
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
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
00066
00067 void SR300Nodelet::setStreams()
00068 {
00069
00070 BaseNodelet::setStreams();
00071
00072
00073 fastest_stream_ = RS_STREAM_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
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
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
00107
00108 void SR300Nodelet::startDynamicReconfCallback()
00109 {
00110 dynamic_reconf_server_->setCallback(boost::bind(&SR300Nodelet::configCallback, this, _1, _2));
00111 }
00112
00113
00114
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
00121 BaseNodelet::setDepthEnable(config.enable_depth);
00122
00123
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
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
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
00181
00182
00183
00184
00185
00186
00187
00188 }
00189 }