zr300_nodelet.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  Copyright (c) 2017, Intel Corporation
3  All rights reserved.
4 
5  Redistribution and use in source and binary forms, with or without
6  modification, are permitted provided that the following conditions are met:
7 
8  1. Redistributions of source code must retain the above copyright notice, this
9  list of conditions and the following disclaimer.
10 
11  2. Redistributions in binary form must reproduce the above copyright notice,
12  this list of conditions and the following disclaimer in the documentation
13  and/or other materials provided with the distribution.
14 
15  3. Neither the name of the copyright holder nor the names of its contributors
16  may be used to endorse or promote products derived from this software without
17  specific prior written permission.
18 
19  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22  DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
23  FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
24  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
25  SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
27  OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
28  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29  *******************************************************************************/
30 
31 #include <string>
32 #include <algorithm>
33 #include <vector>
34 
36 
38 
39 namespace realsense_camera
40 {
41  /*
42  * Nodelet Destructor.
43  */
44  ZR300Nodelet::~ZR300Nodelet()
45  {
46  if (enable_imu_ == true)
47  {
48  stopIMU();
49  // clean up imu thread
50  imu_thread_->join();
51  }
52  }
53 
54  /*
55  * Initialize the nodelet.
56  */
57  void ZR300Nodelet::onInit()
58  {
61  cv_type_[RS_STREAM_COLOR] = CV_8UC3;
62  unit_step_size_[RS_STREAM_COLOR] = sizeof(unsigned char) * 3;
63 
64  format_[RS_STREAM_DEPTH] = RS_FORMAT_Z16;
66  cv_type_[RS_STREAM_DEPTH] = CV_16UC1;
67  unit_step_size_[RS_STREAM_DEPTH] = sizeof(uint16_t);
68 
71  cv_type_[RS_STREAM_INFRARED] = CV_8UC1;
72  unit_step_size_[RS_STREAM_INFRARED] = sizeof(unsigned char);
73 
76  cv_type_[RS_STREAM_INFRARED2] = CV_8UC1;
77  unit_step_size_[RS_STREAM_INFRARED2] = sizeof(unsigned char);
78 
81  cv_type_[RS_STREAM_FISHEYE] = CV_8UC1;
82  unit_step_size_[RS_STREAM_FISHEYE] = sizeof(unsigned char);
83 
84  max_z_ = ZR300_MAX_Z;
85 
86  BaseNodelet::onInit();
87 
88  if (enable_imu_ == true)
89  {
90  imu_thread_ =
91  boost::shared_ptr<boost::thread>(new boost::thread(boost::bind(&ZR300Nodelet::publishIMU, this)));
92  }
93  }
94 
95  /*
96  * Get the nodelet parameters.
97  */
98  void ZR300Nodelet::getParameters()
99  {
100  BaseNodelet::getParameters();
101  pnh_.param("ir2_frame_id", frame_id_[RS_STREAM_INFRARED2], DEFAULT_IR2_FRAME_ID);
102  pnh_.param("ir2_optical_frame_id", optical_frame_id_[RS_STREAM_INFRARED2], DEFAULT_IR2_OPTICAL_FRAME_ID);
103  pnh_.param("enable_fisheye", enable_[RS_STREAM_FISHEYE], ENABLE_FISHEYE);
104  pnh_.param("enable_imu", enable_imu_, ENABLE_IMU);
105  pnh_.param("enable_ir2", enable_[RS_STREAM_INFRARED2], ENABLE_IR2);
106  pnh_.param("fisheye_width", width_[RS_STREAM_FISHEYE], FISHEYE_WIDTH);
107  pnh_.param("fisheye_height", height_[RS_STREAM_FISHEYE], FISHEYE_HEIGHT);
108  pnh_.param("fisheye_fps", fps_[RS_STREAM_FISHEYE], FISHEYE_FPS);
109  pnh_.param("fisheye_frame_id", frame_id_[RS_STREAM_FISHEYE], DEFAULT_FISHEYE_FRAME_ID);
110  pnh_.param("fisheye_optical_frame_id", optical_frame_id_[RS_STREAM_FISHEYE], DEFAULT_FISHEYE_OPTICAL_FRAME_ID);
111  pnh_.param("imu_frame_id", imu_frame_id_, DEFAULT_IMU_FRAME_ID);
112  pnh_.param("imu_optical_frame_id", imu_optical_frame_id_, DEFAULT_IMU_OPTICAL_FRAME_ID);
113 
114  // set IR2 stream to match depth
115  width_[RS_STREAM_INFRARED2] = width_[RS_STREAM_DEPTH];
116  height_[RS_STREAM_INFRARED2] = height_[RS_STREAM_DEPTH];
117  fps_[RS_STREAM_INFRARED2] = fps_[RS_STREAM_DEPTH];
118  }
119 
120  /*
121  * Advertise topics.
122  */
123  void ZR300Nodelet::advertiseTopics()
124  {
125  BaseNodelet::advertiseTopics();
126  ros::NodeHandle ir2_nh(nh_, IR2_NAMESPACE);
127  image_transport::ImageTransport ir2_image_transport(ir2_nh);
128  camera_publisher_[RS_STREAM_INFRARED2] = ir2_image_transport.advertiseCamera(IR2_TOPIC, 1);
129 
130  ros::NodeHandle fisheye_nh(nh_, FISHEYE_NAMESPACE);
131  image_transport::ImageTransport fisheye_image_transport(fisheye_nh);
132  camera_publisher_[RS_STREAM_FISHEYE] = fisheye_image_transport.advertiseCamera(FISHEYE_TOPIC, 1);
133 
134  ros::NodeHandle imu_nh(nh_, IMU_NAMESPACE);
135  imu_publisher_ = imu_nh.advertise<sensor_msgs::Imu>(IMU_TOPIC, 1000);
136  }
137 
138  /*
139  * Advertise services.
140  */
141  void ZR300Nodelet::advertiseServices()
142  {
143  BaseNodelet::advertiseServices();
144  get_imu_info_ = pnh_.advertiseService(IMU_INFO_SERVICE, &ZR300Nodelet::getIMUInfo, this);
145  }
146 
147  /*
148  * Get IMU Info.
149  */
150  bool ZR300Nodelet::getIMUInfo(realsense_camera::GetIMUInfo::Request & req,
151  realsense_camera::GetIMUInfo::Response & res)
152  {
153  ros::Time header_stamp = ros::Time::now();
154  std::string header_frame_id;
155 
156 
157  rs_motion_intrinsics imu_intrinsics;
158  rs_get_motion_intrinsics(rs_device_, &imu_intrinsics, &rs_error_);
159  if (rs_error_)
160  {
161  ROS_ERROR_STREAM(nodelet_name_ << " - Verify camera firmware version!");
162  }
163  checkError();
164 
165  int index = 0;
166  res.accel.header.stamp = header_stamp;
167  res.accel.header.frame_id = IMU_ACCEL;
168  std::transform(res.accel.header.frame_id.begin(), res.accel.header.frame_id.end(),
169  res.accel.header.frame_id.begin(), ::tolower);
170 
171  for (int i = 0; i < 3; ++i)
172  {
173  for (int j = 0; j < 4; ++j)
174  {
175  res.accel.data[index] = imu_intrinsics.acc.data[i][j];
176  ++index;
177  }
178  res.accel.noise_variances[i] = imu_intrinsics.acc.noise_variances[i];
179  res.accel.bias_variances[i] = imu_intrinsics.acc.bias_variances[i];
180  }
181 
182  index = 0;
183  res.gyro.header.stamp = header_stamp;
184  res.gyro.header.frame_id = IMU_GYRO;
185  std::transform(res.gyro.header.frame_id.begin(), res.gyro.header.frame_id.end(),
186  res.gyro.header.frame_id.begin(), ::tolower);
187  for (int i = 0; i < 3; ++i)
188  {
189  for (int j = 0; j < 4; ++j)
190  {
191  res.gyro.data[index] = imu_intrinsics.gyro.data[i][j];
192  ++index;
193  }
194  res.gyro.noise_variances[i] = imu_intrinsics.gyro.noise_variances[i];
195  res.gyro.bias_variances[i] = imu_intrinsics.gyro.bias_variances[i];
196  }
197 
198  return true;
199  }
200 
201  /*
202  * Set Dynamic Reconfigure Server and return the dynamic params.
203  */
204  std::vector<std::string> ZR300Nodelet::setDynamicReconfServer()
205  {
206  dynamic_reconf_server_.reset(new dynamic_reconfigure::Server<realsense_camera::zr300_paramsConfig>(pnh_));
207 
208  // Get dynamic options from the dynamic reconfigure server.
209  realsense_camera::zr300_paramsConfig params_config;
210  dynamic_reconf_server_->getConfigDefault(params_config);
211  std::vector<realsense_camera::zr300_paramsConfig::AbstractParamDescriptionConstPtr> param_desc =
212  params_config.__getParamDescriptions__();
213  std::vector<std::string> dynamic_params;
214  for (realsense_camera::zr300_paramsConfig::AbstractParamDescriptionConstPtr param_desc_ptr : param_desc)
215  {
216  dynamic_params.push_back((* param_desc_ptr).name);
217  }
218 
219  return dynamic_params;
220  }
221 
222  /*
223  * Start Dynamic Reconfigure Callback.
224  */
225  void ZR300Nodelet::startDynamicReconfCallback()
226  {
227  dynamic_reconf_server_->setCallback(boost::bind(&ZR300Nodelet::configCallback, this, _1, _2));
228  }
229 
230  /*
231  * Change the Depth Control Preset
232  */
233  void ZR300Nodelet::setDynamicReconfigDepthControlPreset(int preset)
234  {
235  // There is not a C++ API for dynamic reconfig so we need to use a system call
236  // Adding the sleep to ensure the current callback can end before we
237  // attempt the next callback from the system call.
238  std::vector<std::string> argv;
239  argv.push_back("rosrun");
240  argv.push_back("dynamic_reconfigure");
241  argv.push_back("dynparam");
242  argv.push_back("set");
243  argv.push_back(nodelet_name_);
244  argv.push_back("r200_dc_preset");
245  argv.push_back(std::to_string(preset));
246 
247  wrappedSystem(argv);
248  }
249 
250  /*
251  * Change the Depth Control Individual values
252  * GET ALL of the DC options from librealsense
253  * Call dynamic reconfig and set all 10 values as a set
254  */
255  std::string ZR300Nodelet::setDynamicReconfigDepthControlIndividuals()
256  {
257  std::string current_param;
258  std::string current_dc;
259  std::string option_value;
260 
261  // There is not a C++ API for dynamic reconfig so we need to use a system call
262  // Adding the sleep to ensure the current callback can end before we
263  // attempt the next callback from the system call.
264  std::vector<std::string> argv;
265  argv.push_back("rosrun");
266  argv.push_back("dynamic_reconfigure");
267  argv.push_back("dynparam");
268  argv.push_back("set");
269  argv.push_back(nodelet_name_);
270 
271  current_param = "{";
272 
273  option_value =
274  std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
276  current_param += "'r200_dc_estimate_median_decrement':" + option_value + ", ";
277  current_dc += option_value + ":";
278 
279  option_value =
280  std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
282  current_param += "'r200_dc_estimate_median_increment':" + option_value + ", ";
283  current_dc += option_value + ":";
284 
285  option_value =
286  std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
288  current_param += "'r200_dc_median_threshold':" + option_value + ", ";
289  current_dc += option_value + ":";
290 
291  option_value =
292  std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
294  current_param += "'r200_dc_score_minimum_threshold':" + option_value + ", ";
295  current_dc += option_value + ":";
296 
297  option_value =
298  std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
300  current_param += "'r200_dc_score_maximum_threshold':" + option_value + ", ";
301  current_dc += option_value + ":";
302 
303  option_value =
304  std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
306  current_param += "'r200_dc_texture_count_threshold':" + option_value + ", ";
307  current_dc += option_value + ":";
308 
309  option_value =
310  std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
312  current_param += "'r200_dc_texture_difference_threshold':" + option_value + ", ";
313  current_dc += option_value + ":";
314 
315  option_value =
316  std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
318  current_param += "'r200_dc_second_peak_threshold':" + option_value + ", ";
319  current_dc += option_value + ":";
320 
321  option_value =
322  std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
324  current_param += "'r200_dc_neighbor_threshold':" + option_value + ", ";
325  current_dc += option_value + ":";
326 
327  option_value =
328  std::to_string(static_cast<uint32_t>(rs_get_device_option(rs_device_,
330  current_param += "'r200_dc_lr_threshold':" + option_value + "}";
331  current_dc += option_value;
332 
333  ROS_DEBUG_STREAM(nodelet_name_ << " - Setting DC: " << current_param);
334 
335  argv.push_back(current_param);
336 
337  wrappedSystem(argv);
338 
339  return current_dc;
340  }
341 
342  /*
343  * Get the dynamic param values.
344  */
345  void ZR300Nodelet::configCallback(realsense_camera::zr300_paramsConfig &config, uint32_t level)
346  {
347  // Save the dc_preset value as there is no getter API for this value
348  static int dc_preset = -2;
349  int previous_dc_preset = dc_preset;
350  // Save the last depth control preset values as a string
351  static std::string last_dc;
352 
353  // level is the ORing of all levels which have a changed value
354  std::bitset<32> bit_level{level};
355 
356  if (bit_level.test(6)) // 2^6 = 64 : Depth Control Preset
357  {
358  ROS_INFO_STREAM(nodelet_name_ << " - Setting dynamic camera options" <<
359  " (r200_dc_preset=" << config.r200_dc_preset << ")");
360  }
361  else
362  {
363  ROS_INFO_STREAM(nodelet_name_ << " - Setting dynamic camera options");
364  }
365 
366  // set the depth enable
367  BaseNodelet::setDepthEnable(config.enable_depth);
368 
369  // Set common options
370  rs_set_device_option(rs_device_, RS_OPTION_COLOR_BACKLIGHT_COMPENSATION, config.color_backlight_compensation, 0);
371  rs_set_device_option(rs_device_, RS_OPTION_COLOR_BRIGHTNESS, config.color_brightness, 0);
372  rs_set_device_option(rs_device_, RS_OPTION_COLOR_CONTRAST, config.color_contrast, 0);
373  rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAIN, config.color_gain, 0);
374  rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAMMA, config.color_gamma, 0);
375  rs_set_device_option(rs_device_, RS_OPTION_COLOR_HUE, config.color_hue, 0);
376  rs_set_device_option(rs_device_, RS_OPTION_COLOR_SATURATION, config.color_saturation, 0);
377  rs_set_device_option(rs_device_, RS_OPTION_COLOR_SHARPNESS, config.color_sharpness, 0);
378  rs_set_device_option(rs_device_, RS_OPTION_COLOR_ENABLE_AUTO_EXPOSURE, config.color_enable_auto_exposure, 0);
379  if (config.color_enable_auto_exposure == 0)
380  {
381  rs_set_device_option(rs_device_, RS_OPTION_COLOR_EXPOSURE, config.color_exposure, 0);
382  }
384  config.color_enable_auto_white_balance, 0);
385  if (config.color_enable_auto_white_balance == 0)
386  {
387  rs_set_device_option(rs_device_, RS_OPTION_COLOR_WHITE_BALANCE, config.color_white_balance, 0);
388  }
389 
390  // Set R200 specific options
391  rs_set_device_option(rs_device_, RS_OPTION_R200_LR_AUTO_EXPOSURE_ENABLED, config.r200_lr_auto_exposure_enabled, 0);
392  if (config.r200_lr_auto_exposure_enabled == 0)
393  {
394  rs_set_device_option(rs_device_, RS_OPTION_R200_LR_GAIN, config.r200_lr_gain, 0);
395  rs_set_device_option(rs_device_, RS_OPTION_R200_LR_EXPOSURE, config.r200_lr_exposure, 0);
396  }
397 
398  rs_set_device_option(rs_device_, RS_OPTION_R200_EMITTER_ENABLED, config.r200_emitter_enabled, 0);
399  rs_set_device_option(rs_device_, RS_OPTION_R200_DEPTH_CLAMP_MIN, config.r200_depth_clamp_min, 0);
400  rs_set_device_option(rs_device_, RS_OPTION_R200_DEPTH_CLAMP_MAX, config.r200_depth_clamp_max, 0);
401 
402  // Depth Control Group Settings
403  // NOTE: do NOT use the config.groups values as they are zero the first time called
404  if (bit_level.test(5)) // 2^5 = 32 : Individual Depth Control settings
405  {
406  std::string current_dc;
407 
408  ROS_DEBUG_STREAM(nodelet_name_ << " - Setting Individual Depth Control");
409 
411  config.r200_dc_estimate_median_decrement, 0);
412  current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_estimate_median_decrement)) + ":";
414  config.r200_dc_estimate_median_increment, 0);
415  current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_estimate_median_increment)) + ":";
417  config.r200_dc_median_threshold, 0);
418  current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_median_threshold)) + ":";
420  config.r200_dc_score_minimum_threshold, 0);
421  current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_score_minimum_threshold)) + ":";
423  config.r200_dc_score_maximum_threshold, 0);
424  current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_score_maximum_threshold)) + ":";
426  config.r200_dc_texture_count_threshold, 0);
427  current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_texture_count_threshold)) + ":";
429  config.r200_dc_texture_difference_threshold, 0);
430  current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_texture_difference_threshold)) + ":";
432  config.r200_dc_second_peak_threshold, 0);
433  current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_second_peak_threshold)) + ":";
435  config.r200_dc_neighbor_threshold, 0);
436  current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_neighbor_threshold)) + ":";
438  config.r200_dc_lr_threshold, 0);
439  current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_lr_threshold));
440 
441  // Preset also changed in the same update callback
442  // This is either First callback special case, or both set via
443  // dynamic configure command line.
444  if (bit_level.test(6)) // 2^6 = 64 : Depth Control Preset
445  {
446  dc_preset = config.r200_dc_preset;
447 
448  if (previous_dc_preset != -2) // not the first pass special case (-2)
449  {
450  // Changing individual Depth Control params means preset is Unused/Invalid
451  // if the individual values are not the same as the preset values
452  if (dc_preset != -1 && current_dc != last_dc)
453  {
454  ROS_DEBUG_STREAM(nodelet_name_ << " - Forcing Depth Control Preset to Unused");
455  setDynamicReconfigDepthControlPreset(-1);
456  }
457  }
458  else
459  {
460  // This is the first pass callback, in this instance we allow the
461  // dc_preset to trump the individual values as it might have been
462  // set from the launch file. To allow override of individual values,
463  // set dc_preset to -1 (Unused) in the launch file.
464  if (dc_preset != -1)
465  {
466  ROS_INFO_STREAM(nodelet_name_ << " - Initializing Depth Control Preset to " << dc_preset);
467  ROS_DEBUG_STREAM(nodelet_name_ << " - NOTICE: Individual Depth Control values " <<
468  "set by params will be ignored; set r200_dc_preset=-1 to override.");
469  rs_apply_depth_control_preset(rs_device_, dc_preset);
470 
471  // Save the preset value string
472  last_dc = setDynamicReconfigDepthControlIndividuals();
473  }
474  }
475  }
476  else
477  {
478  // Changing individual Depth Control params means preset is Unused/Invalid
479  // if the individual values are not the same as the preset values
480  if (dc_preset != -1 && current_dc != last_dc)
481  {
482  ROS_DEBUG_STREAM(nodelet_name_ << " - Forcing Depth Control Preset to Unused");
483  setDynamicReconfigDepthControlPreset(-1);
484  }
485  }
486  }
487  else
488  { // Individual Depth Control not set
489  if (bit_level.test(6)) // 2^6 = 64 : Depth Control Preset
490  {
491  dc_preset = config.r200_dc_preset;
492 
493  if (dc_preset != -1)
494  {
495  ROS_DEBUG_STREAM(nodelet_name_ << " - Set Depth Control Preset to " << dc_preset);
496  rs_apply_depth_control_preset(rs_device_, dc_preset);
497 
498  // Save the preset value string
499  last_dc = setDynamicReconfigDepthControlIndividuals();
500  }
501  }
502  }
503 
505  config.fisheye_exposure, 0);
506  rs_set_device_option(rs_device_, RS_OPTION_FISHEYE_GAIN, config.fisheye_gain, 0);
507  rs_set_device_option(rs_device_, RS_OPTION_FISHEYE_ENABLE_AUTO_EXPOSURE, config.fisheye_enable_auto_exposure, 0);
508  rs_set_device_option(rs_device_, RS_OPTION_FISHEYE_AUTO_EXPOSURE_MODE, config.fisheye_auto_exposure_mode, 0);
510  config.fisheye_auto_exposure_antiflicker_rate, 0);
512  config.fisheye_auto_exposure_pixel_sample_rate, 0);
514  config.fisheye_auto_exposure_skip_frames, 0);
515  rs_set_device_option(rs_device_, RS_OPTION_FRAMES_QUEUE_SIZE, config.frames_queue_size, 0);
516  rs_set_device_option(rs_device_, RS_OPTION_HARDWARE_LOGGER_ENABLED, config.hardware_logger_enabled, 0);
517  }
518 
519  /*
520  * Publish IMU.
521  */
522  void ZR300Nodelet::publishIMU()
523  {
524  prev_imu_ts_ = -1;
525  while (ros::ok())
526  {
527  if (start_stop_srv_called_ == true)
528  {
529  if (start_camera_ == true)
530  {
531  ROS_INFO_STREAM(nodelet_name_ << " - " << startCamera());
532  }
533  else
534  {
535  ROS_INFO_STREAM(nodelet_name_ << " - " << stopCamera());
536  }
537  start_stop_srv_called_ = false;
538  }
539 
540  if (enable_[RS_STREAM_DEPTH] != rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0))
541  {
542  stopCamera();
543  setStreams();
544  startCamera();
545  }
546 
547  if (imu_publisher_.getNumSubscribers() > 0)
548  {
549  std::unique_lock<std::mutex> lock(imu_mutex_);
550 
551  if (prev_imu_ts_ != imu_ts_)
552  {
553  sensor_msgs::Imu imu_msg = sensor_msgs::Imu();
554  imu_msg.header.stamp = ros::Time(camera_start_ts_) + ros::Duration(imu_ts_ * 0.001);
555  imu_msg.header.frame_id = imu_optical_frame_id_;
556 
557  // Setting just the first element to -1.0 because device does not give orientation data
558  imu_msg.orientation_covariance[0] = -1.0;
559 
560  imu_msg.angular_velocity = imu_angular_vel_;
561  imu_msg.linear_acceleration = imu_linear_accel_;
562 
563  imu_publisher_.publish(imu_msg);
564  prev_imu_ts_ = imu_ts_;
565  }
566  }
567  }
568  stopIMU();
569  }
570 
571  /*
572  * Set up IMU -- overrides base class
573  */
574  void ZR300Nodelet::setStreams()
575  {
576  // enable camera streams
577  BaseNodelet::setStreams();
578 
579  if (enable_imu_ == true)
580  {
581  // enable IMU
582  ROS_INFO_STREAM(nodelet_name_ << " - Enabling IMU");
583  setIMUCallbacks();
584  rs_enable_motion_tracking_cpp(rs_device_, new rs::motion_callback(motion_handler_),
585  new rs::timestamp_callback(timestamp_handler_), &rs_error_);
586  checkError();
587  rs_source_ = RS_SOURCE_ALL; // overrides default to enable motion tracking
588  }
589  }
590 
591  /*
592  * Set IMU callbacks.
593  */
594  void ZR300Nodelet::setIMUCallbacks()
595  {
596  motion_handler_ = [&](rs::motion_data entry) // NOLINT(build/c++11)
597  {
598  std::unique_lock<std::mutex> lock(imu_mutex_);
599 
600  if (entry.timestamp_data.source_id == RS_EVENT_IMU_GYRO)
601  {
602  imu_angular_vel_.x = entry.axes[0];
603  imu_angular_vel_.y = entry.axes[1];
604  imu_angular_vel_.z = entry.axes[2];
605  }
606  else if (entry.timestamp_data.source_id == RS_EVENT_IMU_ACCEL)
607  {
608  imu_linear_accel_.x = entry.axes[0];
609  imu_linear_accel_.y = entry.axes[1];
610  imu_linear_accel_.z = entry.axes[2];
611  }
612  imu_ts_ = static_cast<double>(entry.timestamp_data.timestamp);
613 
614  ROS_DEBUG_STREAM(" - Motion,\t host time " << imu_ts_
615  << "\ttimestamp: " << std::setprecision(8) << (double)entry.timestamp_data.timestamp*IMU_UNITS_TO_MSEC
616  << "\tsource: " << (rs::event)entry.timestamp_data.source_id
617  << "\tframe_num: " << entry.timestamp_data.frame_number
618  << "\tx: " << std::setprecision(5) << entry.axes[0]
619  << "\ty: " << entry.axes[1]
620  << "\tz: " << entry.axes[2]);
621  };
622 
623  // Get timestamp that syncs all sensors.
624  timestamp_handler_ = [](rs::timestamp_data entry)
625  {
626  auto now = std::chrono::system_clock::now().time_since_epoch();
627  auto sys_time = std::chrono::duration_cast<std::chrono::milliseconds>(now).count();
628 
629  ROS_DEBUG_STREAM(" - TimeEvent, host time " << sys_time
630  << "\ttimestamp: " << std::setprecision(8) << (double)entry.timestamp*IMU_UNITS_TO_MSEC
631  << "\tsource: " << (rs::event)entry.source_id
632  << "\tframe_num: " << entry.frame_number);
633  };
634  }
635 
636  /*
637  * Set up the callbacks for the camera streams
638  */
639  void ZR300Nodelet::setFrameCallbacks()
640  {
641  // call base nodelet method
642  BaseNodelet::setFrameCallbacks();
643 
644  fisheye_frame_handler_ = [&](rs::frame frame) // NOLINT(build/c++11)
645  {
646  publishTopic(RS_STREAM_FISHEYE, frame);
647  };
648 
649  ir2_frame_handler_ = [&](rs::frame frame) // NOLINT(build/c++11)
650  {
651  publishTopic(RS_STREAM_INFRARED2, frame);
652  };
653 
655  new rs::frame_callback(fisheye_frame_handler_), &rs_error_);
656  checkError();
657 
658  rs_set_frame_callback_cpp(rs_device_, RS_STREAM_INFRARED2, new rs::frame_callback(ir2_frame_handler_), &rs_error_);
659  checkError();
660  }
661 
662  /*
663  * Get the camera extrinsics
664  */
665  void ZR300Nodelet::getCameraExtrinsics()
666  {
667  BaseNodelet::getCameraExtrinsics();
668 
669  // Get offset between base frame and infrared2 frame
670  rs_get_device_extrinsics(rs_device_, RS_STREAM_INFRARED2, RS_STREAM_COLOR, &color2ir2_extrinsic_, &rs_error_);
671  if (rs_error_)
672  {
673  ROS_ERROR_STREAM(nodelet_name_ << " - Verify camera is calibrated!");
674  }
675  checkError();
676 
677  // Get offset between base frame and fisheye frame
678  rs_get_device_extrinsics(rs_device_, RS_STREAM_FISHEYE, RS_STREAM_COLOR, &color2fisheye_extrinsic_, &rs_error_);
679  if (rs_error_)
680  {
681  ROS_ERROR_STREAM(nodelet_name_ << " - Verify camera is calibrated!");
682  }
683  checkError();
684 
685  // Get offset between base frame and imu frame
686  rs_get_motion_extrinsics_from(rs_device_, RS_STREAM_COLOR, &color2imu_extrinsic_, &rs_error_);
687  if (rs_error_)
688  {
689 /* Temporarily hardcoding the values until fully supported by librealsense API. */
690  // ROS_ERROR_STREAM(nodelet_name_ << " - Verify camera is calibrated!");
691  ROS_WARN_STREAM(nodelet_name_ << " - Using Hardcoded extrinsic for IMU.");
693  rs_error_ = NULL;
694 
695  color2imu_extrinsic_.translation[0] = -0.07;
696  color2imu_extrinsic_.translation[1] = 0.0;
697  color2imu_extrinsic_.translation[2] = 0.0;
698  }
699  // checkError();
700  }
701 
702  /*
703  * Publish Static transforms.
704  */
705  void ZR300Nodelet::publishStaticTransforms()
706  {
707  BaseNodelet::publishStaticTransforms();
708 
709  tf::Quaternion q_i2io;
710  tf::Quaternion q_f2fo;
711  tf::Quaternion q_imu2imuo;
712  geometry_msgs::TransformStamped b2i_msg;
713  geometry_msgs::TransformStamped i2io_msg;
714  geometry_msgs::TransformStamped b2f_msg;
715  geometry_msgs::TransformStamped f2fo_msg;
716  geometry_msgs::TransformStamped b2imu_msg;
717  geometry_msgs::TransformStamped imu2imuo_msg;
718 
719  // Transform base frame to infrared2 frame
720  b2i_msg.header.stamp = transform_ts_;
721  b2i_msg.header.frame_id = base_frame_id_;
722  b2i_msg.child_frame_id = frame_id_[RS_STREAM_INFRARED2];
723  b2i_msg.transform.translation.x = color2ir2_extrinsic_.translation[2];
724  b2i_msg.transform.translation.y = -color2ir2_extrinsic_.translation[0];
725  b2i_msg.transform.translation.z = -color2ir2_extrinsic_.translation[1];
726  b2i_msg.transform.rotation.x = 0;
727  b2i_msg.transform.rotation.y = 0;
728  b2i_msg.transform.rotation.z = 0;
729  b2i_msg.transform.rotation.w = 1;
730  static_tf_broadcaster_.sendTransform(b2i_msg);
731 
732  // Transform infrared2 frame to infrared2 optical frame
733  q_i2io.setRPY(-M_PI/2, 0.0, -M_PI/2);
734  i2io_msg.header.stamp = transform_ts_;
735  i2io_msg.header.frame_id = frame_id_[RS_STREAM_INFRARED2];
736  i2io_msg.child_frame_id = optical_frame_id_[RS_STREAM_INFRARED2];
737  i2io_msg.transform.translation.x = 0;
738  i2io_msg.transform.translation.y = 0;
739  i2io_msg.transform.translation.z = 0;
740  i2io_msg.transform.rotation.x = q_i2io.getX();
741  i2io_msg.transform.rotation.y = q_i2io.getY();
742  i2io_msg.transform.rotation.z = q_i2io.getZ();
743  i2io_msg.transform.rotation.w = q_i2io.getW();
744  static_tf_broadcaster_.sendTransform(i2io_msg);
745 
746  // Transform base frame to fisheye frame
747  b2f_msg.header.stamp = transform_ts_;
748  b2f_msg.header.frame_id = base_frame_id_;
749  b2f_msg.child_frame_id = frame_id_[RS_STREAM_FISHEYE];
750  b2f_msg.transform.translation.x = color2fisheye_extrinsic_.translation[2];
751  b2f_msg.transform.translation.y = -color2fisheye_extrinsic_.translation[0];
752  b2f_msg.transform.translation.z = -color2fisheye_extrinsic_.translation[1];
753  b2f_msg.transform.rotation.x = 0;
754  b2f_msg.transform.rotation.y = 0;
755  b2f_msg.transform.rotation.z = 0;
756  b2f_msg.transform.rotation.w = 1;
757  static_tf_broadcaster_.sendTransform(b2f_msg);
758 
759  // Transform fisheye frame to fisheye optical frame
760  q_f2fo.setRPY(-M_PI/2, 0.0, -M_PI/2);
761  f2fo_msg.header.stamp = transform_ts_;
762  f2fo_msg.header.frame_id = frame_id_[RS_STREAM_FISHEYE];
763  f2fo_msg.child_frame_id = optical_frame_id_[RS_STREAM_FISHEYE];
764  f2fo_msg.transform.translation.x = 0;
765  f2fo_msg.transform.translation.y = 0;
766  f2fo_msg.transform.translation.z = 0;
767  f2fo_msg.transform.rotation.x = q_f2fo.getX();
768  f2fo_msg.transform.rotation.y = q_f2fo.getY();
769  f2fo_msg.transform.rotation.z = q_f2fo.getZ();
770  f2fo_msg.transform.rotation.w = q_f2fo.getW();
771  static_tf_broadcaster_.sendTransform(f2fo_msg);
772 
773  // Transform base frame to imu frame
774  b2imu_msg.header.stamp = transform_ts_;
775  b2imu_msg.header.frame_id = base_frame_id_;
776  b2imu_msg.child_frame_id = imu_frame_id_;
777  b2imu_msg.transform.translation.x = color2imu_extrinsic_.translation[2];
778  b2imu_msg.transform.translation.y = -color2imu_extrinsic_.translation[0];
779  b2imu_msg.transform.translation.z = -color2imu_extrinsic_.translation[1];
780  b2imu_msg.transform.rotation.x = 0;
781  b2imu_msg.transform.rotation.y = 0;
782  b2imu_msg.transform.rotation.z = 0;
783  b2imu_msg.transform.rotation.w = 1;
784  static_tf_broadcaster_.sendTransform(b2imu_msg);
785 
786  // Transform imu frame to imu optical frame
787  q_imu2imuo.setRPY(-M_PI/2, 0.0, -M_PI/2);
788  imu2imuo_msg.header.stamp = transform_ts_;
789  imu2imuo_msg.header.frame_id = imu_frame_id_;
790  imu2imuo_msg.child_frame_id = imu_optical_frame_id_;
791  imu2imuo_msg.transform.translation.x = 0;
792  imu2imuo_msg.transform.translation.y = 0;
793  imu2imuo_msg.transform.translation.z = 0;
794  imu2imuo_msg.transform.rotation.x = q_imu2imuo.getX();
795  imu2imuo_msg.transform.rotation.y = q_imu2imuo.getY();
796  imu2imuo_msg.transform.rotation.z = q_imu2imuo.getZ();
797  imu2imuo_msg.transform.rotation.w = q_imu2imuo.getW();
798  static_tf_broadcaster_.sendTransform(imu2imuo_msg);
799  }
800 
801  /*
802  * Publish Dynamic transforms.
803  */
804  void ZR300Nodelet::publishDynamicTransforms()
805  {
806  tf::Transform tr;
808 
809  BaseNodelet::publishDynamicTransforms();
810 
811  // Transform base frame to infrared2 frame
813  color2ir2_extrinsic_.translation[2],
814  -color2ir2_extrinsic_.translation[0],
815  -color2ir2_extrinsic_.translation[1]));
816  tr.setRotation(tf::Quaternion(0, 0, 0, 1));
817  dynamic_tf_broadcaster_.sendTransform(tf::StampedTransform(tr, transform_ts_,
818  base_frame_id_, frame_id_[RS_STREAM_INFRARED2]));
819 
820  // Transform infrared2 frame to infrared2 optical frame
821  tr.setOrigin(tf::Vector3(0, 0, 0));
822  q.setRPY(-M_PI/2, 0.0, -M_PI/2);
823  tr.setRotation(q);
824  dynamic_tf_broadcaster_.sendTransform(tf::StampedTransform(tr, transform_ts_,
825  frame_id_[RS_STREAM_INFRARED2], optical_frame_id_[RS_STREAM_INFRARED2]));
826 
827  // Transform base frame to fisheye frame
829  color2fisheye_extrinsic_.translation[2],
830  -color2fisheye_extrinsic_.translation[0],
831  -color2fisheye_extrinsic_.translation[1]));
832  tr.setRotation(tf::Quaternion(0, 0, 0, 1));
833  dynamic_tf_broadcaster_.sendTransform(tf::StampedTransform(tr, transform_ts_,
834  base_frame_id_, frame_id_[RS_STREAM_FISHEYE]));
835 
836  // Transform fisheye frame to fisheye optical frame
837  tr.setOrigin(tf::Vector3(0, 0, 0));
838  q.setRPY(-M_PI/2, 0.0, -M_PI/2);
839  tr.setRotation(q);
840  dynamic_tf_broadcaster_.sendTransform(tf::StampedTransform(tr, transform_ts_,
841  frame_id_[RS_STREAM_FISHEYE], optical_frame_id_[RS_STREAM_FISHEYE]));
842 
843  // Transform base frame to imu frame
845  color2imu_extrinsic_.translation[2],
846  -color2imu_extrinsic_.translation[0],
847  -color2imu_extrinsic_.translation[1]));
848  tr.setRotation(tf::Quaternion(0, 0, 0, 1));
849  dynamic_tf_broadcaster_.sendTransform(tf::StampedTransform(tr, transform_ts_,
850  base_frame_id_, imu_frame_id_));
851 
852  // Transform imu frame to imu optical frame
853  tr.setOrigin(tf::Vector3(0, 0, 0));
854  q.setRPY(-M_PI/2, 0.0, -M_PI/2);
855  tr.setRotation(q);
856  dynamic_tf_broadcaster_.sendTransform(tf::StampedTransform(tr, transform_ts_,
857  imu_frame_id_, imu_optical_frame_id_));
858  }
859 
860  /*
861  * Stop the IMU and motion tracking
862  */
863  void ZR300Nodelet::stopIMU()
864  {
866  checkError();
868  checkError();
869  }
870 } // namespace realsense_camera
RS_STREAM_INFRARED2
RS_OPTION_R200_LR_AUTO_EXPOSURE_ENABLED
RS_OPTION_FISHEYE_AUTO_EXPOSURE_ANTIFLICKER_RATE
RS_OPTION_COLOR_ENABLE_AUTO_EXPOSURE
void rs_set_device_option(rs_device *device, rs_option option, double value, rs_error **error)
RS_OPTION_R200_DEPTH_CLAMP_MAX
RS_OPTION_COLOR_BACKLIGHT_COMPENSATION
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
const int FISHEYE_WIDTH
Definition: constants.h:48
RS_OPTION_COLOR_ENABLE_AUTO_WHITE_BALANCE
const std::string FISHEYE_NAMESPACE
Definition: constants.h:114
RS_OPTION_FISHEYE_AUTO_EXPOSURE_SKIP_FRAMES
RS_OPTION_R200_LR_GAIN
const std::string IMU_NAMESPACE
Definition: constants.h:116
RS_OPTION_R200_DEPTH_CONTROL_SECOND_PEAK_THRESHOLD
const std::string DEFAULT_FISHEYE_FRAME_ID
Definition: constants.h:119
void rs_set_frame_callback_cpp(rs_device *device, rs_stream stream, rs_frame_callback *callback, rs_error **error)
RS_EVENT_IMU_GYRO
RS_OPTION_R200_LR_EXPOSURE
RS_OPTION_FISHEYE_AUTO_EXPOSURE_PIXEL_SAMPLE_RATE
PLUGINLIB_EXPORT_CLASS(depth_image_proc::ConvertMetricNodelet, nodelet::Nodelet)
RS_OPTION_R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_INCREMENT
const float ZR300_MAX_Z
Definition: constants.h:113
const std::string TYPE_8UC1
RS_OPTION_COLOR_HUE
TFSIMD_FORCE_INLINE const tfScalar & getW() const
RS_OPTION_COLOR_GAIN
const std::string IMU_INFO_SERVICE
Definition: constants.h:118
RS_OPTION_R200_DEPTH_CONTROL_SCORE_MINIMUM_THRESHOLD
void rs_disable_motion_tracking(rs_device *device, rs_error **error)
const bool ENABLE_FISHEYE
Definition: constants.h:57
RS_OPTION_R200_DEPTH_CONTROL_SCORE_MAXIMUM_THRESHOLD
RS_FORMAT_Z16
RS_EVENT_IMU_ACCEL
RS_OPTION_COLOR_CONTRAST
RS_OPTION_COLOR_WHITE_BALANCE
const std::string IMU_GYRO
Definition: constants.h:124
const bool ENABLE_IR2
Definition: constants.h:56
rs_error * rs_error_
void rs_stop_source(rs_device *device, rs_source source, rs_error **error)
const std::string FISHEYE_TOPIC
Definition: constants.h:115
RS_OPTION_COLOR_EXPOSURE
const std::string IMU_ACCEL
Definition: constants.h:123
const std::string IR2_TOPIC
Definition: constants.h:89
GLint level
const std::string DEFAULT_IMU_OPTICAL_FRAME_ID
Definition: constants.h:122
GLuint index
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
GLuint GLuint GLsizei count
RS_OPTION_COLOR_SHARPNESS
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
const std::string IR2_NAMESPACE
Definition: constants.h:88
RS_OPTION_R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_DECREMENT
RS_FORMAT_RAW8
RS_SOURCE_ALL
RS_OPTION_R200_DEPTH_CLAMP_MIN
const std::string DEFAULT_IMU_FRAME_ID
Definition: constants.h:120
double rs_get_device_option(rs_device *device, rs_option option, rs_error **error)
int rs_is_stream_enabled(const rs_device *device, rs_stream stream, rs_error **error)
ROSCPP_DECL bool ok()
const std::string TYPE_16UC1
const std::string IMU_TOPIC
Definition: constants.h:117
RS_OPTION_R200_DEPTH_CONTROL_NEIGHBOR_THRESHOLD
const bool ENABLE_IMU
Definition: constants.h:58
RS_OPTION_FISHEYE_ENABLE_AUTO_EXPOSURE
void rs_free_error(rs_error *error)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
RS_OPTION_R200_EMITTER_ENABLED
void rs_get_device_extrinsics(const rs_device *device, rs_stream from, rs_stream to, rs_extrinsics *extrin, rs_error **error)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
rs_source
RS_OPTION_FISHEYE_EXPOSURE
const double IMU_UNITS_TO_MSEC
RS_OPTION_R200_DEPTH_CONTROL_MEDIAN_THRESHOLD
void rs_enable_motion_tracking_cpp(rs_device *device, rs_motion_callback *motion_callback, rs_timestamp_callback *ts_callback, rs_error **error)
RS_OPTION_FISHEYE_AUTO_EXPOSURE_MODE
rs_motion_device_intrinsic acc
RS_OPTION_FRAMES_QUEUE_SIZE
const int FISHEYE_FPS
Definition: constants.h:52
RS_OPTION_R200_DEPTH_CONTROL_TEXTURE_DIFFERENCE_THRESHOLD
#define ROS_INFO_STREAM(args)
const std::string DEFAULT_IR2_FRAME_ID
Definition: constants.h:90
const std::string DEFAULT_IR2_OPTICAL_FRAME_ID
Definition: constants.h:91
RS_OPTION_FISHEYE_GAIN
RS_OPTION_COLOR_SATURATION
void rs_get_motion_intrinsics(const rs_device *device, rs_motion_intrinsics *intrinsic, rs_error **error)
GLdouble GLdouble GLdouble GLdouble q
static Time now()
rs_motion_device_intrinsic gyro
RS_OPTION_HARDWARE_LOGGER_ENABLED
void rs_get_motion_extrinsics_from(const rs_device *device, rs_stream from, rs_extrinsics *extrin, rs_error **error)
RS_FORMAT_RGB8
GLuint res
#define ROS_ERROR_STREAM(args)
RS_STREAM_FISHEYE
RS_STREAM_DEPTH
RS_OPTION_R200_DEPTH_CONTROL_LR_THRESHOLD
RS_OPTION_R200_DEPTH_CONTROL_TEXTURE_COUNT_THRESHOLD
const int FISHEYE_HEIGHT
Definition: constants.h:49
RS_FORMAT_Y8
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
const std::string DEFAULT_FISHEYE_OPTICAL_FRAME_ID
Definition: constants.h:121
RS_STREAM_INFRARED
RS_OPTION_COLOR_BRIGHTNESS
RS_OPTION_COLOR_GAMMA
RS_STREAM_COLOR
preset


realsense_camera
Author(s): Rajvi Jingar , Reagan Lopez , Matt Hansen , Mark Horn
autogenerated on Mon Jun 10 2019 14:40:37