openni2_driver.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Willow Garage, Inc.
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  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Author: Julius Kammerl (jkammerl@willowgarage.com)
30  */
31 
34 
37 
38 #include <boost/date_time/posix_time/posix_time.hpp>
39 #include <boost/thread/thread.hpp>
40 
41 namespace openni2_wrapper
42 {
43 
45  nh_(n),
46  pnh_(pnh),
47  device_manager_(OpenNI2DeviceManager::getSingelton()),
48  config_init_(false),
49  data_skip_ir_counter_(0),
50  data_skip_color_counter_(0),
51  data_skip_depth_counter_ (0),
52  ir_subscribers_(false),
53  color_subscribers_(false),
54  depth_subscribers_(false),
55  depth_raw_subscribers_(false),
56  enable_reconnect_(false),
57  serialnumber_as_name_(false)
58 {
59 
61 
63 
64  initDevice();
65 
66  // Initialize dynamic reconfigure
68  reconfigure_server_->setCallback(boost::bind(&OpenNI2Driver::configCb, this, _1, _2));
69 
70  while (!config_init_)
71  {
72  ROS_DEBUG("Waiting for dynamic reconfigure configuration.");
73  boost::this_thread::sleep(boost::posix_time::milliseconds(100));
74  }
75  ROS_DEBUG("Dynamic reconfigure configuration received.");
76 
78 
79  if( enable_reconnect_ )
80  {
81  ROS_WARN_STREAM("Reconnect has been enabled, only one camera "
82  << "should be plugged into each bus");
84  }
85  else
86  {
87  ROS_WARN_STREAM("Reconnect has been disabled");
88  }
89 }
90 
92 {
93 
94  // Allow remapping namespaces rgb, ir, depth, depth_registered
95  ros::NodeHandle color_nh(nh_, "rgb");
96  image_transport::ImageTransport color_it(color_nh);
97  ros::NodeHandle ir_nh(nh_, "ir");
99  ros::NodeHandle depth_nh(nh_, "depth");
100  image_transport::ImageTransport depth_it(depth_nh);
101  ros::NodeHandle depth_raw_nh(nh_, "depth");
102  image_transport::ImageTransport depth_raw_it(depth_raw_nh);
103  ros::NodeHandle projector_nh(nh_, "projector");
104  // Advertise all published topics
105 
106  // Prevent connection callbacks from executing until we've set all the publishers. Otherwise
107  // connectCb() can fire while we're advertising (say) "depth/image_raw", but before we actually
108  // assign to pub_depth_raw_. Then pub_depth_raw_.getNumSubscribers() returns 0, and we fail to start
109  // the depth generator.
110  boost::lock_guard<boost::mutex> lock(connect_mutex_);
111 
112  // Asus Xtion PRO does not have an RGB camera
113  if (device_->hasColorSensor())
114  {
117  pub_color_ = color_it.advertiseCamera("image", 1, itssc, itssc, rssc, rssc);
118  }
119 
120  if (device_->hasIRSensor())
121  {
124  pub_ir_ = ir_it.advertiseCamera("image", 1, itssc, itssc, rssc, rssc);
125  }
126 
127  if (device_->hasDepthSensor())
128  {
131  pub_depth_raw_ = depth_it.advertiseCamera("image_raw", 1, itssc, itssc, rssc, rssc);
132  pub_depth_ = depth_raw_it.advertiseCamera("image", 1, itssc, itssc, rssc, rssc);
133  pub_projector_info_ = projector_nh.advertise<sensor_msgs::CameraInfo>("camera_info", 1, rssc, rssc);
134  }
135 
137 
138  // Pixel offset between depth and IR images.
139  // By default assume offset of (5,4) from 9x7 correlation window.
140  // NOTE: These are now (temporarily?) dynamically reconfigurable, to allow tweaking.
141  //param_nh.param("depth_ir_offset_x", depth_ir_offset_x_, 5.0);
142  //param_nh.param("depth_ir_offset_y", depth_ir_offset_y_, 4.0);
143 
144  // The camera names are set to [rgb|depth]_[serial#], e.g. depth_B00367707227042B.
145  // camera_info_manager substitutes this for ${NAME} in the URL.
146  std::string serial_number;
148  serial_number = device_manager_->getSerial(device_->getUri());
149  else
150  serial_number = device_->getStringID();
151 
152  std::string color_name, ir_name;
153  color_name = "rgb_" + serial_number;
154  ir_name = "depth_" + serial_number;
155 
156  // Load the saved calibrations, if they exist
157  color_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(color_nh, color_name, color_info_url_);
158  ir_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(ir_nh, ir_name, ir_info_url_);
159 
161 
162 }
163 
164 bool OpenNI2Driver::getSerialCb(openni2_camera::GetSerialRequest& req, openni2_camera::GetSerialResponse& res) {
165  res.serial = device_manager_->getSerial(device_->getUri());
166  return true;
167 }
168 
169 void OpenNI2Driver::configCb(Config &config, uint32_t level)
170 {
171  bool stream_reset = false;
172 
173  depth_ir_offset_x_ = config.depth_ir_offset_x;
174  depth_ir_offset_y_ = config.depth_ir_offset_y;
175  z_offset_mm_ = config.z_offset_mm;
176  z_scaling_ = config.z_scaling;
177 
178  ir_time_offset_ = ros::Duration(config.ir_time_offset);
179  color_time_offset_ = ros::Duration(config.color_time_offset);
180  depth_time_offset_ = ros::Duration(config.depth_time_offset);
181 
182  if (lookupVideoModeFromDynConfig(config.ir_mode, ir_video_mode_)<0)
183  {
184  ROS_ERROR("Undefined IR video mode received from dynamic reconfigure");
185  exit(-1);
186  }
187 
188  if (lookupVideoModeFromDynConfig(config.color_mode, color_video_mode_)<0)
189  {
190  ROS_ERROR("Undefined color video mode received from dynamic reconfigure");
191  exit(-1);
192  }
193 
194  if (lookupVideoModeFromDynConfig(config.depth_mode, depth_video_mode_)<0)
195  {
196  ROS_ERROR("Undefined depth video mode received from dynamic reconfigure");
197  exit(-1);
198  }
199 
200  // assign pixel format
201 
205 
206  color_depth_synchronization_ = config.color_depth_synchronization;
207  depth_registration_ = config.depth_registration;
208 
209  auto_exposure_ = config.auto_exposure;
210  auto_white_balance_ = config.auto_white_balance;
211  exposure_ = config.exposure;
212 
213  use_device_time_ = config.use_device_time;
214 
215  data_skip_ = config.data_skip+1;
216 
218 
219  config_init_ = true;
220 
221  old_config_ = config;
222 }
223 
225 {
226  if (device_->isIRVideoModeSupported(ir_video_mode))
227  {
228  if (ir_video_mode != device_->getIRVideoMode())
229  {
230  device_->setIRVideoMode(ir_video_mode);
231  }
232 
233  }
234  else
235  {
236  ROS_ERROR_STREAM("Unsupported IR video mode - " << ir_video_mode);
237  }
238 }
240 {
241  if (device_->isColorVideoModeSupported(color_video_mode))
242  {
243  if (color_video_mode != device_->getColorVideoMode())
244  {
245  device_->setColorVideoMode(color_video_mode);
246  }
247  }
248  else
249  {
250  ROS_ERROR_STREAM("Unsupported color video mode - " << color_video_mode);
251  }
252 }
254 {
255  if (device_->isDepthVideoModeSupported(depth_video_mode))
256  {
257  if (depth_video_mode != device_->getDepthVideoMode())
258  {
259  device_->setDepthVideoMode(depth_video_mode);
260  }
261  }
262  else
263  {
264  ROS_ERROR_STREAM("Unsupported depth video mode - " << depth_video_mode);
265  }
266 }
267 
269 {
270 
274 
278 
279  if (device_->isImageRegistrationModeSupported())
280  {
281  try
282  {
283  if (!config_init_ || (old_config_.depth_registration != depth_registration_))
284  device_->setImageRegistrationMode(depth_registration_);
285  }
286  catch (const OpenNI2Exception& exception)
287  {
288  ROS_ERROR("Could not set image registration. Reason: %s", exception.what());
289  }
290  }
291 
292  try
293  {
294  if (!config_init_ || (old_config_.color_depth_synchronization != color_depth_synchronization_))
295  device_->setDepthColorSync(color_depth_synchronization_);
296  }
297  catch (const OpenNI2Exception& exception)
298  {
299  ROS_ERROR("Could not set color depth synchronization. Reason: %s", exception.what());
300  }
301 
302  try
303  {
304  if (!config_init_ || (old_config_.auto_exposure != auto_exposure_))
305  device_->setAutoExposure(auto_exposure_);
306  }
307  catch (const OpenNI2Exception& exception)
308  {
309  ROS_ERROR("Could not set auto exposure. Reason: %s", exception.what());
310  }
311 
312  try
313  {
314  if (!config_init_ || (old_config_.auto_white_balance != auto_white_balance_))
315  device_->setAutoWhiteBalance(auto_white_balance_);
316  }
317  catch (const OpenNI2Exception& exception)
318  {
319  ROS_ERROR("Could not set auto white balance. Reason: %s", exception.what());
320  }
321 
322 
323  // Workaound for https://github.com/ros-drivers/openni2_camera/issues/51
324  // This is only needed when any of the 3 setting change. For simplicity
325  // this check is always performed and exposure set.
326  if( (!auto_exposure_ && !auto_white_balance_) && exposure_ != 0 )
327  {
328  ROS_INFO_STREAM("Forcing exposure set, when auto exposure/white balance disabled");
330  }
331  else
332  {
333  // Setting the exposure the old way, although this should not have an effect
334  try
335  {
336  if (!config_init_ || (old_config_.exposure != exposure_))
337  device_->setExposure(exposure_);
338  }
339  catch (const OpenNI2Exception& exception)
340  {
341  ROS_ERROR("Could not set exposure. Reason: %s", exception.what());
342  }
343  }
344 
345  device_->setUseDeviceTimer(use_device_time_);
346 }
347 
348 
349 
351 {
352  int current_exposure_ = device_->getExposure();
353  try
354  {
355  if( current_exposure_ == exposure_ )
356  {
357  if( exposure_ < 254 )
358  {
359  device_->setExposure(exposure_ + 1);
360  }
361  else
362  {
363  device_->setExposure(exposure_ - 1);
364  }
365  }
366  device_->setExposure(exposure_);
367  }
368  catch (const OpenNI2Exception& exception)
369  {
370  ROS_ERROR("Could not set exposure. Reason: %s", exception.what());
371  }
372 }
373 
375 {
376  if( !device_ )
377  {
378  ROS_WARN_STREAM("Callback in " << __FUNCTION__ << "failed due to null device");
379  return;
380  }
381  boost::lock_guard<boost::mutex> lock(connect_mutex_);
382 
384 
385  if (color_subscribers_ && !device_->isColorStreamStarted())
386  {
387  // Can't stream IR and RGB at the same time. Give RGB preference.
388  if (device_->isIRStreamStarted())
389  {
390  ROS_ERROR("Cannot stream RGB and IR at the same time. Streaming RGB only.");
391  ROS_INFO("Stopping IR stream.");
392  device_->stopIRStream();
393  }
394 
395  device_->setColorFrameCallback(boost::bind(&OpenNI2Driver::newColorFrameCallback, this, _1));
396 
397  ROS_INFO("Starting color stream.");
398  device_->startColorStream();
399 
400  // Workaound for https://github.com/ros-drivers/openni2_camera/issues/51
401  if( exposure_ != 0 )
402  {
403  ROS_INFO_STREAM("Exposure is set to " << exposure_ << ", forcing on color stream start");
404  //delay for stream to start, before setting exposure
405  boost::this_thread::sleep(boost::posix_time::milliseconds(100));
407  }
408 
409  }
410  else if (!color_subscribers_ && device_->isColorStreamStarted())
411  {
412  ROS_INFO("Stopping color stream.");
413  device_->stopColorStream();
414 
415  // Start IR if it's been blocked on RGB subscribers
416  bool need_ir = pub_ir_.getNumSubscribers() > 0;
417  if (need_ir && !device_->isIRStreamStarted())
418  {
419  device_->setIRFrameCallback(boost::bind(&OpenNI2Driver::newIRFrameCallback, this, _1));
420 
421  ROS_INFO("Starting IR stream.");
422  device_->startIRStream();
423  }
424  }
425 }
426 
428 {
429  if( !device_ )
430  {
431  ROS_WARN_STREAM("Callback in " << __FUNCTION__ << "failed due to null device");
432  return;
433  }
434  boost::lock_guard<boost::mutex> lock(connect_mutex_);
435 
439 
440  bool need_depth = depth_subscribers_ || depth_raw_subscribers_;
441 
442  if (need_depth && !device_->isDepthStreamStarted())
443  {
444  device_->setDepthFrameCallback(boost::bind(&OpenNI2Driver::newDepthFrameCallback, this, _1));
445 
446  ROS_INFO("Starting depth stream.");
447  device_->startDepthStream();
448  }
449  else if (!need_depth && device_->isDepthStreamStarted())
450  {
451  ROS_INFO("Stopping depth stream.");
452  device_->stopDepthStream();
453  }
454 }
455 
457 {
458  if( !device_ )
459  {
460  ROS_WARN_STREAM("Callback in " << __FUNCTION__ << "failed due to null device");
461  return;
462  }
463  boost::lock_guard<boost::mutex> lock(connect_mutex_);
464 
466 
467  if (ir_subscribers_ && !device_->isIRStreamStarted())
468  {
469  // Can't stream IR and RGB at the same time
470  if (device_->isColorStreamStarted())
471  {
472  ROS_ERROR("Cannot stream RGB and IR at the same time. Streaming RGB only.");
473  }
474  else
475  {
476  device_->setIRFrameCallback(boost::bind(&OpenNI2Driver::newIRFrameCallback, this, _1));
477 
478  ROS_INFO("Starting IR stream.");
479  device_->startIRStream();
480  }
481  }
482  else if (!ir_subscribers_ && device_->isIRStreamStarted())
483  {
484  ROS_INFO("Stopping IR stream.");
485  device_->stopIRStream();
486  }
487 }
488 
489 void OpenNI2Driver::newIRFrameCallback(sensor_msgs::ImagePtr image)
490 {
492  {
494 
495  if (ir_subscribers_)
496  {
497  image->header.frame_id = ir_frame_id_;
498  image->header.stamp = image->header.stamp + ir_time_offset_;
499 
500  pub_ir_.publish(image, getIRCameraInfo(image->width, image->height, image->header.stamp));
501  }
502  }
503 }
504 
505 void OpenNI2Driver::newColorFrameCallback(sensor_msgs::ImagePtr image)
506 {
508  {
510 
511  if (color_subscribers_)
512  {
513  image->header.frame_id = color_frame_id_;
514  image->header.stamp = image->header.stamp + color_time_offset_;
515 
516  pub_color_.publish(image, getColorCameraInfo(image->width, image->height, image->header.stamp));
517  }
518  }
519 }
520 
521 void OpenNI2Driver::newDepthFrameCallback(sensor_msgs::ImagePtr image)
522 {
524  {
525 
527 
529  {
530  image->header.stamp = image->header.stamp + depth_time_offset_;
531 
532  if (z_offset_mm_ != 0)
533  {
534  uint16_t* data = reinterpret_cast<uint16_t*>(&image->data[0]);
535  for (unsigned int i = 0; i < image->width * image->height; ++i)
536  if (data[i] != 0)
537  data[i] += z_offset_mm_;
538  }
539 
540  if (fabs(z_scaling_ - 1.0) > 1e-6)
541  {
542  uint16_t* data = reinterpret_cast<uint16_t*>(&image->data[0]);
543  for (unsigned int i = 0; i < image->width * image->height; ++i)
544  if (data[i] != 0)
545  data[i] = static_cast<uint16_t>(data[i] * z_scaling_);
546  }
547 
548  sensor_msgs::CameraInfoPtr cam_info;
549 
551  {
552  image->header.frame_id = color_frame_id_;
553  cam_info = getColorCameraInfo(image->width,image->height, image->header.stamp);
554  } else
555  {
556  image->header.frame_id = depth_frame_id_;
557  cam_info = getDepthCameraInfo(image->width,image->height, image->header.stamp);
558  }
559 
561  {
562  pub_depth_raw_.publish(image, cam_info);
563  }
564 
565  if (depth_subscribers_ )
566  {
567  sensor_msgs::ImageConstPtr floating_point_image = rawToFloatingPointConversion(image);
568  pub_depth_.publish(floating_point_image, cam_info);
569  }
570 
571  // Projector "info" probably only useful for working with disparity images
573  {
574  pub_projector_info_.publish(getProjectorCameraInfo(image->width, image->height, image->header.stamp));
575  }
576  }
577  }
578 }
579 
580 // Methods to get calibration parameters for the various cameras
581 sensor_msgs::CameraInfoPtr OpenNI2Driver::getDefaultCameraInfo(int width, int height, double f) const
582 {
583  sensor_msgs::CameraInfoPtr info = boost::make_shared<sensor_msgs::CameraInfo>();
584 
585  info->width = width;
586  info->height = height;
587 
588  // No distortion
589  info->D.resize(5, 0.0);
590  info->distortion_model = sensor_msgs::distortion_models::PLUMB_BOB;
591 
592  // Simple camera matrix: square pixels (fx = fy), principal point at center
593  info->K.assign(0.0);
594  info->K[0] = info->K[4] = f;
595  info->K[2] = (width / 2) - 0.5;
596  // Aspect ratio for the camera center on Kinect (and other devices?) is 4/3
597  // This formula keeps the principal point the same in VGA and SXGA modes
598  info->K[5] = (width * (3./8.)) - 0.5;
599  info->K[8] = 1.0;
600 
601  // No separate rectified image plane, so R = I
602  info->R.assign(0.0);
603  info->R[0] = info->R[4] = info->R[8] = 1.0;
604 
605  // Then P=K(I|0) = (K|0)
606  info->P.assign(0.0);
607  info->P[0] = info->P[5] = f; // fx, fy
608  info->P[2] = info->K[2]; // cx
609  info->P[6] = info->K[5]; // cy
610  info->P[10] = 1.0;
611 
612  return info;
613 }
614 
616 sensor_msgs::CameraInfoPtr OpenNI2Driver::getColorCameraInfo(int width, int height, ros::Time time) const
617 {
618  sensor_msgs::CameraInfoPtr info;
619 
620  if (color_info_manager_->isCalibrated())
621  {
622  info = boost::make_shared<sensor_msgs::CameraInfo>(color_info_manager_->getCameraInfo());
623  if ( info->width != width )
624  {
625  // Use uncalibrated values
626  ROS_WARN_ONCE("Image resolution doesn't match calibration of the RGB camera. Using default parameters.");
627  info = getDefaultCameraInfo(width, height, device_->getColorFocalLength(height));
628  }
629  }
630  else
631  {
632  // If uncalibrated, fill in default values
633  info = getDefaultCameraInfo(width, height, device_->getColorFocalLength(height));
634  }
635 
636  // Fill in header
637  info->header.stamp = time;
638  info->header.frame_id = color_frame_id_;
639 
640  return info;
641 }
642 
643 
644 sensor_msgs::CameraInfoPtr OpenNI2Driver::getIRCameraInfo(int width, int height, ros::Time time) const
645 {
646  sensor_msgs::CameraInfoPtr info;
647 
648  if (ir_info_manager_->isCalibrated())
649  {
650  info = boost::make_shared<sensor_msgs::CameraInfo>(ir_info_manager_->getCameraInfo());
651  if ( info->width != width )
652  {
653  // Use uncalibrated values
654  ROS_WARN_ONCE("Image resolution doesn't match calibration of the IR camera. Using default parameters.");
655  info = getDefaultCameraInfo(width, height, device_->getIRFocalLength(height));
656  }
657  }
658  else
659  {
660  // If uncalibrated, fill in default values
661  info = getDefaultCameraInfo(width, height, device_->getDepthFocalLength(height));
662  }
663 
664  // Fill in header
665  info->header.stamp = time;
666  info->header.frame_id = depth_frame_id_;
667 
668  return info;
669 }
670 
671 sensor_msgs::CameraInfoPtr OpenNI2Driver::getDepthCameraInfo(int width, int height, ros::Time time) const
672 {
673  // The depth image has essentially the same intrinsics as the IR image, BUT the
674  // principal point is offset by half the size of the hardware correlation window
675  // (probably 9x9 or 9x7 in 640x480 mode). See http://www.ros.org/wiki/kinect_calibration/technical
676 
677  double scaling = (double)width / 640;
678 
679  sensor_msgs::CameraInfoPtr info = getIRCameraInfo(width, height, time);
680  info->K[2] -= depth_ir_offset_x_*scaling; // cx
681  info->K[5] -= depth_ir_offset_y_*scaling; // cy
682  info->P[2] -= depth_ir_offset_x_*scaling; // cx
683  info->P[6] -= depth_ir_offset_y_*scaling; // cy
684 
686  return info;
687 }
688 
689 sensor_msgs::CameraInfoPtr OpenNI2Driver::getProjectorCameraInfo(int width, int height, ros::Time time) const
690 {
691  // The projector info is simply the depth info with the baseline encoded in the P matrix.
692  // It's only purpose is to be the "right" camera info to the depth camera's "left" for
693  // processing disparity images.
694  sensor_msgs::CameraInfoPtr info = getDepthCameraInfo(width, height, time);
695  // Tx = -baseline * fx
696  info->P[3] = -device_->getBaseline() * info->P[0];
697  return info;
698 }
699 
701 {
702  if (!pnh_.getParam("device_id", device_id_))
703  {
704  ROS_WARN ("~device_id is not set! Using first device.");
705  device_id_ = "#1";
706  }
707 
708  // Camera TF frames
709  pnh_.param("ir_frame_id", ir_frame_id_, std::string("/openni_ir_optical_frame"));
710  pnh_.param("rgb_frame_id", color_frame_id_, std::string("/openni_rgb_optical_frame"));
711  pnh_.param("depth_frame_id", depth_frame_id_, std::string("/openni_depth_optical_frame"));
712 
713  ROS_DEBUG("ir_frame_id = '%s' ", ir_frame_id_.c_str());
714  ROS_DEBUG("rgb_frame_id = '%s' ", color_frame_id_.c_str());
715  ROS_DEBUG("depth_frame_id = '%s' ", depth_frame_id_.c_str());
716 
717  pnh_.param("rgb_camera_info_url", color_info_url_, std::string());
718  pnh_.param("depth_camera_info_url", ir_info_url_, std::string());
719 
720  pnh_.param("enable_reconnect", enable_reconnect_, true);
721 
722  pnh_.param("serialnumber_as_name", serialnumber_as_name_, false);
723 
724 }
725 
726 std::string OpenNI2Driver::resolveDeviceURI(const std::string& device_id) throw(OpenNI2Exception)
727 {
728  // retrieve available device URIs, they look like this: "1d27/0601@1/5"
729  // which is <vendor ID>/<product ID>@<bus number>/<device number>
730  boost::shared_ptr<std::vector<std::string> > available_device_URIs =
731  device_manager_->getConnectedDeviceURIs();
732 
733  // look for '#<number>' format
734  if (device_id.size() > 1 && device_id[0] == '#')
735  {
736  std::istringstream device_number_str(device_id.substr(1));
737  int device_number;
738  device_number_str >> device_number;
739  int device_index = device_number - 1; // #1 refers to first device
740  if (device_index >= available_device_URIs->size() || device_index < 0)
741  {
743  "Invalid device number %i, there are %zu devices connected.",
744  device_number, available_device_URIs->size());
745  }
746  else
747  {
748  return available_device_URIs->at(device_index);
749  }
750  }
751  // look for '<bus>@<number>' format
752  // <bus> is usb bus id, typically start at 1
753  // <number> is the device number, for consistency with openni_camera, these start at 1
754  // although 0 specifies "any device on this bus"
755  else if (device_id.size() > 1 && device_id.find('@') != std::string::npos && device_id.find('/') == std::string::npos)
756  {
757  // get index of @ character
758  size_t index = device_id.find('@');
759  if (index <= 0)
760  {
762  "%s is not a valid device URI, you must give the bus number before the @.",
763  device_id.c_str());
764  }
765  if (index >= device_id.size() - 1)
766  {
768  "%s is not a valid device URI, you must give the device number after the @, specify 0 for any device on this bus",
769  device_id.c_str());
770  }
771 
772  // pull out device number on bus
773  std::istringstream device_number_str(device_id.substr(index+1));
774  int device_number;
775  device_number_str >> device_number;
776 
777  // reorder to @<bus>
778  std::string bus = device_id.substr(0, index);
779  bus.insert(0, "@");
780 
781  for (size_t i = 0; i < available_device_URIs->size(); ++i)
782  {
783  std::string s = (*available_device_URIs)[i];
784  if (s.find(bus) != std::string::npos)
785  {
786  // this matches our bus, check device number
787  std::ostringstream ss;
788  ss << bus << '/' << device_number;
789  if (device_number == 0 || s.find(ss.str()) != std::string::npos)
790  return s;
791  }
792  }
793 
794  THROW_OPENNI_EXCEPTION("Device not found %s", device_id.c_str());
795  }
796  else
797  {
798  // check if the device id given matches a serial number of a connected device
799  for(std::vector<std::string>::const_iterator it = available_device_URIs->begin();
800  it != available_device_URIs->end(); ++it)
801  {
802  try {
803  std::string serial = device_manager_->getSerial(*it);
804  if (serial.size() > 0 && device_id == serial)
805  return *it;
806  }
807  catch (const OpenNI2Exception& exception)
808  {
809  ROS_WARN("Could not query serial number of device \"%s\":", exception.what());
810  }
811  }
812 
813  // everything else is treated as part of the device_URI
814  bool match_found = false;
815  std::string matched_uri;
816  for (size_t i = 0; i < available_device_URIs->size(); ++i)
817  {
818  std::string s = (*available_device_URIs)[i];
819  if (s.find(device_id) != std::string::npos)
820  {
821  if (!match_found)
822  {
823  matched_uri = s;
824  match_found = true;
825  }
826  else
827  {
828  // more than one match
829  THROW_OPENNI_EXCEPTION("Two devices match the given device id '%s': %s and %s.", device_id.c_str(), matched_uri.c_str(), s.c_str());
830  }
831  }
832  }
833  if (match_found)
834  return matched_uri;
835  else
836  return "INVALID";
837  }
838 }
839 
841 {
842  while (ros::ok() && !device_)
843  {
844  try
845  {
846  std::string device_URI = resolveDeviceURI(device_id_);
847  device_ = device_manager_->getDevice(device_URI);
848  bus_id_ = extractBusID(device_->getUri() );
849  }
850  catch (const OpenNI2Exception& exception)
851  {
852  if (!device_)
853  {
854  ROS_INFO("No matching device found.... waiting for devices. Reason: %s", exception.what());
855  boost::this_thread::sleep(boost::posix_time::seconds(3));
856  continue;
857  }
858  else
859  {
860  ROS_ERROR("Could not retrieve device. Reason: %s", exception.what());
861  exit(-1);
862  }
863  }
864  }
865 
866  while (ros::ok() && !device_->isValid())
867  {
868  ROS_DEBUG("Waiting for device initialization..");
869  boost::this_thread::sleep(boost::posix_time::milliseconds(100));
870  }
871 
872 }
873 
874 
875 int OpenNI2Driver::extractBusID(const std::string& uri) const
876 {
877  // URI format is <vendor ID>/<product ID>@<bus number>/<device number>
878  unsigned first = uri.find('@');
879  unsigned last = uri.find('/', first);
880  std::string bus_id = uri.substr (first+1,last-first-1);
881  int rtn = atoi(bus_id.c_str());
882  return rtn;
883 }
884 
885 
887 {
888  // TODO: The current isConnected logic assumes that there is only one sensor
889  // on the bus of interest. In the future, we could compare serial numbers
890  // to make certain the same camera as been re-connected.
892  device_manager_->getConnectedDeviceURIs();
893  for (std::size_t i = 0; i != list->size(); ++i)
894  {
895  int uri_bus_id = extractBusID( list->at(i) );
896  if( uri_bus_id == bus_id_ )
897  {
898  return true;
899  }
900  }
901  return false;
902 }
903 
905 {
906  // If the connection is lost, clean up the device. If connected
907  // and the devices is not initialized, then initialize.
908  if( isConnected() )
909  {
910  if( !device_ )
911  {
912  ROS_INFO_STREAM("Detected re-connect...attempting reinit");
913  try
914  {
915  {
916  boost::lock_guard<boost::mutex> lock(connect_mutex_);
917  std::string device_URI = resolveDeviceURI(device_id_);
918  device_ = device_manager_->getDevice(device_URI);
919  bus_id_ = extractBusID(device_->getUri() );
920  while (ros::ok() && !device_->isValid())
921  {
922  ROS_INFO("Waiting for device initialization, before configuring and restarting publishers");
923  boost::this_thread::sleep(boost::posix_time::milliseconds(100));
924  }
925  }
926  ROS_INFO_STREAM("Re-applying configuration to camera on re-init");
927  config_init_ = false;
929 
930  // The color stream must be started in order to adjust the exposure white
931  // balance.
932  ROS_INFO_STREAM("Starting color stream to adjust camera");
933  colorConnectCb();
934 
935  // If auto exposure/white balance is disabled, then the rbg image won't
936  // be adjusted properly. This is a work around for now, but the final
937  // implimentation should only allow reconnection when auto exposure and
938  // white balance are disabled, and FIXED exposure is used instead.
939  if((!auto_exposure_ && !auto_white_balance_ ) && exposure_ == 0)
940  {
941  ROS_WARN_STREAM("Reconnection should not be enabled if auto expousre"
942  << "/white balance are disabled. Temporarily working"
943  << " around this issue");
944  ROS_WARN_STREAM("Toggling exposure and white balance to auto on re-connect"
945  << ", otherwise image will be very dark");
946  device_->setAutoExposure(true);
947  device_->setAutoWhiteBalance(true);
948  ROS_INFO_STREAM("Waiting for color camera to come up and adjust");
949  // It takes about 2.5 seconds for the camera to adjust
950  boost::this_thread::sleep(boost::posix_time::milliseconds(2500));
951  ROS_WARN_STREAM("Resetting auto exposure and white balance to previous values");
952  device_->setAutoExposure(auto_exposure_);
953  device_->setAutoWhiteBalance(auto_white_balance_);
954  }
955 
956  ROS_INFO_STREAM("Restarting publishers, if needed");
957  irConnectCb();
958  depthConnectCb();
959  ROS_INFO_STREAM("Done re-initializing cameras");
960  }
961 
962  catch (const OpenNI2Exception& exception)
963  {
964  if (!device_)
965  {
966  ROS_INFO_STREAM("Failed to re-initialize device on bus: " << bus_id_
967  << ", reason: " << exception.what());
968  }
969  }
970  }
971  }
972  else if( device_ )
973  {
974  ROS_WARN_STREAM("Detected loss of connection. Stopping all streams and resetting device");
975  device_->stopAllStreams();
976  device_.reset();
977  }
978 }
979 
980 
982 {
983  /*
984  * # Video modes defined by dynamic reconfigure:
985 output_mode_enum = gen.enum([ gen.const( "SXGA_30Hz", int_t, 1, "1280x1024@30Hz"),
986  gen.const( "SXGA_15Hz", int_t, 2, "1280x1024@15Hz"),
987  gen.const( "XGA_30Hz", int_t, 3, "1280x720@30Hz"),
988  gen.const( "XGA_15Hz", int_t, 4, "1280x720@15Hz"),
989  gen.const( "VGA_30Hz", int_t, 5, "640x480@30Hz"),
990  gen.const( "VGA_25Hz", int_t, 6, "640x480@25Hz"),
991  gen.const( "QVGA_25Hz", int_t, 7, "320x240@25Hz"),
992  gen.const( "QVGA_30Hz", int_t, 8, "320x240@30Hz"),
993  gen.const( "QVGA_60Hz", int_t, 9, "320x240@60Hz"),
994  gen.const( "QQVGA_25Hz", int_t, 10, "160x120@25Hz"),
995  gen.const( "QQVGA_30Hz", int_t, 11, "160x120@30Hz"),
996  gen.const( "QQVGA_60Hz", int_t, 12, "160x120@60Hz")],
997  "output mode")
998  */
999 
1000  video_modes_lookup_.clear();
1001 
1002  OpenNI2VideoMode video_mode;
1003 
1004  // SXGA_30Hz
1005  video_mode.x_resolution_ = 1280;
1006  video_mode.y_resolution_ = 1024;
1007  video_mode.frame_rate_ = 30;
1008 
1009  video_modes_lookup_[1] = video_mode;
1010 
1011  // SXGA_15Hz
1012  video_mode.x_resolution_ = 1280;
1013  video_mode.y_resolution_ = 1024;
1014  video_mode.frame_rate_ = 15;
1015 
1016  video_modes_lookup_[2] = video_mode;
1017 
1018  // XGA_30Hz
1019  video_mode.x_resolution_ = 1280;
1020  video_mode.y_resolution_ = 720;
1021  video_mode.frame_rate_ = 30;
1022 
1023  video_modes_lookup_[3] = video_mode;
1024 
1025  // XGA_15Hz
1026  video_mode.x_resolution_ = 1280;
1027  video_mode.y_resolution_ = 720;
1028  video_mode.frame_rate_ = 15;
1029 
1030  video_modes_lookup_[4] = video_mode;
1031 
1032  // VGA_30Hz
1033  video_mode.x_resolution_ = 640;
1034  video_mode.y_resolution_ = 480;
1035  video_mode.frame_rate_ = 30;
1036 
1037  video_modes_lookup_[5] = video_mode;
1038 
1039  // VGA_25Hz
1040  video_mode.x_resolution_ = 640;
1041  video_mode.y_resolution_ = 480;
1042  video_mode.frame_rate_ = 25;
1043 
1044  video_modes_lookup_[6] = video_mode;
1045 
1046  // QVGA_25Hz
1047  video_mode.x_resolution_ = 320;
1048  video_mode.y_resolution_ = 240;
1049  video_mode.frame_rate_ = 25;
1050 
1051  video_modes_lookup_[7] = video_mode;
1052 
1053  // QVGA_30Hz
1054  video_mode.x_resolution_ = 320;
1055  video_mode.y_resolution_ = 240;
1056  video_mode.frame_rate_ = 30;
1057 
1058  video_modes_lookup_[8] = video_mode;
1059 
1060  // QVGA_60Hz
1061  video_mode.x_resolution_ = 320;
1062  video_mode.y_resolution_ = 240;
1063  video_mode.frame_rate_ = 60;
1064 
1065  video_modes_lookup_[9] = video_mode;
1066 
1067  // QQVGA_25Hz
1068  video_mode.x_resolution_ = 160;
1069  video_mode.y_resolution_ = 120;
1070  video_mode.frame_rate_ = 25;
1071 
1072  video_modes_lookup_[10] = video_mode;
1073 
1074  // QQVGA_30Hz
1075  video_mode.x_resolution_ = 160;
1076  video_mode.y_resolution_ = 120;
1077  video_mode.frame_rate_ = 30;
1078 
1079  video_modes_lookup_[11] = video_mode;
1080 
1081  // QQVGA_60Hz
1082  video_mode.x_resolution_ = 160;
1083  video_mode.y_resolution_ = 120;
1084  video_mode.frame_rate_ = 60;
1085 
1086  video_modes_lookup_[12] = video_mode;
1087 
1088 }
1089 
1091 {
1092  int ret = -1;
1093 
1094  std::map<int, OpenNI2VideoMode>::const_iterator it;
1095 
1096  it = video_modes_lookup_.find(mode_nr);
1097 
1098  if (it!=video_modes_lookup_.end())
1099  {
1100  video_mode = it->second;
1101  ret = 0;
1102  }
1103 
1104  return ret;
1105 }
1106 
1107 sensor_msgs::ImageConstPtr OpenNI2Driver::rawToFloatingPointConversion(sensor_msgs::ImageConstPtr raw_image)
1108 {
1109  static const float bad_point = std::numeric_limits<float>::quiet_NaN ();
1110 
1111  sensor_msgs::ImagePtr new_image = boost::make_shared<sensor_msgs::Image>();
1112 
1113  new_image->header = raw_image->header;
1114  new_image->width = raw_image->width;
1115  new_image->height = raw_image->height;
1116  new_image->is_bigendian = 0;
1117  new_image->encoding = sensor_msgs::image_encodings::TYPE_32FC1;
1118  new_image->step = sizeof(float)*raw_image->width;
1119 
1120  std::size_t data_size = new_image->width*new_image->height;
1121  new_image->data.resize(data_size*sizeof(float));
1122 
1123  const unsigned short* in_ptr = reinterpret_cast<const unsigned short*>(&raw_image->data[0]);
1124  float* out_ptr = reinterpret_cast<float*>(&new_image->data[0]);
1125 
1126  for (std::size_t i = 0; i<data_size; ++i, ++in_ptr, ++out_ptr)
1127  {
1128  if (*in_ptr==0 || *in_ptr==0x7FF)
1129  {
1130  *out_ptr = bad_point;
1131  } else
1132  {
1133  *out_ptr = static_cast<float>(*in_ptr)/1000.0f;
1134  }
1135  }
1136 
1137  return new_image;
1138 }
1139 
1140 }
boost::shared_ptr< ReconfigureServer > reconfigure_server_
reconfigure server
sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const
boost::shared_ptr< camera_info_manager::CameraInfoManager > ir_info_manager_
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
bool enable_reconnect_
indicates if reconnect logic is enabled.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
std::string resolveDeviceURI(const std::string &device_id)
void publish(const boost::shared_ptr< M > &message) const
bool serialnumber_as_name_
indicates if the serialnumber is used in the camera names. Default is false. The name is based on the...
ros::ServiceServer get_serial_server
get_serial server
uint32_t getNumSubscribers() const
boost::shared_ptr< OpenNI2Device > device_
XmlRpcServer s
bool getSerialCb(openni2_camera::GetSerialRequest &req, openni2_camera::GetSerialResponse &res)
sensor_msgs::ImageConstPtr rawToFloatingPointConversion(sensor_msgs::ImageConstPtr raw_image)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
openni2_camera::OpenNI2Config Config
void setColorVideoMode(const OpenNI2VideoMode &color_video_mode)
#define THROW_OPENNI_EXCEPTION(format,...)
void setDepthVideoMode(const OpenNI2VideoMode &depth_video_mode)
image_transport::CameraPublisher pub_depth_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
#define ROS_WARN(...)
boost::shared_ptr< OpenNI2DeviceManager > device_manager_
int lookupVideoModeFromDynConfig(int mode_nr, OpenNI2VideoMode &video_mode)
image_transport::CameraPublisher pub_ir_
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
boost::shared_ptr< camera_info_manager::CameraInfoManager > color_info_manager_
Camera info manager objects.
void newColorFrameCallback(sensor_msgs::ImagePtr image)
sensor_msgs::CameraInfoPtr getProjectorCameraInfo(int width, int height, ros::Time time) const
#define ROS_WARN_ONCE(...)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
const std::string TYPE_32FC1
General exception class.
sensor_msgs::CameraInfoPtr getDepthCameraInfo(int width, int height, ros::Time time) const
ROSCPP_DECL bool ok()
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
image_transport::CameraPublisher pub_depth_raw_
std::map< int, OpenNI2VideoMode > video_modes_lookup_
image_transport::CameraPublisher pub_color_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
sensor_msgs::CameraInfoPtr getColorCameraInfo(int width, int height, ros::Time time) const
OpenNI2Driver(ros::NodeHandle &n, ros::NodeHandle &pnh)
#define ROS_WARN_STREAM(args)
void monitorConnection(const ros::TimerEvent &event)
virtual const char * what() const
uint32_t getNumSubscribers() const
#define ROS_INFO_STREAM(args)
void newIRFrameCallback(sensor_msgs::ImagePtr image)
bool getParam(const std::string &key, std::string &s) const
dynamic_reconfigure::Server< Config > ReconfigureServer
sensor_msgs::CameraInfoPtr getIRCameraInfo(int width, int height, ros::Time time) const
int extractBusID(const std::string &uri) const
#define ROS_ERROR_STREAM(args)
ros::Timer timer_
timer for connection monitoring thread
#define ROS_ERROR(...)
void setIRVideoMode(const OpenNI2VideoMode &ir_video_mode)
OpenNI2VideoMode depth_video_mode_
OpenNI2VideoMode color_video_mode_
void newDepthFrameCallback(sensor_msgs::ImagePtr image)
#define ROS_DEBUG(...)
void configCb(Config &config, uint32_t level)


openni2_camera
Author(s): Julius Kammerl
autogenerated on Wed Feb 3 2021 03:18:41