zr300_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 <algorithm>
00033 #include <vector>
00034 
00035 #include <realsense_camera/zr300_nodelet.h>
00036 
00037 PLUGINLIB_EXPORT_CLASS(realsense_camera::ZR300Nodelet, nodelet::Nodelet)
00038 
00039 namespace realsense_camera
00040 {
00041   /*
00042    * Nodelet Destructor.
00043    */
00044   ZR300Nodelet::~ZR300Nodelet()
00045   {
00046     if (enable_imu_ == true)
00047     {
00048       stopIMU();
00049       // clean up imu thread
00050       imu_thread_->join();
00051     }
00052   }
00053 
00054   /*
00055    * Initialize the nodelet.
00056    */
00057   void ZR300Nodelet::onInit()
00058   {
00059     format_[RS_STREAM_COLOR] = RS_FORMAT_RGB8;
00060     encoding_[RS_STREAM_COLOR] = sensor_msgs::image_encodings::RGB8;
00061     cv_type_[RS_STREAM_COLOR] = CV_8UC3;
00062     unit_step_size_[RS_STREAM_COLOR] = sizeof(unsigned char) * 3;
00063 
00064     format_[RS_STREAM_DEPTH] = RS_FORMAT_Z16;
00065     encoding_[RS_STREAM_DEPTH] = sensor_msgs::image_encodings::TYPE_16UC1;
00066     cv_type_[RS_STREAM_DEPTH] = CV_16UC1;
00067     unit_step_size_[RS_STREAM_DEPTH] = sizeof(uint16_t);
00068 
00069     format_[RS_STREAM_INFRARED] = RS_FORMAT_Y8;
00070     encoding_[RS_STREAM_INFRARED] = sensor_msgs::image_encodings::TYPE_8UC1;
00071     cv_type_[RS_STREAM_INFRARED] = CV_8UC1;
00072     unit_step_size_[RS_STREAM_INFRARED] = sizeof(unsigned char);
00073 
00074     format_[RS_STREAM_INFRARED2] = RS_FORMAT_Y8;
00075     encoding_[RS_STREAM_INFRARED2] = sensor_msgs::image_encodings::TYPE_8UC1;
00076     cv_type_[RS_STREAM_INFRARED2] = CV_8UC1;
00077     unit_step_size_[RS_STREAM_INFRARED2] = sizeof(unsigned char);
00078 
00079     format_[RS_STREAM_FISHEYE] = RS_FORMAT_RAW8;
00080     encoding_[RS_STREAM_FISHEYE] = sensor_msgs::image_encodings::TYPE_8UC1;
00081     cv_type_[RS_STREAM_FISHEYE] = CV_8UC1;
00082     unit_step_size_[RS_STREAM_FISHEYE] = sizeof(unsigned char);
00083 
00084     max_z_ = ZR300_MAX_Z;
00085 
00086     BaseNodelet::onInit();
00087 
00088     if (enable_imu_ == true)
00089     {
00090       imu_thread_ =
00091           boost::shared_ptr<boost::thread>(new boost::thread(boost::bind(&ZR300Nodelet::publishIMU, this)));
00092     }
00093   }
00094 
00095   /*
00096    * Get the nodelet parameters.
00097    */
00098   void ZR300Nodelet::getParameters()
00099   {
00100     BaseNodelet::getParameters();
00101     pnh_.param("ir2_frame_id", frame_id_[RS_STREAM_INFRARED2], DEFAULT_IR2_FRAME_ID);
00102     pnh_.param("ir2_optical_frame_id", optical_frame_id_[RS_STREAM_INFRARED2], DEFAULT_IR2_OPTICAL_FRAME_ID);
00103     pnh_.param("enable_fisheye", enable_[RS_STREAM_FISHEYE], ENABLE_FISHEYE);
00104     pnh_.param("enable_imu", enable_imu_, ENABLE_IMU);
00105     pnh_.param("enable_ir2", enable_[RS_STREAM_INFRARED2], ENABLE_IR2);
00106     pnh_.param("fisheye_width", width_[RS_STREAM_FISHEYE], FISHEYE_WIDTH);
00107     pnh_.param("fisheye_height", height_[RS_STREAM_FISHEYE], FISHEYE_HEIGHT);
00108     pnh_.param("fisheye_fps", fps_[RS_STREAM_FISHEYE], FISHEYE_FPS);
00109     pnh_.param("fisheye_frame_id", frame_id_[RS_STREAM_FISHEYE], DEFAULT_FISHEYE_FRAME_ID);
00110     pnh_.param("fisheye_optical_frame_id", optical_frame_id_[RS_STREAM_FISHEYE], DEFAULT_FISHEYE_OPTICAL_FRAME_ID);
00111     pnh_.param("imu_frame_id", imu_frame_id_, DEFAULT_IMU_FRAME_ID);
00112     pnh_.param("imu_optical_frame_id", imu_optical_frame_id_, DEFAULT_IMU_OPTICAL_FRAME_ID);
00113 
00114     // set IR2 stream to match depth
00115     width_[RS_STREAM_INFRARED2] = width_[RS_STREAM_DEPTH];
00116     height_[RS_STREAM_INFRARED2] = height_[RS_STREAM_DEPTH];
00117     fps_[RS_STREAM_INFRARED2] = fps_[RS_STREAM_DEPTH];
00118   }
00119 
00120   /*
00121    * Advertise topics.
00122    */
00123   void ZR300Nodelet::advertiseTopics()
00124   {
00125     BaseNodelet::advertiseTopics();
00126     ros::NodeHandle ir2_nh(nh_, IR2_NAMESPACE);
00127     image_transport::ImageTransport ir2_image_transport(ir2_nh);
00128     camera_publisher_[RS_STREAM_INFRARED2] = ir2_image_transport.advertiseCamera(IR2_TOPIC, 1);
00129 
00130     ros::NodeHandle fisheye_nh(nh_, FISHEYE_NAMESPACE);
00131     image_transport::ImageTransport fisheye_image_transport(fisheye_nh);
00132     camera_publisher_[RS_STREAM_FISHEYE] = fisheye_image_transport.advertiseCamera(FISHEYE_TOPIC, 1);
00133 
00134     ros::NodeHandle imu_nh(nh_, IMU_NAMESPACE);
00135     imu_publisher_ = imu_nh.advertise<sensor_msgs::Imu>(IMU_TOPIC, 1000);
00136   }
00137 
00138   /*
00139    * Advertise services.
00140    */
00141   void ZR300Nodelet::advertiseServices()
00142   {
00143     BaseNodelet::advertiseServices();
00144     get_imu_info_ = pnh_.advertiseService(IMU_INFO_SERVICE, &ZR300Nodelet::getIMUInfo, this);
00145   }
00146 
00147   /*
00148    * Get IMU Info.
00149    */
00150   bool ZR300Nodelet::getIMUInfo(realsense_camera::GetIMUInfo::Request & req,
00151       realsense_camera::GetIMUInfo::Response & res)
00152   {
00153     ros::Time header_stamp = ros::Time::now();
00154     std::string header_frame_id;
00155 
00156 
00157     rs_motion_intrinsics imu_intrinsics;
00158     rs_get_motion_intrinsics(rs_device_, &imu_intrinsics, &rs_error_);
00159     if (rs_error_)
00160     {
00161       ROS_ERROR_STREAM(nodelet_name_ << " - Verify camera firmware version!");
00162     }
00163     checkError();
00164 
00165     int index = 0;
00166     res.accel.header.stamp = header_stamp;
00167     res.accel.header.frame_id = IMU_ACCEL;
00168     std::transform(res.accel.header.frame_id.begin(), res.accel.header.frame_id.end(),
00169         res.accel.header.frame_id.begin(), ::tolower);
00170 
00171     for (int i = 0; i < 3; ++i)
00172     {
00173       for (int j = 0; j < 4; ++j)
00174       {
00175         res.accel.data[index] = imu_intrinsics.acc.data[i][j];
00176         ++index;
00177       }
00178       res.accel.noise_variances[i] = imu_intrinsics.acc.noise_variances[i];
00179       res.accel.bias_variances[i] = imu_intrinsics.acc.bias_variances[i];
00180     }
00181 
00182     index = 0;
00183     res.gyro.header.stamp = header_stamp;
00184     res.gyro.header.frame_id = IMU_GYRO;
00185     std::transform(res.gyro.header.frame_id.begin(), res.gyro.header.frame_id.end(),
00186         res.gyro.header.frame_id.begin(), ::tolower);
00187     for (int i = 0; i < 3; ++i)
00188     {
00189       for (int j = 0; j < 4; ++j)
00190       {
00191         res.gyro.data[index] = imu_intrinsics.gyro.data[i][j];
00192         ++index;
00193       }
00194       res.gyro.noise_variances[i] = imu_intrinsics.gyro.noise_variances[i];
00195       res.gyro.bias_variances[i] = imu_intrinsics.gyro.bias_variances[i];
00196     }
00197 
00198     return true;
00199   }
00200 
00201   /*
00202    * Set Dynamic Reconfigure Server and return the dynamic params.
00203    */
00204   std::vector<std::string> ZR300Nodelet::setDynamicReconfServer()
00205   {
00206     dynamic_reconf_server_.reset(new dynamic_reconfigure::Server<realsense_camera::zr300_paramsConfig>(pnh_));
00207 
00208     // Get dynamic options from the dynamic reconfigure server.
00209     realsense_camera::zr300_paramsConfig params_config;
00210     dynamic_reconf_server_->getConfigDefault(params_config);
00211     std::vector<realsense_camera::zr300_paramsConfig::AbstractParamDescriptionConstPtr> param_desc =
00212       params_config.__getParamDescriptions__();
00213     std::vector<std::string> dynamic_params;
00214     for (realsense_camera::zr300_paramsConfig::AbstractParamDescriptionConstPtr param_desc_ptr : param_desc)
00215     {
00216       dynamic_params.push_back((* param_desc_ptr).name);
00217     }
00218 
00219     return dynamic_params;
00220   }
00221 
00222   /*
00223    * Start Dynamic Reconfigure Callback.
00224    */
00225   void ZR300Nodelet::startDynamicReconfCallback()
00226   {
00227     dynamic_reconf_server_->setCallback(boost::bind(&ZR300Nodelet::configCallback, this, _1, _2));
00228   }
00229 
00230   /*
00231    * Change the Depth Control Preset
00232    */
00233   void ZR300Nodelet::setDynamicReconfigDepthControlPreset(int preset)
00234   {
00235     // There is not a C++ API for dynamic reconfig so we need to use a system call
00236     // Adding the sleep to ensure the current callback can end before we
00237     // attempt the next callback from the system call.
00238     std::vector<std::string> argv;
00239     argv.push_back("rosrun");
00240     argv.push_back("dynamic_reconfigure");
00241     argv.push_back("dynparam");
00242     argv.push_back("set");
00243     argv.push_back(nodelet_name_);
00244     argv.push_back("r200_dc_preset");
00245     argv.push_back(std::to_string(preset));
00246 
00247     wrappedSystem(argv);
00248   }
00249 
00250   /*
00251    * Change the Depth Control Individual values
00252    * GET ALL of the DC options from librealsense
00253    * Call dynamic reconfig and set all 10 values as a set
00254    */
00255   std::string ZR300Nodelet::setDynamicReconfigDepthControlIndividuals()
00256   {
00257     std::string current_param;
00258     std::string current_dc;
00259     std::string option_value;
00260 
00261     // There is not a C++ API for dynamic reconfig so we need to use a system call
00262     // Adding the sleep to ensure the current callback can end before we
00263     // attempt the next callback from the system call.
00264     std::vector<std::string> argv;
00265     argv.push_back("rosrun");
00266     argv.push_back("dynamic_reconfigure");
00267     argv.push_back("dynparam");
00268     argv.push_back("set");
00269     argv.push_back(nodelet_name_);
00270 
00271     current_param = "{";
00272 
00273     option_value =
00274       std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
00275               RS_OPTION_R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_DECREMENT, 0)));
00276     current_param += "'r200_dc_estimate_median_decrement':" + option_value + ", ";
00277     current_dc += option_value + ":";
00278 
00279     option_value =
00280       std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
00281               RS_OPTION_R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_INCREMENT, 0)));
00282     current_param += "'r200_dc_estimate_median_increment':" + option_value + ", ";
00283     current_dc += option_value + ":";
00284 
00285     option_value =
00286       std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
00287               RS_OPTION_R200_DEPTH_CONTROL_MEDIAN_THRESHOLD, 0)));
00288     current_param += "'r200_dc_median_threshold':" + option_value + ", ";
00289     current_dc += option_value + ":";
00290 
00291     option_value =
00292       std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
00293               RS_OPTION_R200_DEPTH_CONTROL_SCORE_MINIMUM_THRESHOLD, 0)));
00294     current_param += "'r200_dc_score_minimum_threshold':" + option_value + ", ";
00295     current_dc += option_value + ":";
00296 
00297     option_value =
00298       std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
00299               RS_OPTION_R200_DEPTH_CONTROL_SCORE_MAXIMUM_THRESHOLD, 0)));
00300     current_param += "'r200_dc_score_maximum_threshold':" + option_value + ", ";
00301     current_dc += option_value + ":";
00302 
00303     option_value =
00304       std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
00305               RS_OPTION_R200_DEPTH_CONTROL_TEXTURE_COUNT_THRESHOLD, 0)));
00306     current_param += "'r200_dc_texture_count_threshold':" + option_value + ", ";
00307     current_dc += option_value + ":";
00308 
00309     option_value =
00310       std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
00311               RS_OPTION_R200_DEPTH_CONTROL_TEXTURE_DIFFERENCE_THRESHOLD, 0)));
00312     current_param += "'r200_dc_texture_difference_threshold':" + option_value + ", ";
00313     current_dc += option_value + ":";
00314 
00315     option_value =
00316       std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
00317               RS_OPTION_R200_DEPTH_CONTROL_SECOND_PEAK_THRESHOLD, 0)));
00318     current_param += "'r200_dc_second_peak_threshold':" + option_value + ", ";
00319     current_dc += option_value + ":";
00320 
00321     option_value =
00322       std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
00323               RS_OPTION_R200_DEPTH_CONTROL_NEIGHBOR_THRESHOLD, 0)));
00324     current_param += "'r200_dc_neighbor_threshold':" + option_value + ", ";
00325     current_dc += option_value + ":";
00326 
00327     option_value =
00328       std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
00329               RS_OPTION_R200_DEPTH_CONTROL_LR_THRESHOLD, 0)));
00330     current_param += "'r200_dc_lr_threshold':" + option_value + "}";
00331     current_dc += option_value;
00332 
00333     ROS_DEBUG_STREAM(nodelet_name_ << " - Setting DC: " << current_param);
00334 
00335     argv.push_back(current_param);
00336 
00337     wrappedSystem(argv);
00338 
00339     return current_dc;
00340   }
00341 
00342   /*
00343    * Get the dynamic param values.
00344    */
00345   void ZR300Nodelet::configCallback(realsense_camera::zr300_paramsConfig &config, uint32_t level)
00346   {
00347     // Save the dc_preset value as there is no getter API for this value
00348     static int dc_preset = -2;
00349     int previous_dc_preset = dc_preset;
00350     // Save the last depth control preset values as a string
00351     static std::string last_dc;
00352 
00353     // level is the ORing of all levels which have a changed value
00354     std::bitset<32> bit_level{level};
00355 
00356     if (bit_level.test(6))  // 2^6 = 64 : Depth Control Preset
00357     {
00358       ROS_INFO_STREAM(nodelet_name_ << " - Setting dynamic camera options" <<
00359           " (r200_dc_preset=" << config.r200_dc_preset << ")");
00360     }
00361     else
00362     {
00363       ROS_INFO_STREAM(nodelet_name_ << " - Setting dynamic camera options");
00364     }
00365 
00366     // set the depth enable
00367     BaseNodelet::setDepthEnable(config.enable_depth);
00368 
00369     // Set common options
00370     rs_set_device_option(rs_device_, RS_OPTION_COLOR_BACKLIGHT_COMPENSATION, config.color_backlight_compensation, 0);
00371     rs_set_device_option(rs_device_, RS_OPTION_COLOR_BRIGHTNESS, config.color_brightness, 0);
00372     rs_set_device_option(rs_device_, RS_OPTION_COLOR_CONTRAST, config.color_contrast, 0);
00373     rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAIN, config.color_gain, 0);
00374     rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAMMA, config.color_gamma, 0);
00375     rs_set_device_option(rs_device_, RS_OPTION_COLOR_HUE, config.color_hue, 0);
00376     rs_set_device_option(rs_device_, RS_OPTION_COLOR_SATURATION, config.color_saturation, 0);
00377     rs_set_device_option(rs_device_, RS_OPTION_COLOR_SHARPNESS, config.color_sharpness, 0);
00378     rs_set_device_option(rs_device_, RS_OPTION_COLOR_ENABLE_AUTO_EXPOSURE, config.color_enable_auto_exposure, 0);
00379     if (config.color_enable_auto_exposure == 0)
00380     {
00381       rs_set_device_option(rs_device_, RS_OPTION_COLOR_EXPOSURE, config.color_exposure, 0);
00382     }
00383     rs_set_device_option(rs_device_, RS_OPTION_COLOR_ENABLE_AUTO_WHITE_BALANCE,
00384         config.color_enable_auto_white_balance, 0);
00385     if (config.color_enable_auto_white_balance == 0)
00386     {
00387       rs_set_device_option(rs_device_, RS_OPTION_COLOR_WHITE_BALANCE, config.color_white_balance, 0);
00388     }
00389 
00390     // Set R200 specific options
00391     rs_set_device_option(rs_device_, RS_OPTION_R200_LR_AUTO_EXPOSURE_ENABLED, config.r200_lr_auto_exposure_enabled, 0);
00392     if (config.r200_lr_auto_exposure_enabled == 0)
00393     {
00394       rs_set_device_option(rs_device_, RS_OPTION_R200_LR_GAIN, config.r200_lr_gain, 0);
00395       rs_set_device_option(rs_device_, RS_OPTION_R200_LR_EXPOSURE, config.r200_lr_exposure, 0);
00396     }
00397 
00398     rs_set_device_option(rs_device_, RS_OPTION_R200_EMITTER_ENABLED, config.r200_emitter_enabled, 0);
00399     rs_set_device_option(rs_device_, RS_OPTION_R200_DEPTH_CLAMP_MIN, config.r200_depth_clamp_min, 0);
00400     rs_set_device_option(rs_device_, RS_OPTION_R200_DEPTH_CLAMP_MAX, config.r200_depth_clamp_max, 0);
00401 
00402     // Depth Control Group Settings
00403     // NOTE: do NOT use the config.groups values as they are zero the first time called
00404     if (bit_level.test(5))  // 2^5 = 32 : Individual Depth Control settings
00405     {
00406       std::string current_dc;
00407 
00408       ROS_DEBUG_STREAM(nodelet_name_ << " - Setting Individual Depth Control");
00409 
00410       rs_set_device_option(rs_device_, RS_OPTION_R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_DECREMENT,
00411           config.r200_dc_estimate_median_decrement, 0);
00412       current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_estimate_median_decrement)) + ":";
00413       rs_set_device_option(rs_device_, RS_OPTION_R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_INCREMENT,
00414           config.r200_dc_estimate_median_increment, 0);
00415       current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_estimate_median_increment)) + ":";
00416       rs_set_device_option(rs_device_, RS_OPTION_R200_DEPTH_CONTROL_MEDIAN_THRESHOLD,
00417           config.r200_dc_median_threshold, 0);
00418       current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_median_threshold)) + ":";
00419       rs_set_device_option(rs_device_, RS_OPTION_R200_DEPTH_CONTROL_SCORE_MINIMUM_THRESHOLD,
00420           config.r200_dc_score_minimum_threshold, 0);
00421       current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_score_minimum_threshold)) + ":";
00422       rs_set_device_option(rs_device_, RS_OPTION_R200_DEPTH_CONTROL_SCORE_MAXIMUM_THRESHOLD,
00423           config.r200_dc_score_maximum_threshold, 0);
00424       current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_score_maximum_threshold)) + ":";
00425       rs_set_device_option(rs_device_, RS_OPTION_R200_DEPTH_CONTROL_TEXTURE_COUNT_THRESHOLD,
00426           config.r200_dc_texture_count_threshold, 0);
00427       current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_texture_count_threshold)) + ":";
00428       rs_set_device_option(rs_device_, RS_OPTION_R200_DEPTH_CONTROL_TEXTURE_DIFFERENCE_THRESHOLD,
00429           config.r200_dc_texture_difference_threshold, 0);
00430       current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_texture_difference_threshold)) + ":";
00431       rs_set_device_option(rs_device_, RS_OPTION_R200_DEPTH_CONTROL_SECOND_PEAK_THRESHOLD,
00432           config.r200_dc_second_peak_threshold, 0);
00433       current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_second_peak_threshold)) + ":";
00434       rs_set_device_option(rs_device_, RS_OPTION_R200_DEPTH_CONTROL_NEIGHBOR_THRESHOLD,
00435           config.r200_dc_neighbor_threshold, 0);
00436       current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_neighbor_threshold)) + ":";
00437       rs_set_device_option(rs_device_, RS_OPTION_R200_DEPTH_CONTROL_LR_THRESHOLD,
00438           config.r200_dc_lr_threshold, 0);
00439       current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_lr_threshold));
00440 
00441       // Preset also changed in the same update callback
00442       // This is either First callback special case, or both set via
00443       // dynamic configure command line.
00444       if (bit_level.test(6))  // 2^6 = 64 : Depth Control Preset
00445       {
00446         dc_preset = config.r200_dc_preset;
00447 
00448         if (previous_dc_preset != -2)  // not the first pass special case (-2)
00449         {
00450           // Changing individual Depth Control params means preset is Unused/Invalid
00451           // if the individual values are not the same as the preset values
00452           if (dc_preset != -1 && current_dc != last_dc)
00453           {
00454             ROS_DEBUG_STREAM(nodelet_name_ << " - Forcing Depth Control Preset to Unused");
00455             setDynamicReconfigDepthControlPreset(-1);
00456           }
00457         }
00458         else
00459         {
00460           // This is the first pass callback, in this instance we allow the
00461           // dc_preset to trump the individual values as it might have been
00462           // set from the launch file. To allow override of individual values,
00463           // set dc_preset to -1 (Unused) in the launch file.
00464           if (dc_preset != -1)
00465           {
00466             ROS_INFO_STREAM(nodelet_name_ << " - Initializing Depth Control Preset to " << dc_preset);
00467             ROS_DEBUG_STREAM(nodelet_name_ << " - NOTICE: Individual Depth Control values " <<
00468                 "set by params will be ignored; set r200_dc_preset=-1 to override.");
00469             rs_apply_depth_control_preset(rs_device_, dc_preset);
00470 
00471             // Save the preset value string
00472             last_dc = setDynamicReconfigDepthControlIndividuals();
00473           }
00474         }
00475       }
00476       else
00477       {
00478         // Changing individual Depth Control params means preset is Unused/Invalid
00479         // if the individual values are not the same as the preset values
00480         if (dc_preset != -1 && current_dc != last_dc)
00481         {
00482           ROS_DEBUG_STREAM(nodelet_name_ << " - Forcing Depth Control Preset to Unused");
00483           setDynamicReconfigDepthControlPreset(-1);
00484         }
00485       }
00486     }
00487     else
00488     { // Individual Depth Control not set
00489       if (bit_level.test(6))  // 2^6 = 64 : Depth Control Preset
00490       {
00491         dc_preset = config.r200_dc_preset;
00492 
00493         if (dc_preset != -1)
00494         {
00495           ROS_DEBUG_STREAM(nodelet_name_ << " - Set Depth Control Preset to " << dc_preset);
00496           rs_apply_depth_control_preset(rs_device_, dc_preset);
00497 
00498           // Save the preset value string
00499           last_dc = setDynamicReconfigDepthControlIndividuals();
00500         }
00501       }
00502     }
00503 
00504     rs_set_device_option(rs_device_, RS_OPTION_FISHEYE_EXPOSURE,
00505         config.fisheye_exposure, 0);
00506     rs_set_device_option(rs_device_, RS_OPTION_FISHEYE_GAIN, config.fisheye_gain, 0);
00507     rs_set_device_option(rs_device_, RS_OPTION_FISHEYE_ENABLE_AUTO_EXPOSURE, config.fisheye_enable_auto_exposure, 0);
00508     rs_set_device_option(rs_device_, RS_OPTION_FISHEYE_AUTO_EXPOSURE_MODE, config.fisheye_auto_exposure_mode, 0);
00509     rs_set_device_option(rs_device_, RS_OPTION_FISHEYE_AUTO_EXPOSURE_ANTIFLICKER_RATE,
00510         config.fisheye_auto_exposure_antiflicker_rate, 0);
00511     rs_set_device_option(rs_device_, RS_OPTION_FISHEYE_AUTO_EXPOSURE_PIXEL_SAMPLE_RATE,
00512         config.fisheye_auto_exposure_pixel_sample_rate, 0);
00513     rs_set_device_option(rs_device_, RS_OPTION_FISHEYE_AUTO_EXPOSURE_SKIP_FRAMES,
00514         config.fisheye_auto_exposure_skip_frames, 0);
00515     rs_set_device_option(rs_device_, RS_OPTION_FRAMES_QUEUE_SIZE, config.frames_queue_size, 0);
00516     rs_set_device_option(rs_device_, RS_OPTION_HARDWARE_LOGGER_ENABLED, config.hardware_logger_enabled, 0);
00517   }
00518 
00519   /*
00520    * Publish IMU.
00521    */
00522   void ZR300Nodelet::publishIMU()
00523   {
00524     prev_imu_ts_ = -1;
00525     while (ros::ok())
00526     {
00527       if (start_stop_srv_called_ == true)
00528       {
00529         if (start_camera_ == true)
00530         {
00531           ROS_INFO_STREAM(nodelet_name_ << " - " << startCamera());
00532         }
00533         else
00534         {
00535           ROS_INFO_STREAM(nodelet_name_ << " - " << stopCamera());
00536         }
00537         start_stop_srv_called_ = false;
00538       }
00539 
00540       if (enable_[RS_STREAM_DEPTH] != rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0))
00541       {
00542         stopCamera();
00543         setStreams();
00544         startCamera();
00545       }
00546 
00547       if (imu_publisher_.getNumSubscribers() > 0)
00548       {
00549         std::unique_lock<std::mutex> lock(imu_mutex_);
00550 
00551         if (prev_imu_ts_ != imu_ts_)
00552         {
00553           sensor_msgs::Imu imu_msg = sensor_msgs::Imu();
00554           imu_msg.header.stamp = ros::Time(camera_start_ts_) + ros::Duration(imu_ts_ * 0.001);
00555           imu_msg.header.frame_id = imu_optical_frame_id_;
00556 
00557           // Setting just the first element to -1.0 because device does not give orientation data
00558           imu_msg.orientation_covariance[0] = -1.0;
00559 
00560           imu_msg.angular_velocity = imu_angular_vel_;
00561           imu_msg.linear_acceleration = imu_linear_accel_;
00562 
00563           imu_publisher_.publish(imu_msg);
00564           prev_imu_ts_ = imu_ts_;
00565         }
00566       }
00567     }
00568     stopIMU();
00569   }
00570 
00571   /*
00572    * Set up IMU -- overrides base class
00573    */
00574   void ZR300Nodelet::setStreams()
00575   {
00576     // enable camera streams
00577     BaseNodelet::setStreams();
00578 
00579     if (enable_imu_ == true)
00580     {
00581       // enable IMU
00582       ROS_INFO_STREAM(nodelet_name_ << " - Enabling IMU");
00583       setIMUCallbacks();
00584       rs_enable_motion_tracking_cpp(rs_device_, new rs::motion_callback(motion_handler_),
00585           new rs::timestamp_callback(timestamp_handler_), &rs_error_);
00586       checkError();
00587       rs_source_ = RS_SOURCE_ALL;  // overrides default to enable motion tracking
00588     }
00589   }
00590 
00591   /*
00592    * Set IMU callbacks.
00593    */
00594   void ZR300Nodelet::setIMUCallbacks()
00595   {
00596     motion_handler_ = [&](rs::motion_data entry)  // NOLINT(build/c++11)
00597     {
00598       std::unique_lock<std::mutex> lock(imu_mutex_);
00599 
00600       if (entry.timestamp_data.source_id == RS_EVENT_IMU_GYRO)
00601       {
00602         imu_angular_vel_.x = entry.axes[0];
00603         imu_angular_vel_.y = entry.axes[1];
00604         imu_angular_vel_.z = entry.axes[2];
00605       }
00606       else if (entry.timestamp_data.source_id == RS_EVENT_IMU_ACCEL)
00607       {
00608         imu_linear_accel_.x = entry.axes[0];
00609         imu_linear_accel_.y = entry.axes[1];
00610         imu_linear_accel_.z = entry.axes[2];
00611       }
00612       imu_ts_ = static_cast<double>(entry.timestamp_data.timestamp);
00613 
00614       ROS_DEBUG_STREAM(" - Motion,\t host time " << imu_ts_
00615           << "\ttimestamp: " << std::setprecision(8) << (double)entry.timestamp_data.timestamp*IMU_UNITS_TO_MSEC
00616           << "\tsource: " << (rs::event)entry.timestamp_data.source_id
00617           << "\tframe_num: " << entry.timestamp_data.frame_number
00618           << "\tx: " << std::setprecision(5) <<  entry.axes[0]
00619           << "\ty: " << entry.axes[1]
00620           << "\tz: " << entry.axes[2]);
00621     };
00622 
00623     // Get timestamp that syncs all sensors.
00624     timestamp_handler_ = [](rs::timestamp_data entry)
00625     {
00626         auto now = std::chrono::system_clock::now().time_since_epoch();
00627         auto sys_time = std::chrono::duration_cast<std::chrono::milliseconds>(now).count();
00628 
00629         ROS_DEBUG_STREAM(" - TimeEvent, host time " << sys_time
00630             << "\ttimestamp: " << std::setprecision(8) << (double)entry.timestamp*IMU_UNITS_TO_MSEC
00631             << "\tsource: " << (rs::event)entry.source_id
00632             << "\tframe_num: " << entry.frame_number);
00633     };
00634   }
00635 
00636   /*
00637   * Set up the callbacks for the camera streams
00638   */
00639   void ZR300Nodelet::setFrameCallbacks()
00640   {
00641     // call base nodelet method
00642     BaseNodelet::setFrameCallbacks();
00643 
00644     fisheye_frame_handler_ = [&](rs::frame frame)  // NOLINT(build/c++11)
00645     {
00646       publishTopic(RS_STREAM_FISHEYE, frame);
00647     };
00648 
00649     ir2_frame_handler_ = [&](rs::frame frame)  // NOLINT(build/c++11)
00650     {
00651       publishTopic(RS_STREAM_INFRARED2, frame);
00652     };
00653 
00654     rs_set_frame_callback_cpp(rs_device_, RS_STREAM_FISHEYE,
00655         new rs::frame_callback(fisheye_frame_handler_), &rs_error_);
00656     checkError();
00657 
00658     rs_set_frame_callback_cpp(rs_device_, RS_STREAM_INFRARED2, new rs::frame_callback(ir2_frame_handler_), &rs_error_);
00659     checkError();
00660   }
00661 
00662   /*
00663    * Get the camera extrinsics
00664    */
00665   void ZR300Nodelet::getCameraExtrinsics()
00666   {
00667     BaseNodelet::getCameraExtrinsics();
00668 
00669     // Get offset between base frame and infrared2 frame
00670     rs_get_device_extrinsics(rs_device_, RS_STREAM_INFRARED2, RS_STREAM_COLOR, &color2ir2_extrinsic_, &rs_error_);
00671     if (rs_error_)
00672     {
00673       ROS_ERROR_STREAM(nodelet_name_ << " - Verify camera is calibrated!");
00674     }
00675     checkError();
00676 
00677     // Get offset between base frame and fisheye frame
00678     rs_get_device_extrinsics(rs_device_, RS_STREAM_FISHEYE, RS_STREAM_COLOR, &color2fisheye_extrinsic_, &rs_error_);
00679     if (rs_error_)
00680     {
00681       ROS_ERROR_STREAM(nodelet_name_ << " - Verify camera is calibrated!");
00682     }
00683     checkError();
00684 
00685     // Get offset between base frame and imu frame
00686     rs_get_motion_extrinsics_from(rs_device_, RS_STREAM_COLOR, &color2imu_extrinsic_, &rs_error_);
00687     if (rs_error_)
00688     {
00689 /*  Temporarily hardcoding the values until fully supported by librealsense API.  */
00690       // ROS_ERROR_STREAM(nodelet_name_ << " - Verify camera is calibrated!");
00691       ROS_WARN_STREAM(nodelet_name_ << " - Using Hardcoded extrinsic for IMU.");
00692       rs_free_error(rs_error_);
00693       rs_error_ = NULL;
00694 
00695       color2imu_extrinsic_.translation[0] = -0.07;
00696       color2imu_extrinsic_.translation[1] = 0.0;
00697       color2imu_extrinsic_.translation[2] = 0.0;
00698     }
00699     // checkError();
00700   }
00701 
00702   /*
00703    * Publish Static transforms.
00704    */
00705   void ZR300Nodelet::publishStaticTransforms()
00706   {
00707     BaseNodelet::publishStaticTransforms();
00708 
00709     tf::Quaternion q_i2io;
00710     tf::Quaternion q_f2fo;
00711     tf::Quaternion q_imu2imuo;
00712     geometry_msgs::TransformStamped b2i_msg;
00713     geometry_msgs::TransformStamped i2io_msg;
00714     geometry_msgs::TransformStamped b2f_msg;
00715     geometry_msgs::TransformStamped f2fo_msg;
00716     geometry_msgs::TransformStamped b2imu_msg;
00717     geometry_msgs::TransformStamped imu2imuo_msg;
00718 
00719     // Transform base frame to infrared2 frame
00720     b2i_msg.header.stamp = transform_ts_;
00721     b2i_msg.header.frame_id = base_frame_id_;
00722     b2i_msg.child_frame_id = frame_id_[RS_STREAM_INFRARED2];
00723     b2i_msg.transform.translation.x =  color2ir2_extrinsic_.translation[2];
00724     b2i_msg.transform.translation.y = -color2ir2_extrinsic_.translation[0];
00725     b2i_msg.transform.translation.z = -color2ir2_extrinsic_.translation[1];
00726     b2i_msg.transform.rotation.x = 0;
00727     b2i_msg.transform.rotation.y = 0;
00728     b2i_msg.transform.rotation.z = 0;
00729     b2i_msg.transform.rotation.w = 1;
00730     static_tf_broadcaster_.sendTransform(b2i_msg);
00731 
00732     // Transform infrared2 frame to infrared2 optical frame
00733     q_i2io.setRPY(-M_PI/2, 0.0, -M_PI/2);
00734     i2io_msg.header.stamp = transform_ts_;
00735     i2io_msg.header.frame_id = frame_id_[RS_STREAM_INFRARED2];
00736     i2io_msg.child_frame_id = optical_frame_id_[RS_STREAM_INFRARED2];
00737     i2io_msg.transform.translation.x = 0;
00738     i2io_msg.transform.translation.y = 0;
00739     i2io_msg.transform.translation.z = 0;
00740     i2io_msg.transform.rotation.x = q_i2io.getX();
00741     i2io_msg.transform.rotation.y = q_i2io.getY();
00742     i2io_msg.transform.rotation.z = q_i2io.getZ();
00743     i2io_msg.transform.rotation.w = q_i2io.getW();
00744     static_tf_broadcaster_.sendTransform(i2io_msg);
00745 
00746     // Transform base frame to fisheye frame
00747     b2f_msg.header.stamp = transform_ts_;
00748     b2f_msg.header.frame_id = base_frame_id_;
00749     b2f_msg.child_frame_id = frame_id_[RS_STREAM_FISHEYE];
00750     b2f_msg.transform.translation.x =  color2fisheye_extrinsic_.translation[2];
00751     b2f_msg.transform.translation.y = -color2fisheye_extrinsic_.translation[0];
00752     b2f_msg.transform.translation.z = -color2fisheye_extrinsic_.translation[1];
00753     b2f_msg.transform.rotation.x = 0;
00754     b2f_msg.transform.rotation.y = 0;
00755     b2f_msg.transform.rotation.z = 0;
00756     b2f_msg.transform.rotation.w = 1;
00757     static_tf_broadcaster_.sendTransform(b2f_msg);
00758 
00759     // Transform fisheye frame to fisheye optical frame
00760     q_f2fo.setRPY(-M_PI/2, 0.0, -M_PI/2);
00761     f2fo_msg.header.stamp = transform_ts_;
00762     f2fo_msg.header.frame_id = frame_id_[RS_STREAM_FISHEYE];
00763     f2fo_msg.child_frame_id = optical_frame_id_[RS_STREAM_FISHEYE];
00764     f2fo_msg.transform.translation.x = 0;
00765     f2fo_msg.transform.translation.y = 0;
00766     f2fo_msg.transform.translation.z = 0;
00767     f2fo_msg.transform.rotation.x = q_f2fo.getX();
00768     f2fo_msg.transform.rotation.y = q_f2fo.getY();
00769     f2fo_msg.transform.rotation.z = q_f2fo.getZ();
00770     f2fo_msg.transform.rotation.w = q_f2fo.getW();
00771     static_tf_broadcaster_.sendTransform(f2fo_msg);
00772 
00773     // Transform base frame to imu frame
00774     b2imu_msg.header.stamp = transform_ts_;
00775     b2imu_msg.header.frame_id = base_frame_id_;
00776     b2imu_msg.child_frame_id = imu_frame_id_;
00777     b2imu_msg.transform.translation.x =  color2imu_extrinsic_.translation[2];
00778     b2imu_msg.transform.translation.y = -color2imu_extrinsic_.translation[0];
00779     b2imu_msg.transform.translation.z = -color2imu_extrinsic_.translation[1];
00780     b2imu_msg.transform.rotation.x = 0;
00781     b2imu_msg.transform.rotation.y = 0;
00782     b2imu_msg.transform.rotation.z = 0;
00783     b2imu_msg.transform.rotation.w = 1;
00784     static_tf_broadcaster_.sendTransform(b2imu_msg);
00785 
00786     // Transform imu frame to imu optical frame
00787     q_imu2imuo.setRPY(-M_PI/2, 0.0, -M_PI/2);
00788     imu2imuo_msg.header.stamp = transform_ts_;
00789     imu2imuo_msg.header.frame_id = imu_frame_id_;
00790     imu2imuo_msg.child_frame_id = imu_optical_frame_id_;
00791     imu2imuo_msg.transform.translation.x = 0;
00792     imu2imuo_msg.transform.translation.y = 0;
00793     imu2imuo_msg.transform.translation.z = 0;
00794     imu2imuo_msg.transform.rotation.x = q_imu2imuo.getX();
00795     imu2imuo_msg.transform.rotation.y = q_imu2imuo.getY();
00796     imu2imuo_msg.transform.rotation.z = q_imu2imuo.getZ();
00797     imu2imuo_msg.transform.rotation.w = q_imu2imuo.getW();
00798     static_tf_broadcaster_.sendTransform(imu2imuo_msg);
00799   }
00800 
00801   /*
00802    * Publish Dynamic transforms.
00803    */
00804   void ZR300Nodelet::publishDynamicTransforms()
00805   {
00806     tf::Transform tr;
00807     tf::Quaternion q;
00808 
00809     BaseNodelet::publishDynamicTransforms();
00810 
00811     // Transform base frame to infrared2 frame
00812     tr.setOrigin(tf::Vector3(
00813            color2ir2_extrinsic_.translation[2],
00814           -color2ir2_extrinsic_.translation[0],
00815           -color2ir2_extrinsic_.translation[1]));
00816     tr.setRotation(tf::Quaternion(0, 0, 0, 1));
00817     dynamic_tf_broadcaster_.sendTransform(tf::StampedTransform(tr, transform_ts_,
00818           base_frame_id_, frame_id_[RS_STREAM_INFRARED2]));
00819 
00820     // Transform infrared2 frame to infrared2 optical frame
00821     tr.setOrigin(tf::Vector3(0, 0, 0));
00822     q.setRPY(-M_PI/2, 0.0, -M_PI/2);
00823     tr.setRotation(q);
00824     dynamic_tf_broadcaster_.sendTransform(tf::StampedTransform(tr, transform_ts_,
00825           frame_id_[RS_STREAM_INFRARED2], optical_frame_id_[RS_STREAM_INFRARED2]));
00826 
00827     // Transform base frame to fisheye frame
00828     tr.setOrigin(tf::Vector3(
00829            color2fisheye_extrinsic_.translation[2],
00830           -color2fisheye_extrinsic_.translation[0],
00831           -color2fisheye_extrinsic_.translation[1]));
00832     tr.setRotation(tf::Quaternion(0, 0, 0, 1));
00833     dynamic_tf_broadcaster_.sendTransform(tf::StampedTransform(tr, transform_ts_,
00834           base_frame_id_, frame_id_[RS_STREAM_FISHEYE]));
00835 
00836     // Transform fisheye frame to fisheye optical frame
00837     tr.setOrigin(tf::Vector3(0, 0, 0));
00838     q.setRPY(-M_PI/2, 0.0, -M_PI/2);
00839     tr.setRotation(q);
00840     dynamic_tf_broadcaster_.sendTransform(tf::StampedTransform(tr, transform_ts_,
00841           frame_id_[RS_STREAM_FISHEYE], optical_frame_id_[RS_STREAM_FISHEYE]));
00842 
00843     // Transform base frame to imu frame
00844     tr.setOrigin(tf::Vector3(
00845            color2imu_extrinsic_.translation[2],
00846           -color2imu_extrinsic_.translation[0],
00847           -color2imu_extrinsic_.translation[1]));
00848     tr.setRotation(tf::Quaternion(0, 0, 0, 1));
00849     dynamic_tf_broadcaster_.sendTransform(tf::StampedTransform(tr, transform_ts_,
00850           base_frame_id_, imu_frame_id_));
00851 
00852     // Transform imu frame to imu optical frame
00853     tr.setOrigin(tf::Vector3(0, 0, 0));
00854     q.setRPY(-M_PI/2, 0.0, -M_PI/2);
00855     tr.setRotation(q);
00856     dynamic_tf_broadcaster_.sendTransform(tf::StampedTransform(tr, transform_ts_,
00857           imu_frame_id_, imu_optical_frame_id_));
00858   }
00859 
00860   /*
00861    * Stop the IMU and motion tracking
00862    */
00863   void ZR300Nodelet::stopIMU()
00864   {
00865     rs_stop_source(rs_device_, (rs_source)rs::source::motion_data, &rs_error_);
00866     checkError();
00867     rs_disable_motion_tracking(rs_device_, &rs_error_);
00868     checkError();
00869   }
00870 }  // namespace realsense_camera


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