driver.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011 Willow Garage, Inc.
5  * Suat Gedikli <gedikli@willowgarage.com>
6  * Patrick Michelich <michelich@willowgarage.com>
7  * Radu Bogdan Rusu <rusu@willowgarage.com>
8  *
9  * All rights reserved.
10  *
11  * Redistribution and use in source and binary forms, with or without
12  * modification, are permitted provided that the following conditions
13  * are met:
14  *
15  * * Redistributions of source code must retain the above copyright
16  * notice, this list of conditions and the following disclaimer.
17  * * Redistributions in binary form must reproduce the above
18  * copyright notice, this list of conditions and the following
19  * disclaimer in the documentation and/or other materials provided
20  * with the distribution.
21  * * Neither the name of Willow Garage, Inc. nor the names of its
22  * contributors may be used to endorse or promote products derived
23  * from this software without specific prior written permission.
24  *
25  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
26  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
27  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
28  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
29  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
30  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
31  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
32  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
33  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
34  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
35  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
36  * POSSIBILITY OF SUCH DAMAGE.
37  *
38  */
39 
40 #include "driver.h"
43 #include <boost/algorithm/string/replace.hpp>
44 #include <log4cxx/logger.h>
45 
46 
47 using namespace std;
48 namespace xiaoqiang_freenect_camera {
49 
50 DriverNodelet::~DriverNodelet ()
51 {
52  // If we're still stuck in initialization (e.g. can't connect to device), break out
53  init_thread_.interrupt();
54  init_thread_.join();
55 
56  // Interrupt and close diagnostics thread
57  close_diagnostics_ = true;
58  diagnostics_thread_.join();
59  if(motor_processing_)
60  {
61  close_tiltThread_ =true;
62  tilt_thread_.join();
63  }
64  FreenectDriver& driver = FreenectDriver::getInstance(subdevs_);
65  driver.shutdown();
66 
69 }
70 
71 void DriverNodelet::onInit ()
72 {
73 
74  // Setting up device can take awhile but onInit shouldn't block, so we spawn a
75  // new thread to do all the initialization
76  init_thread_ = boost::thread(boost::bind(&DriverNodelet::onInitImpl, this));
77 }
78 
79 void DriverNodelet::onInitImpl ()
80 {
81 
82  ros::NodeHandle& nh = this->getNodeHandle(); // topics
83  ros::NodeHandle& param_nh = this->getPrivateNodeHandle(); // parameters
84  num_frame_=1;
85  // Allow remapping namespaces rgb, ir, depth, depth_registered
87  ros::NodeHandle rgb_nh(nh, "rgb");
88  image_transport::ImageTransport rgb_it(rgb_nh);
89  ros::NodeHandle ir_nh(nh, "ir");
91  ros::NodeHandle depth_nh(nh, "depth");
92  image_transport::ImageTransport depth_it(depth_nh);
93  ros::NodeHandle depth_registered_nh(nh, "depth_registered");
94  image_transport::ImageTransport depth_registered_it(depth_registered_nh);
95  ros::NodeHandle projector_nh(nh, "projector");
96 
97  rgb_frame_counter_ = depth_frame_counter_ = ir_frame_counter_ = 0;
98  publish_rgb_ = publish_ir_ = publish_depth_ = true;
99 
100  // Check to see if we should enable debugging messages in libfreenect
101  // libfreenect_debug_ should be set before calling setupDevice
102  param_nh.param("debug" , libfreenect_debug_, false);
103 
104  // Initialize the sensor, but don't start any streams yet. That happens in the connection callbacks.
105  updateModeMaps();
106 
107  //get subdevs
108  param_nh.param("motor_processing", motor_processing_, false);
109  param_nh.param("audio_processing", audio_processing_, true);
110  param_nh.param("rgb_processing", rgb_processing_, false);
111  param_nh.param("ir_processing", ir_processing_, false);
112  param_nh.param("depth_processing", depth_processing_, false);
113  subdevs_=(freenect_device_flags)(0);
114  if(!(motor_processing_||audio_processing_||rgb_processing_||ir_processing_||depth_processing_))
115  {
117  }
118  if(motor_processing_) subdevs_=(freenect_device_flags)(subdevs_|FREENECT_DEVICE_MOTOR);
119  if(audio_processing_)
120  {
121  subdevs_=(freenect_device_flags)(subdevs_|FREENECT_DEVICE_AUDIO);
122  }
123  if(rgb_processing_||ir_processing_||depth_processing_) subdevs_=(freenect_device_flags)(subdevs_|FREENECT_DEVICE_CAMERA);
124 
125 
126  setupDevice();
127 
128  // Initialize dynamic reconfigure
129  reconfigure_server_.reset( new ReconfigureServer(param_nh) );
130 
131  reconfigure_server_->setCallback(boost::bind(&DriverNodelet::configCb, this, _1, _2));
132  // Camera TF frames
133  param_nh.param("rgb_frame_id", rgb_frame_id_, string("/openni_rgb_optical_frame"));
134  param_nh.param("depth_frame_id", depth_frame_id_, string("/openni_depth_optical_frame"));
135  NODELET_INFO("rgb_frame_id = '%s' ", rgb_frame_id_.c_str());
136  NODELET_INFO("depth_frame_id = '%s' ", depth_frame_id_.c_str());
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 = device_->getSerialNumber();
147  std::string rgb_name, ir_name;
148  if (serial_number.empty())
149  {
150  rgb_name = "rgb";
151  ir_name = "depth";
152  }
153  else
154  {
155  rgb_name = "rgb_" + serial_number;
156  ir_name = "depth_" + serial_number;
157  }
158 
159  std::string rgb_info_url, ir_info_url;
160  param_nh.param("rgb_camera_info_url", rgb_info_url, std::string());
161  param_nh.param("depth_camera_info_url", ir_info_url, std::string());
162 
163  double diagnostics_max_frequency, diagnostics_min_frequency;
164  double diagnostics_tolerance, diagnostics_window_time;
165 
166 
167  param_nh.param("enable_rgb_diagnostics", enable_rgb_diagnostics_, false);
168 
169 
170  param_nh.param("enable_ir_diagnostics", enable_ir_diagnostics_, false);
171 
172 
173  param_nh.param("enable_depth_diagnostics", enable_depth_diagnostics_, false);
174 
175 
176  param_nh.param("diagnostics_max_frequency", diagnostics_max_frequency, 30.0);
177 
178 
179  param_nh.param("diagnostics_min_frequency", diagnostics_min_frequency, 30.0);
180 
181 
182  param_nh.param("diagnostics_tolerance", diagnostics_tolerance, 0.05);
183 
184 
185  param_nh.param("diagnostics_window_time", diagnostics_window_time, 5.0);
186 
187  // Suppress some of the output from loading camera calibrations (kinda hacky)
188  log4cxx::LoggerPtr logger_ccp = log4cxx::Logger::getLogger("ros.camera_calibration_parsers");
189  log4cxx::LoggerPtr logger_cim = log4cxx::Logger::getLogger("ros.camera_info_manager");
190  logger_ccp->setLevel(log4cxx::Level::getFatal());
191  logger_cim->setLevel(log4cxx::Level::getWarn());
192  // Also suppress sync warnings from image_transport::CameraSubscriber. When subscribing to
193  // depth_registered/foo with Freenect registration disabled, the rectify nodelet for depth_registered/
194  // will complain because it receives depth_registered/camera_info (from the register nodelet), but
195  // the driver is not publishing depth_registered/image_raw.
196  log4cxx::LoggerPtr logger_its = log4cxx::Logger::getLogger("ros.image_transport.sync");
197  logger_its->setLevel(log4cxx::Level::getError());
199 
200  // Load the saved calibrations, if they exist
201  rgb_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(rgb_nh, rgb_name, rgb_info_url);
202  ir_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(ir_nh, ir_name, ir_info_url);
203 
204  if (!rgb_info_manager_->isCalibrated())
205  NODELET_WARN("Using default parameters for RGB camera calibration.");
206  if (!ir_info_manager_->isCalibrated())
207  NODELET_WARN("Using default parameters for IR camera calibration.");
208 
209  // Advertise all published topics
210  {
211  // Prevent connection callbacks from executing until we've set all the publishers. Otherwise
212  // connectCb() can fire while we're advertising (say) "depth/image_raw", but before we actually
213  // assign to pub_depth_. Then pub_depth_.getNumSubscribers() returns 0, and we fail to start
214  // the depth generator.
215  boost::lock_guard<boost::mutex> lock(connect_mutex_);
216 
217  // Instantiate the diagnostic updater
218  pub_freq_max_ = diagnostics_max_frequency;
219  pub_freq_min_ = diagnostics_min_frequency;
220  diagnostic_updater_.reset(new diagnostic_updater::Updater);
221 
222  // Set hardware id
223  std::string hardware_id = std::string(device_->getProductName()) + "-" +
224  std::string(device_->getSerialNumber());
225  diagnostic_updater_->setHardwareID(hardware_id);
226 
227 
228  // Asus Xtion PRO does not have an RGB camera
229  if (device_->hasImageStream()&&rgb_processing_)
230  {
231  image_transport::SubscriberStatusCallback itssc = boost::bind(&DriverNodelet::rgbConnectCb, this);
232  ros::SubscriberStatusCallback rssc = boost::bind(&DriverNodelet::rgbConnectCb, this);
233  pub_rgb_ = rgb_it.advertiseCamera("image_raw", 1, itssc, itssc, rssc, rssc);
234  if (enable_rgb_diagnostics_) {
235  pub_rgb_freq_.reset(new TopicDiagnostic("RGB Image", *diagnostic_updater_,
236  FrequencyStatusParam(&pub_freq_min_, &pub_freq_max_,
237  diagnostics_tolerance, diagnostics_window_time)));
238  }
239  }
240 
241  if (device_->hasIRStream()&&ir_processing_)
242  {
243  image_transport::SubscriberStatusCallback itssc = boost::bind(&DriverNodelet::irConnectCb, this);
244  ros::SubscriberStatusCallback rssc = boost::bind(&DriverNodelet::irConnectCb, this);
245  pub_ir_ = ir_it.advertiseCamera("image_raw", 1, itssc, itssc, rssc, rssc);
246  if (enable_ir_diagnostics_) {
247  pub_ir_freq_.reset(new TopicDiagnostic("IR Image", *diagnostic_updater_,
248  FrequencyStatusParam(&pub_freq_min_, &pub_freq_max_,
249  diagnostics_tolerance, diagnostics_window_time)));
250  }
251  }
252 
253  if (device_->hasDepthStream()&&depth_processing_)
254  {
255  image_transport::SubscriberStatusCallback itssc = boost::bind(&DriverNodelet::depthConnectCb, this);
256  ros::SubscriberStatusCallback rssc = boost::bind(&DriverNodelet::depthConnectCb, this);
257  pub_depth_ = depth_it.advertiseCamera("image_raw", 1, itssc, itssc, rssc, rssc);
258  if (enable_depth_diagnostics_) {
259  pub_depth_freq_.reset(new TopicDiagnostic("Depth Image", *diagnostic_updater_,
260  FrequencyStatusParam(&pub_freq_min_, &pub_freq_max_,
261  diagnostics_tolerance, diagnostics_window_time)));
262  }
263 
264  pub_projector_info_ = projector_nh.advertise<sensor_msgs::CameraInfo>("camera_info", 1, rssc, rssc);
265 
266  if (device_->isDepthRegistrationSupported()) {
267  pub_depth_registered_ = depth_registered_it.advertiseCamera("image_raw", 1, itssc, itssc, rssc, rssc);
268  }
269  }
270  }
271 
272  //stop camera stream
273  if(subdevs_&FREENECT_DEVICE_CAMERA)
274  {
275  stopSynchronization();
276  if(!depth_processing_ && device_->isDepthStreamRunning())
277  {
278  device_->stopDepthStream();
279  }
280  if(!rgb_processing_ && device_->isImageStreamRunning())
281  {
282  device_->stopImageStream();
283  }
284  if(!ir_processing_ && device_->isIRStreamRunning())
285  {
286  device_->stopIRStream();
287  }
288  startSynchronization();
289  }
290  // Create separate diagnostics thread
291  close_diagnostics_ = false;
292  diagnostics_thread_ = boost::thread(boost::bind(&DriverNodelet::updateDiagnostics, this));
293 
294  // Create watch dog timer callback
295  param_nh.param<double>("time_out", time_out_, 5.0);
296  if (time_out_ > 0.0)
297  {
298  watch_dog_timer_ = nh.createTimer(ros::Duration(time_out_), &DriverNodelet::watchDog, this);
299  }
300 
301  device_->publishersAreReady();
302 
303  // Create separate tilt motor thread
304  if(motor_processing_)
305  {
306  close_tiltThread_ = false;
307  tiltDriver_= TiltDriver(device_,&close_tiltThread_);
308  tilt_thread_ = boost::thread(boost::bind(&TiltDriver::run, &tiltDriver_));
309  }
310 
311 
312 }
313 
314 void DriverNodelet::updateDiagnostics() {
315  while (!close_diagnostics_) {
316  diagnostic_updater_->update();
317  boost::this_thread::sleep(boost::posix_time::milliseconds(10));
318  }
319 }
320 
321 void DriverNodelet::setupDevice ()
322 {
323  // Initialize the openni device
324  FreenectDriver& driver = FreenectDriver::getInstance(subdevs_);
325  ROS_INFO("subdevs: %d\n",subdevs_);
326  // Enable debugging in libfreenect if requested
327  if (libfreenect_debug_)
328  driver.enableDebug();
329 
330  do {
331  driver.updateDeviceList ();
332 
333  if (driver.getNumberDevices () == 0)
334  {
335  NODELET_INFO ("No devices connected.... waiting for devices to be connected");
336  boost::this_thread::sleep(boost::posix_time::seconds(3));
337  continue;
338  }
339 
340  NODELET_INFO ("Number devices connected: %d", driver.getNumberDevices ());
341  for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
342  {
343  NODELET_INFO("%u. device on bus %03u:%02u is a %s (%03x) from %s (%03x) with serial id \'%s\'",
344  deviceIdx + 1, driver.getBus(deviceIdx), driver.getAddress(deviceIdx),
345  driver.getProductName(deviceIdx), driver.getProductID(deviceIdx),
346  driver.getVendorName(deviceIdx), driver.getVendorID(deviceIdx),
347  driver.getSerialNumber(deviceIdx));
348  }
349 
350  try {
351  string device_id;
352  if (!getPrivateNodeHandle().getParam("device_id", device_id))
353  {
354  NODELET_WARN ("~device_id is not set! Using first device.");
355  device_ = driver.getDeviceByIndex(0);
356  }
357  else if (device_id.find ('@') != string::npos)
358  {
359  size_t pos = device_id.find ('@');
360  unsigned bus = atoi (device_id.substr (0, pos).c_str ());
361  unsigned address = atoi (device_id.substr (pos + 1, device_id.length () - pos - 1).c_str ());
362  NODELET_INFO ("Searching for device with bus@address = %d@%d", bus, address);
363  device_ = driver.getDeviceByAddress (bus, address);
364  }
365  else if (device_id[0] == '#')
366  {
367  unsigned index = atoi (device_id.c_str() + 1);
368  NODELET_INFO ("Searching for device with index = %d", index);
369  device_ = driver.getDeviceByIndex (index - 1);
370  }
371  else
372  {
373  NODELET_INFO ("Searching for device with serial number = '%s'", device_id.c_str ());
374  device_ = driver.getDeviceBySerialNumber (device_id);
375  }
376  }
377  catch (exception& e)
378  {
379  if (!device_)
380  {
381  NODELET_INFO ("No matching device found.... waiting for devices. Reason: %s", e.what ());
382  boost::this_thread::sleep(boost::posix_time::seconds(3));
383  continue;
384  }
385  else
386  {
387  NODELET_FATAL ("Could not retrieve device. Reason: %s", e.what ());
388  exit (-1);
389  }
390  }
391  } while (!device_);
392 
393  NODELET_INFO ("Opened '%s' on bus %d:%d with serial number '%s'", device_->getProductName (),
394  device_->getBus (), device_->getAddress (), device_->getSerialNumber ());
395 
396  if(subdevs_&FREENECT_DEVICE_CAMERA) device_->registerImageCallback(&DriverNodelet::rgbCb, *this);
397  if(subdevs_&FREENECT_DEVICE_CAMERA) device_->registerDepthCallback(&DriverNodelet::depthCb, *this);
398  if(subdevs_&FREENECT_DEVICE_CAMERA) device_->registerIRCallback (&DriverNodelet::irCb, *this);
399 
400 
401 }
402 
403 void DriverNodelet::rgbConnectCb()
404 {
405  //std::cout << "rgb connect cb called";
406  boost::lock_guard<boost::mutex> lock(connect_mutex_);
407  //std::cout << "..." << std::endl;
408  bool need_rgb = pub_rgb_.getNumSubscribers() > 0;
409  //std::cout << " need_rgb: " << need_rgb << std::endl;
410 
411  if (need_rgb && !device_->isImageStreamRunning())
412  {
413  // Can't stream IR and RGB at the same time. Give RGB preference.
414  if (device_->isIRStreamRunning())
415  {
416  NODELET_ERROR("Cannot stream RGB and IR at the same time. Streaming RGB only.");
417  device_->stopIRStream();
418  }
419 
420  device_->startImageStream();
421  startSynchronization();
422  rgb_time_stamp_ = ros::Time::now(); // update stamp for watchdog
423  }
424  else if (!need_rgb && device_->isImageStreamRunning())
425  {
426  stopSynchronization();
427  device_->stopImageStream();
428 
429  // Start IR if it's been blocked on RGB subscribers
430  bool need_ir = pub_ir_.getNumSubscribers() > 0;
431  if (need_ir && !device_->isIRStreamRunning())
432  {
433  device_->startIRStream();
434  ir_time_stamp_ = ros::Time::now(); // update stamp for watchdog
435  }
436  }
437  //std::cout << "rgb connect cb end..." << std::endl;
438 }
439 
440 void DriverNodelet::depthConnectCb()
441 {
442  //std::cout << "depth connect cb called";
443  boost::lock_guard<boost::mutex> lock(connect_mutex_);
444  //std::cout << "..." << std::endl;
446  bool need_depth =
447  device_->isDepthRegistered() ? pub_depth_registered_.getNumSubscribers() > 0 : pub_depth_.getNumSubscribers() > 0;
449  //std::cout << " need_depth: " << need_depth << std::endl;
450 
451  if (need_depth && !device_->isDepthStreamRunning())
452  {
453  device_->startDepthStream();
454  startSynchronization();
455  depth_time_stamp_ = ros::Time::now(); // update stamp for watchdog
456 
457  }
458  else if (!need_depth && device_->isDepthStreamRunning())
459  {
460  stopSynchronization();
461  device_->stopDepthStream();
462  }
463  //std::cout << "depth connect cb end..." << std::endl;
464 }
465 
466 void DriverNodelet::irConnectCb()
467 {
468  boost::lock_guard<boost::mutex> lock(connect_mutex_);
469  bool need_ir = pub_ir_.getNumSubscribers() > 0;
470 
471  if (need_ir && !device_->isIRStreamRunning())
472  {
473  // Can't stream IR and RGB at the same time
474  if (device_->isImageStreamRunning())
475  {
476  NODELET_ERROR("Cannot stream RGB and IR at the same time. Streaming RGB only.");
477  }
478  else
479  {
480  device_->startIRStream();
481  ir_time_stamp_ = ros::Time::now(); // update stamp for watchdog
482  }
483  }
484  else if (!need_ir)
485  {
486  device_->stopIRStream();
487  }
488 }
489 
490 // If any stream is ready, publish next available image from all streams
491 // This publishes all available data with a maximum time offset of one frame between any two sources
492 // Need to have lock to call this, since callbacks can be in different threads
493 void DriverNodelet::checkFrameCounters()
494 {
495  if (max(rgb_frame_counter_, max(depth_frame_counter_, ir_frame_counter_)) > config_.data_skip) {
496  // Reset all counters after we trigger publish
497  rgb_frame_counter_ = 0;
498  depth_frame_counter_ = 0;
499  ir_frame_counter_ = 0;
500 
501  // Trigger publish on all topics
502  publish_rgb_ = true;
503  publish_depth_ = true;
504  publish_ir_ = true;
505  }
506 }
507 
508 void DriverNodelet::rgbCb(const ImageBuffer& image, void* cookie)
509 {
510  ros::Time time = ros::Time::now () + ros::Duration(config_.image_time_offset);
511  rgb_time_stamp_ = time; // for watchdog
512 
513  bool publish = false;
514  {
515  boost::unique_lock<boost::mutex> counter_lock(counter_mutex_);
516  rgb_frame_counter_++;
517  checkFrameCounters();
518  publish = publish_rgb_;
519 
520  if (publish)
521  rgb_frame_counter_ = 0; // Reset counter if we publish this message to avoid under-throttling
522  }
523 
524  if (publish)
525  publishRgbImage(image, time);
526 
527  publish_rgb_ = false;
528 }
529 
530 void DriverNodelet::depthCb(const ImageBuffer& depth_image, void* cookie)
531 {
532  ros::Time time = ros::Time::now () + ros::Duration(config_.depth_time_offset);
533  depth_time_stamp_ = time; // for watchdog
534  if((num_frame_%3==0))
535  {
536  num_frame_++;
537  return;//20hz
538  }
539  num_frame_++;
540  bool publish = false;
541  {
542  boost::unique_lock<boost::mutex> counter_lock(counter_mutex_);
543  depth_frame_counter_++;
544  checkFrameCounters();
545  publish = publish_depth_;
546 
547  if (publish)
548  depth_frame_counter_ = 0; // Reset counter if we publish this message to avoid under-throttling
549  }
550 
551  if (publish)
552  publishDepthImage(depth_image, time);
553 
554  publish_depth_ = false;
555 }
556 
557 void DriverNodelet::irCb(const ImageBuffer& ir_image, void* cookie)
558 {
559  ros::Time time = ros::Time::now() + ros::Duration(config_.depth_time_offset);
560  ir_time_stamp_ = time; // for watchdog
561 
562  bool publish = false;
563  {
564  boost::unique_lock<boost::mutex> counter_lock(counter_mutex_);
565  ir_frame_counter_++;
566  checkFrameCounters();
567  publish = publish_ir_;
568 
569  if (publish)
570  ir_frame_counter_ = 0; // Reset counter if we publish this message to avoid under-throttling
571  }
572 
573  if (publish)
574  publishIrImage(ir_image, time);
575  publish_ir_ = false;
576 }
577 
578 void DriverNodelet::publishRgbImage(const ImageBuffer& image, ros::Time time) const
579 {
580  //NODELET_INFO_THROTTLE(1.0, "rgb image callback called");
581  sensor_msgs::ImagePtr rgb_msg = boost::make_shared<sensor_msgs::Image >();
582  rgb_msg->header.stamp = time;
583  rgb_msg->header.frame_id = rgb_frame_id_;
584  rgb_msg->height = image.metadata.height;
585  rgb_msg->width = image.metadata.width;
586  switch(image.metadata.video_format) {
587  case FREENECT_VIDEO_RGB:
588  rgb_msg->encoding = sensor_msgs::image_encodings::RGB8;
589  rgb_msg->step = rgb_msg->width * 3;
590  break;
592  rgb_msg->encoding = sensor_msgs::image_encodings::BAYER_GRBG8;
593  rgb_msg->step = rgb_msg->width;
594  break;
596  rgb_msg->encoding = sensor_msgs::image_encodings::YUV422;
597  rgb_msg->step = rgb_msg->width * 2;
598  break;
599  default:
600  NODELET_ERROR("Unknown RGB image format received from libfreenect");
601  // Unknown encoding -- don't publish
602  return;
603  }
604  rgb_msg->data.resize(rgb_msg->height * rgb_msg->step);
605  fillImage(image, reinterpret_cast<void*>(&rgb_msg->data[0]));
606 
607  pub_rgb_.publish(rgb_msg, getRgbCameraInfo(image, time));
608  if (enable_rgb_diagnostics_)
609  pub_rgb_freq_->tick();
610 }
611 
612 void DriverNodelet::publishDepthImage(const ImageBuffer& depth, ros::Time time) const
613 {
614  //NODELET_INFO_THROTTLE(1.0, "depth image callback called");
615  bool registered = depth.is_registered;
616 
617  sensor_msgs::ImagePtr depth_msg = boost::make_shared<sensor_msgs::Image>();
618  depth_msg->header.stamp = time;
619  depth_msg->encoding = sensor_msgs::image_encodings::TYPE_16UC1;
620  depth_msg->height = depth.metadata.height;
621  depth_msg->width = depth.metadata.width;
622  depth_msg->step = depth_msg->width * sizeof(short);
623  depth_msg->data.resize(depth_msg->height * depth_msg->step);
624 
625  fillImage(depth, reinterpret_cast<void*>(&depth_msg->data[0]));
626 
627  if (z_offset_mm_ != 0)
628  {
629  uint16_t* data = reinterpret_cast<uint16_t*>(&depth_msg->data[0]);
630  for (unsigned int i = 0; i < depth_msg->width * depth_msg->height; ++i)
631  if (data[i] != 0)
632  data[i] += z_offset_mm_;
633  }
634 
635  if (registered)
636  {
637  // Publish RGB camera info and raw depth image to depth_registered/ ns
638  depth_msg->header.frame_id = rgb_frame_id_;
639  pub_depth_registered_.publish(depth_msg, getRgbCameraInfo(depth, time));
640  }
641  else
642  {
643  // Publish depth camera info and raw depth image to depth/ ns
644  depth_msg->header.frame_id = depth_frame_id_;
645  pub_depth_.publish(depth_msg, getDepthCameraInfo(depth, time));
646  }
647  if (enable_depth_diagnostics_)
648  pub_depth_freq_->tick();
649 
650  // Projector "info" probably only useful for working with disparity images
651  if (pub_projector_info_.getNumSubscribers() > 0)
652  {
653  pub_projector_info_.publish(getProjectorCameraInfo(depth, time));
654  }
655 }
656 
657 void DriverNodelet::publishIrImage(const ImageBuffer& ir, ros::Time time) const
658 {
659  sensor_msgs::ImagePtr ir_msg = boost::make_shared<sensor_msgs::Image>();
660  ir_msg->header.stamp = time;
661  ir_msg->header.frame_id = depth_frame_id_;
662  ir_msg->encoding = sensor_msgs::image_encodings::MONO16;
663  ir_msg->height = ir.metadata.height;
664  ir_msg->width = ir.metadata.width;
665  ir_msg->step = ir_msg->width * sizeof(uint16_t);
666  ir_msg->data.resize(ir_msg->height * ir_msg->step);
667 
668  fillImage(ir, reinterpret_cast<void*>(&ir_msg->data[0]));
669 
670  pub_ir_.publish(ir_msg, getIrCameraInfo(ir, time));
671 
672  if (enable_ir_diagnostics_)
673  pub_ir_freq_->tick();
674 }
675 
676 sensor_msgs::CameraInfoPtr DriverNodelet::getDefaultCameraInfo(int width, int height, double f) const
677 {
678  sensor_msgs::CameraInfoPtr info = boost::make_shared<sensor_msgs::CameraInfo>();
679 
680  info->width = width;
681  info->height = height;
682 
683  // No distortion
684  info->D.resize(5, 0.0);
685  info->distortion_model = sensor_msgs::distortion_models::PLUMB_BOB;
686 
687  // Simple camera matrix: square pixels (fx = fy), principal point at center
688  info->K.assign(0.0);
689  info->K[0] = info->K[4] = f;
690  info->K[2] = (width / 2) - 0.5;
691  // Aspect ratio for the camera center on Kinect (and other devices?) is 4/3
692  // This formula keeps the principal point the same in VGA and SXGA modes
693  info->K[5] = (width * (3./8.)) - 0.5;
694  info->K[8] = 1.0;
695 
696  // No separate rectified image plane, so R = I
697  info->R.assign(0.0);
698  info->R[0] = info->R[4] = info->R[8] = 1.0;
699 
700  // Then P=K(I|0) = (K|0)
701  info->P.assign(0.0);
702  info->P[0] = info->P[5] = f; // fx, fy
703  info->P[2] = info->K[2]; // cx
704  info->P[6] = info->K[5]; // cy
705  info->P[10] = 1.0;
706 
707  return info;
708 }
709 
711 sensor_msgs::CameraInfoPtr DriverNodelet::getRgbCameraInfo(const ImageBuffer& image, ros::Time time) const
712 {
713  sensor_msgs::CameraInfoPtr info;
714 
715  if (rgb_info_manager_->isCalibrated())
716  {
717  info = boost::make_shared<sensor_msgs::CameraInfo>(rgb_info_manager_->getCameraInfo());
718  }
719  else
720  {
721  // If uncalibrated, fill in default values
722  info = getDefaultCameraInfo(image.metadata.width, image.metadata.height, image.focal_length);
723  }
724 
725  // Fill in header
726  info->header.stamp = time;
727  info->header.frame_id = rgb_frame_id_;
728 
729  return info;
730 }
731 
732 sensor_msgs::CameraInfoPtr DriverNodelet::getIrCameraInfo(
733  const ImageBuffer& image, ros::Time time) const {
734  sensor_msgs::CameraInfoPtr info;
735 
736  if (ir_info_manager_->isCalibrated())
737  {
738  info = boost::make_shared<sensor_msgs::CameraInfo>(ir_info_manager_->getCameraInfo());
739  }
740  else
741  {
742  // If uncalibrated, fill in default values
743  info = getDefaultCameraInfo(image.metadata.width, image.metadata.height, image.focal_length);
744  }
745 
746  // Fill in header
747  info->header.stamp = time;
748  info->header.frame_id = depth_frame_id_;
749 
750  return info;
751 }
752 
753 sensor_msgs::CameraInfoPtr DriverNodelet::getDepthCameraInfo(
754  const ImageBuffer& image, ros::Time time) const {
755  // The depth image has essentially the same intrinsics as the IR image, BUT the
756  // principal point is offset by half the size of the hardware correlation window
757  // (probably 9x9 or 9x7). See http://www.ros.org/wiki/kinect_calibration/technical
758 
759  sensor_msgs::CameraInfoPtr info = getIrCameraInfo(image, time);
760  info->K[2] -= depth_ir_offset_x_; // cx
761  info->K[5] -= depth_ir_offset_y_; // cy
762  info->P[2] -= depth_ir_offset_x_; // cx
763  info->P[6] -= depth_ir_offset_y_; // cy
764 
766  return info;
767 }
768 
769 sensor_msgs::CameraInfoPtr DriverNodelet::getProjectorCameraInfo(
770  const ImageBuffer& image, ros::Time time) const {
771  // The projector info is simply the depth info with the baseline encoded in the P matrix.
772  // It's only purpose is to be the "right" camera info to the depth camera's "left" for
773  // processing disparity images.
774  sensor_msgs::CameraInfoPtr info = getDepthCameraInfo(image, time);
775  // Tx = -baseline * fx
776  info->P[3] = -device_->getBaseline() * info->P[0];
777  return info;
778 }
779 
780 void DriverNodelet::configCb(Config &config, uint32_t level)
781 {
782  depth_ir_offset_x_ = config.depth_ir_offset_x;
783  depth_ir_offset_y_ = config.depth_ir_offset_y;
784  z_offset_mm_ = config.z_offset_mm;
785 
786  // We need this for the ASUS Xtion Pro
787  OutputMode old_image_mode, image_mode, compatible_image_mode;
788  if (device_->hasImageStream ())
789  {
790  old_image_mode = device_->getImageOutputMode ();
791 
792  // does the device support the new image mode?
793  image_mode = mapConfigMode2OutputMode (config.image_mode);
794 
795  if (!device_->findCompatibleImageMode (image_mode, compatible_image_mode))
796  {
797  OutputMode default_mode = device_->getDefaultImageMode();
798  NODELET_WARN("Could not find any compatible image output mode for %d. "
799  "Falling back to default image output mode %d.",
800  image_mode,
801  default_mode);
802 
803  config.image_mode = mapMode2ConfigMode(default_mode);
804  image_mode = compatible_image_mode = default_mode;
805  }
806  }
807 
808  OutputMode old_depth_mode, depth_mode, compatible_depth_mode;
809  old_depth_mode = device_->getDepthOutputMode();
810  depth_mode = mapConfigMode2OutputMode (config.depth_mode);
811  if (!device_->findCompatibleDepthMode (depth_mode, compatible_depth_mode))
812  {
813  OutputMode default_mode = device_->getDefaultDepthMode();
814  NODELET_WARN("Could not find any compatible depth output mode for %d. "
815  "Falling back to default depth output mode %d.",
816  depth_mode,
817  default_mode);
818 
819  config.depth_mode = mapMode2ConfigMode(default_mode);
820  depth_mode = compatible_depth_mode = default_mode;
821  }
822 
823  // here everything is fine. Now make the changes
824  if ( (device_->hasImageStream () && compatible_image_mode != old_image_mode) ||
825  compatible_depth_mode != old_depth_mode)
826  {
827  // streams need to be reset!
828  stopSynchronization();
829 
830  if (device_->hasImageStream () && compatible_image_mode != old_image_mode)
831  device_->setImageOutputMode (compatible_image_mode);
832 
833  if (compatible_depth_mode != old_depth_mode)
834  device_->setDepthOutputMode (compatible_depth_mode);
835 
836  startSynchronization ();
837  }
838 
839  // @todo Run connectCb if registration setting changes
840  if (device_->isDepthRegistered () && !config.depth_registration)
841  {
842  device_->setDepthRegistration (false);
843  }
844  else if (!device_->isDepthRegistered () && config.depth_registration)
845  {
846  device_->setDepthRegistration (true);
847  }
848 
849  // now we can copy
850  config_ = config;
851 }
852 
853 void DriverNodelet::startSynchronization()
854 {
855  if (device_->isSynchronizationSupported() &&
856  !device_->isSynchronized() &&
857  device_->isImageStreamRunning() &&
858  device_->isDepthStreamRunning() )
859  {
860  device_->setSynchronization(true);
861  }
862 }
863 
864 void DriverNodelet::stopSynchronization()
865 {
866  if (device_->isSynchronizationSupported() &&
867  device_->isSynchronized())
868  {
869  device_->setSynchronization(false);
870  }
871 }
872 
873 void DriverNodelet::updateModeMaps ()
874 {
875  OutputMode output_mode;
876 
877  output_mode = FREENECT_RESOLUTION_HIGH;
878  mode2config_map_[output_mode] = Freenect_SXGA;
879  config2mode_map_[Freenect_SXGA] = output_mode;
880 
881  output_mode = FREENECT_RESOLUTION_MEDIUM;
882  mode2config_map_[output_mode] = Freenect_VGA;
883  config2mode_map_[Freenect_VGA] = output_mode;
884 }
885 
886 int DriverNodelet::mapMode2ConfigMode (const OutputMode& output_mode) const
887 {
888  std::map<OutputMode, int>::const_iterator it = mode2config_map_.find (output_mode);
889 
890  if (it == mode2config_map_.end ())
891  {
892  NODELET_ERROR ("mode not be found");
893  exit (-1);
894  }
895  else
896  return it->second;
897 }
898 
899 OutputMode DriverNodelet::mapConfigMode2OutputMode (int mode) const
900 {
901  std::map<int, OutputMode>::const_iterator it = config2mode_map_.find (mode);
902  if (it == config2mode_map_.end ())
903  {
904  NODELET_ERROR ("mode %d could not be found", mode);
905  exit (-1);
906  }
907  else
908  return it->second;
909 }
910 
911 void DriverNodelet::watchDog (const ros::TimerEvent& event)
912 {
913  bool timed_out = false;
914  if (!rgb_time_stamp_.isZero() && device_->isImageStreamRunning()) {
915  ros::Duration duration = ros::Time::now() - rgb_time_stamp_;
916  timed_out = timed_out || duration.toSec() > time_out_;
917  }
918  if (!depth_time_stamp_.isZero() && device_->isDepthStreamRunning()) {
919  ros::Duration duration = ros::Time::now() - depth_time_stamp_;
920  timed_out = timed_out || duration.toSec() > time_out_;
921  }
922  if (!ir_time_stamp_.isZero() && device_->isIRStreamRunning()) {
923  ros::Duration duration = ros::Time::now() - ir_time_stamp_;
924  timed_out = timed_out || duration.toSec() > time_out_;
925  }
926 
927  if (timed_out) {
928  ROS_INFO("Device timed out. Flushing device.");
929  if(subdevs_&FREENECT_DEVICE_CAMERA) device_->flushDeviceStreams();
930  }
931 
932 }
933 
934 }
935 
936 // Register as nodelet
dynamic_reconfigure::Server< Config > ReconfigureServer
Definition: driver.h:69
const std::string BAYER_GRBG8
FREENECT_VIDEO_RGB
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
#define NODELET_ERROR(...)
void fillImage(const ImageBuffer &buffer, void *data)
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
#define NODELET_WARN(...)
unsigned short uint16_t
boost::shared_ptr< FreenectDevice > getDeviceByAddress(unsigned bus, unsigned address)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
data
Holds an image buffer with all the metadata required to transmit the image over ROS channels...
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
FREENECT_DEVICE_MOTOR
unsigned getVendorID(unsigned device_idx)
boost::shared_ptr< FreenectDevice > getDeviceByIndex(unsigned device_idx)
#define ROS_INFO(...)
unsigned getBus(unsigned device_idx)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
char * rgb_name
const std::string TYPE_16UC1
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
FREENECT_DEVICE_AUDIO
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
const std::string MONO16
boost::shared_ptr< FreenectDevice > getDeviceBySerialNumber(std::string serial)
const char * getSerialNumber(unsigned device_idx)
FREENECT_VIDEO_YUV_RGB
FREENECT_VIDEO_BAYER
FREENECT_DEVICE_CAMERA
freenect_resolution
#define NODELET_INFO(...)
FREENECT_RESOLUTION_MEDIUM
const std::string YUV422
const char * getProductName(unsigned device_idx)
unsigned int uint32_t
unsigned getAddress(unsigned device_idx)
static Time now()
freenect_device_flags
#define NODELET_FATAL(...)
FREENECT_RESOLUTION_HIGH
const char * getVendorName(unsigned device_idx)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
unsigned getProductID(unsigned device_idx)
freenect_video_format video_format


xiaoqiang_freenect_camera
Author(s): Patrick Mihelich, Suat Gedikli, Radu Bogdan Rusu (original openni_camera driver)., Piyush Khandelwal (libfreenect port).
autogenerated on Mon Jun 10 2019 15:53:18