00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #include "driver.h"
00040 #include <sensor_msgs/image_encodings.h>
00041 #include <sensor_msgs/distortion_models.h>
00042 #include <boost/algorithm/string/replace.hpp>
00043
00044 using namespace std;
00045 namespace freenect_camera {
00046
00047 DriverNodelet::~DriverNodelet ()
00048 {
00049
00050 init_thread_.interrupt();
00051 init_thread_.join();
00052
00053
00054 close_diagnostics_ = true;
00055 diagnostics_thread_.join();
00056
00057 FreenectDriver& driver = FreenectDriver::getInstance ();
00058 driver.shutdown();
00059
00062 }
00063
00064 void DriverNodelet::onInit ()
00065 {
00066
00067
00068 init_thread_ = boost::thread(boost::bind(&DriverNodelet::onInitImpl, this));
00069 }
00070
00071 void DriverNodelet::onInitImpl ()
00072 {
00073 ros::NodeHandle& nh = getNodeHandle();
00074 ros::NodeHandle& param_nh = getPrivateNodeHandle();
00075
00076
00077 image_transport::ImageTransport it(nh);
00078 ros::NodeHandle rgb_nh(nh, "rgb");
00079 image_transport::ImageTransport rgb_it(rgb_nh);
00080 ros::NodeHandle ir_nh(nh, "ir");
00081 image_transport::ImageTransport ir_it(ir_nh);
00082 ros::NodeHandle depth_nh(nh, "depth");
00083 image_transport::ImageTransport depth_it(depth_nh);
00084 ros::NodeHandle depth_registered_nh(nh, "depth_registered");
00085 image_transport::ImageTransport depth_registered_it(depth_registered_nh);
00086 ros::NodeHandle projector_nh(nh, "projector");
00087
00088 rgb_frame_counter_ = depth_frame_counter_ = ir_frame_counter_ = 0;
00089 publish_rgb_ = publish_ir_ = publish_depth_ = true;
00090
00091
00092
00093 param_nh.param("debug" , libfreenect_debug_, false);
00094
00095
00096 updateModeMaps();
00097 setupDevice();
00098
00099
00100 reconfigure_server_.reset( new ReconfigureServer(param_nh) );
00101 reconfigure_server_->setCallback(boost::bind(&DriverNodelet::configCb, this, _1, _2));
00102
00103
00104 param_nh.param("rgb_frame_id", rgb_frame_id_, string("/openni_rgb_optical_frame"));
00105 param_nh.param("depth_frame_id", depth_frame_id_, string("/openni_depth_optical_frame"));
00106 NODELET_INFO("rgb_frame_id = '%s' ", rgb_frame_id_.c_str());
00107 NODELET_INFO("depth_frame_id = '%s' ", depth_frame_id_.c_str());
00108
00109
00110
00111
00112
00113
00114
00115
00116
00117 std::string serial_number = device_->getSerialNumber();
00118 std::string rgb_name, ir_name;
00119 if (serial_number.empty())
00120 {
00121 rgb_name = "rgb";
00122 ir_name = "depth";
00123 }
00124 else
00125 {
00126 rgb_name = "rgb_" + serial_number;
00127 ir_name = "depth_" + serial_number;
00128 }
00129
00130 std::string rgb_info_url, ir_info_url;
00131 param_nh.param("rgb_camera_info_url", rgb_info_url, std::string());
00132 param_nh.param("depth_camera_info_url", ir_info_url, std::string());
00133
00134 double diagnostics_max_frequency, diagnostics_min_frequency;
00135 double diagnostics_tolerance, diagnostics_window_time;
00136 param_nh.param("enable_rgb_diagnostics", enable_rgb_diagnostics_, false);
00137 param_nh.param("enable_ir_diagnostics", enable_ir_diagnostics_, false);
00138 param_nh.param("enable_depth_diagnostics", enable_depth_diagnostics_, false);
00139 param_nh.param("diagnostics_max_frequency", diagnostics_max_frequency, 30.0);
00140 param_nh.param("diagnostics_min_frequency", diagnostics_min_frequency, 30.0);
00141 param_nh.param("diagnostics_tolerance", diagnostics_tolerance, 0.05);
00142 param_nh.param("diagnostics_window_time", diagnostics_window_time, 5.0);
00143
00144
00145 log4cxx::LoggerPtr logger_ccp = log4cxx::Logger::getLogger("ros.camera_calibration_parsers");
00146 log4cxx::LoggerPtr logger_cim = log4cxx::Logger::getLogger("ros.camera_info_manager");
00147 logger_ccp->setLevel(log4cxx::Level::getFatal());
00148 logger_cim->setLevel(log4cxx::Level::getWarn());
00149
00150
00151
00152
00153 log4cxx::LoggerPtr logger_its = log4cxx::Logger::getLogger("ros.image_transport.sync");
00154 logger_its->setLevel(log4cxx::Level::getError());
00155 ros::console::notifyLoggerLevelsChanged();
00156
00157
00158 rgb_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(rgb_nh, rgb_name, rgb_info_url);
00159 ir_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(ir_nh, ir_name, ir_info_url);
00160
00161 if (!rgb_info_manager_->isCalibrated())
00162 NODELET_WARN("Using default parameters for RGB camera calibration.");
00163 if (!ir_info_manager_->isCalibrated())
00164 NODELET_WARN("Using default parameters for IR camera calibration.");
00165
00166
00167 {
00168
00169
00170
00171
00172 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00173
00174
00175 pub_freq_max_ = diagnostics_max_frequency;
00176 pub_freq_min_ = diagnostics_min_frequency;
00177 diagnostic_updater_.reset(new diagnostic_updater::Updater);
00178
00179
00180 std::string hardware_id = std::string(device_->getProductName()) + "-" +
00181 std::string(device_->getSerialNumber());
00182 diagnostic_updater_->setHardwareID(hardware_id);
00183
00184
00185 if (device_->hasImageStream())
00186 {
00187 image_transport::SubscriberStatusCallback itssc = boost::bind(&DriverNodelet::rgbConnectCb, this);
00188 ros::SubscriberStatusCallback rssc = boost::bind(&DriverNodelet::rgbConnectCb, this);
00189 pub_rgb_ = rgb_it.advertiseCamera("image_raw", 1, itssc, itssc, rssc, rssc);
00190 if (enable_rgb_diagnostics_) {
00191 pub_rgb_freq_.reset(new TopicDiagnostic("RGB Image", *diagnostic_updater_,
00192 FrequencyStatusParam(&pub_freq_min_, &pub_freq_max_,
00193 diagnostics_tolerance, diagnostics_window_time)));
00194 }
00195 }
00196
00197 if (device_->hasIRStream())
00198 {
00199 image_transport::SubscriberStatusCallback itssc = boost::bind(&DriverNodelet::irConnectCb, this);
00200 ros::SubscriberStatusCallback rssc = boost::bind(&DriverNodelet::irConnectCb, this);
00201 pub_ir_ = ir_it.advertiseCamera("image_raw", 1, itssc, itssc, rssc, rssc);
00202 if (enable_ir_diagnostics_) {
00203 pub_ir_freq_.reset(new TopicDiagnostic("IR Image", *diagnostic_updater_,
00204 FrequencyStatusParam(&pub_freq_min_, &pub_freq_max_,
00205 diagnostics_tolerance, diagnostics_window_time)));
00206 }
00207 }
00208
00209 if (device_->hasDepthStream())
00210 {
00211 image_transport::SubscriberStatusCallback itssc = boost::bind(&DriverNodelet::depthConnectCb, this);
00212 ros::SubscriberStatusCallback rssc = boost::bind(&DriverNodelet::depthConnectCb, this);
00213 pub_depth_ = depth_it.advertiseCamera("image_raw", 1, itssc, itssc, rssc, rssc);
00214 if (enable_depth_diagnostics_) {
00215 pub_depth_freq_.reset(new TopicDiagnostic("Depth Image", *diagnostic_updater_,
00216 FrequencyStatusParam(&pub_freq_min_, &pub_freq_max_,
00217 diagnostics_tolerance, diagnostics_window_time)));
00218 }
00219
00220 pub_projector_info_ = projector_nh.advertise<sensor_msgs::CameraInfo>("camera_info", 1, rssc, rssc);
00221
00222 if (device_->isDepthRegistrationSupported()) {
00223 pub_depth_registered_ = depth_registered_it.advertiseCamera("image_raw", 1, itssc, itssc, rssc, rssc);
00224 }
00225 }
00226 }
00227
00228
00229 close_diagnostics_ = false;
00230 diagnostics_thread_ = boost::thread(boost::bind(&DriverNodelet::updateDiagnostics, this));
00231
00232
00233 param_nh.param<double>("time_out", time_out_, 5.0);
00234 if (time_out_ > 0.0)
00235 {
00236 watch_dog_timer_ = nh.createTimer(ros::Duration(time_out_), &DriverNodelet::watchDog, this);
00237 }
00238
00239 device_->publishersAreReady();
00240 }
00241
00242 void DriverNodelet::updateDiagnostics() {
00243 while (!close_diagnostics_) {
00244 diagnostic_updater_->update();
00245 boost::this_thread::sleep(boost::posix_time::milliseconds(10));
00246 }
00247 }
00248
00249 void DriverNodelet::setupDevice ()
00250 {
00251
00252 FreenectDriver& driver = FreenectDriver::getInstance();
00253
00254
00255 if (libfreenect_debug_)
00256 driver.enableDebug();
00257
00258 do {
00259 driver.updateDeviceList ();
00260
00261 if (driver.getNumberDevices () == 0)
00262 {
00263 NODELET_INFO ("No devices connected.... waiting for devices to be connected");
00264 boost::this_thread::sleep(boost::posix_time::seconds(3));
00265 continue;
00266 }
00267
00268 NODELET_INFO ("Number devices connected: %d", driver.getNumberDevices ());
00269 for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00270 {
00271 NODELET_INFO("%u. device on bus %03u:%02u is a %s (%03x) from %s (%03x) with serial id \'%s\'",
00272 deviceIdx + 1, driver.getBus(deviceIdx), driver.getAddress(deviceIdx),
00273 driver.getProductName(deviceIdx), driver.getProductID(deviceIdx),
00274 driver.getVendorName(deviceIdx), driver.getVendorID(deviceIdx),
00275 driver.getSerialNumber(deviceIdx));
00276 }
00277
00278 try {
00279 string device_id;
00280 if (!getPrivateNodeHandle().getParam("device_id", device_id))
00281 {
00282 NODELET_WARN ("~device_id is not set! Using first device.");
00283 device_ = driver.getDeviceByIndex(0);
00284 }
00285 else if (device_id.find ('@') != string::npos)
00286 {
00287 size_t pos = device_id.find ('@');
00288 unsigned bus = atoi (device_id.substr (0, pos).c_str ());
00289 unsigned address = atoi (device_id.substr (pos + 1, device_id.length () - pos - 1).c_str ());
00290 NODELET_INFO ("Searching for device with bus@address = %d@%d", bus, address);
00291 device_ = driver.getDeviceByAddress (bus, address);
00292 }
00293 else if (device_id[0] == '#')
00294 {
00295 unsigned index = atoi (device_id.c_str() + 1);
00296 NODELET_INFO ("Searching for device with index = %d", index);
00297 device_ = driver.getDeviceByIndex (index - 1);
00298 }
00299 else
00300 {
00301 NODELET_INFO ("Searching for device with serial number = '%s'", device_id.c_str ());
00302 device_ = driver.getDeviceBySerialNumber (device_id);
00303 }
00304 }
00305 catch (exception& e)
00306 {
00307 if (!device_)
00308 {
00309 NODELET_INFO ("No matching device found.... waiting for devices. Reason: %s", e.what ());
00310 boost::this_thread::sleep(boost::posix_time::seconds(3));
00311 continue;
00312 }
00313 else
00314 {
00315 NODELET_FATAL ("Could not retrieve device. Reason: %s", e.what ());
00316 exit (-1);
00317 }
00318 }
00319 } while (!device_);
00320
00321 NODELET_INFO ("Opened '%s' on bus %d:%d with serial number '%s'", device_->getProductName (),
00322 device_->getBus (), device_->getAddress (), device_->getSerialNumber ());
00323
00324 device_->registerImageCallback(&DriverNodelet::rgbCb, *this);
00325 device_->registerDepthCallback(&DriverNodelet::depthCb, *this);
00326 device_->registerIRCallback (&DriverNodelet::irCb, *this);
00327 }
00328
00329 void DriverNodelet::rgbConnectCb()
00330 {
00331
00332 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00333
00334 bool need_rgb = pub_rgb_.getNumSubscribers() > 0;
00335
00336
00337 if (need_rgb && !device_->isImageStreamRunning())
00338 {
00339
00340 if (device_->isIRStreamRunning())
00341 {
00342 NODELET_ERROR("Cannot stream RGB and IR at the same time. Streaming RGB only.");
00343 device_->stopIRStream();
00344 }
00345
00346 device_->startImageStream();
00347 startSynchronization();
00348 rgb_time_stamp_ = ros::Time::now();
00349 }
00350 else if (!need_rgb && device_->isImageStreamRunning())
00351 {
00352 stopSynchronization();
00353 device_->stopImageStream();
00354
00355
00356 bool need_ir = pub_ir_.getNumSubscribers() > 0;
00357 if (need_ir && !device_->isIRStreamRunning())
00358 {
00359 device_->startIRStream();
00360 ir_time_stamp_ = ros::Time::now();
00361 }
00362 }
00363
00364 }
00365
00366 void DriverNodelet::depthConnectCb()
00367 {
00368
00369 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00370
00372 bool need_depth =
00373 device_->isDepthRegistered() ? pub_depth_registered_.getNumSubscribers() > 0 : pub_depth_.getNumSubscribers() > 0;
00375
00376
00377 if (need_depth && !device_->isDepthStreamRunning())
00378 {
00379 device_->startDepthStream();
00380 startSynchronization();
00381 depth_time_stamp_ = ros::Time::now();
00382
00383 }
00384 else if (!need_depth && device_->isDepthStreamRunning())
00385 {
00386 stopSynchronization();
00387 device_->stopDepthStream();
00388 }
00389
00390 }
00391
00392 void DriverNodelet::irConnectCb()
00393 {
00394 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00395 bool need_ir = pub_ir_.getNumSubscribers() > 0;
00396
00397 if (need_ir && !device_->isIRStreamRunning())
00398 {
00399
00400 if (device_->isImageStreamRunning())
00401 {
00402 NODELET_ERROR("Cannot stream RGB and IR at the same time. Streaming RGB only.");
00403 }
00404 else
00405 {
00406 device_->startIRStream();
00407 ir_time_stamp_ = ros::Time::now();
00408 }
00409 }
00410 else if (!need_ir)
00411 {
00412 device_->stopIRStream();
00413 }
00414 }
00415
00416
00417
00418
00419 void DriverNodelet::checkFrameCounters()
00420 {
00421 if (max(rgb_frame_counter_, max(depth_frame_counter_, ir_frame_counter_)) > config_.data_skip) {
00422
00423 rgb_frame_counter_ = 0;
00424 depth_frame_counter_ = 0;
00425 ir_frame_counter_ = 0;
00426
00427
00428 publish_rgb_ = true;
00429 publish_depth_ = true;
00430 publish_ir_ = true;
00431 }
00432 }
00433
00434 void DriverNodelet::rgbCb(const ImageBuffer& image, void* cookie)
00435 {
00436 ros::Time time = ros::Time::now () + ros::Duration(config_.image_time_offset);
00437 rgb_time_stamp_ = time;
00438
00439 bool publish = false;
00440 {
00441 boost::unique_lock<boost::mutex> counter_lock(counter_mutex_);
00442 rgb_frame_counter_++;
00443 checkFrameCounters();
00444 publish = publish_rgb_;
00445
00446 if (publish)
00447 rgb_frame_counter_ = 0;
00448 }
00449
00450 if (publish)
00451 publishRgbImage(image, time);
00452
00453 publish_rgb_ = false;
00454 }
00455
00456 void DriverNodelet::depthCb(const ImageBuffer& depth_image, void* cookie)
00457 {
00458 ros::Time time = ros::Time::now () + ros::Duration(config_.depth_time_offset);
00459 depth_time_stamp_ = time;
00460
00461 bool publish = false;
00462 {
00463 boost::unique_lock<boost::mutex> counter_lock(counter_mutex_);
00464 depth_frame_counter_++;
00465 checkFrameCounters();
00466 publish = publish_depth_;
00467
00468 if (publish)
00469 depth_frame_counter_ = 0;
00470 }
00471
00472 if (publish)
00473 publishDepthImage(depth_image, time);
00474
00475 publish_depth_ = false;
00476 }
00477
00478 void DriverNodelet::irCb(const ImageBuffer& ir_image, void* cookie)
00479 {
00480 ros::Time time = ros::Time::now() + ros::Duration(config_.depth_time_offset);
00481 ir_time_stamp_ = time;
00482
00483 bool publish = false;
00484 {
00485 boost::unique_lock<boost::mutex> counter_lock(counter_mutex_);
00486 ir_frame_counter_++;
00487 checkFrameCounters();
00488 publish = publish_ir_;
00489
00490 if (publish)
00491 ir_frame_counter_ = 0;
00492 }
00493
00494 if (publish)
00495 publishIrImage(ir_image, time);
00496 publish_ir_ = false;
00497 }
00498
00499 void DriverNodelet::publishRgbImage(const ImageBuffer& image, ros::Time time) const
00500 {
00501
00502 sensor_msgs::ImagePtr rgb_msg = boost::make_shared<sensor_msgs::Image >();
00503 rgb_msg->header.stamp = time;
00504 rgb_msg->header.frame_id = rgb_frame_id_;
00505 rgb_msg->height = image.metadata.height;
00506 rgb_msg->width = image.metadata.width;
00507 switch(image.metadata.video_format) {
00508 case FREENECT_VIDEO_RGB:
00509 rgb_msg->encoding = sensor_msgs::image_encodings::RGB8;
00510 rgb_msg->step = rgb_msg->width * 3;
00511 break;
00512 case FREENECT_VIDEO_BAYER:
00513 rgb_msg->encoding = sensor_msgs::image_encodings::BAYER_GRBG8;
00514 rgb_msg->step = rgb_msg->width;
00515 break;
00516 case FREENECT_VIDEO_YUV_RGB:
00517 rgb_msg->encoding = sensor_msgs::image_encodings::YUV422;
00518 rgb_msg->step = rgb_msg->width * 2;
00519 break;
00520 default:
00521 NODELET_ERROR("Unknown RGB image format received from libfreenect");
00522
00523 return;
00524 }
00525 rgb_msg->data.resize(rgb_msg->height * rgb_msg->step);
00526 fillImage(image, reinterpret_cast<void*>(&rgb_msg->data[0]));
00527
00528 pub_rgb_.publish(rgb_msg, getRgbCameraInfo(image, time));
00529 if (enable_rgb_diagnostics_)
00530 pub_rgb_freq_->tick();
00531 }
00532
00533 void DriverNodelet::publishDepthImage(const ImageBuffer& depth, ros::Time time) const
00534 {
00535
00536 bool registered = depth.is_registered;
00537
00538 sensor_msgs::ImagePtr depth_msg = boost::make_shared<sensor_msgs::Image>();
00539 depth_msg->header.stamp = time;
00540 depth_msg->encoding = sensor_msgs::image_encodings::TYPE_16UC1;
00541 depth_msg->height = depth.metadata.height;
00542 depth_msg->width = depth.metadata.width;
00543 depth_msg->step = depth_msg->width * sizeof(short);
00544 depth_msg->data.resize(depth_msg->height * depth_msg->step);
00545
00546 fillImage(depth, reinterpret_cast<void*>(&depth_msg->data[0]));
00547
00548 if (z_offset_mm_ != 0)
00549 {
00550 uint16_t* data = reinterpret_cast<uint16_t*>(&depth_msg->data[0]);
00551 for (unsigned int i = 0; i < depth_msg->width * depth_msg->height; ++i)
00552 if (data[i] != 0)
00553 data[i] += z_offset_mm_;
00554 }
00555
00556 if (registered)
00557 {
00558
00559 depth_msg->header.frame_id = rgb_frame_id_;
00560 pub_depth_registered_.publish(depth_msg, getRgbCameraInfo(depth, time));
00561 }
00562 else
00563 {
00564
00565 depth_msg->header.frame_id = depth_frame_id_;
00566 pub_depth_.publish(depth_msg, getDepthCameraInfo(depth, time));
00567 }
00568 if (enable_depth_diagnostics_)
00569 pub_depth_freq_->tick();
00570
00571
00572 if (pub_projector_info_.getNumSubscribers() > 0)
00573 {
00574 pub_projector_info_.publish(getProjectorCameraInfo(depth, time));
00575 }
00576 }
00577
00578 void DriverNodelet::publishIrImage(const ImageBuffer& ir, ros::Time time) const
00579 {
00580 sensor_msgs::ImagePtr ir_msg = boost::make_shared<sensor_msgs::Image>();
00581 ir_msg->header.stamp = time;
00582 ir_msg->header.frame_id = depth_frame_id_;
00583 ir_msg->encoding = sensor_msgs::image_encodings::MONO16;
00584 ir_msg->height = ir.metadata.height;
00585 ir_msg->width = ir.metadata.width;
00586 ir_msg->step = ir_msg->width * sizeof(uint16_t);
00587 ir_msg->data.resize(ir_msg->height * ir_msg->step);
00588
00589 fillImage(ir, reinterpret_cast<void*>(&ir_msg->data[0]));
00590
00591 pub_ir_.publish(ir_msg, getIrCameraInfo(ir, time));
00592
00593 if (enable_ir_diagnostics_)
00594 pub_ir_freq_->tick();
00595 }
00596
00597 sensor_msgs::CameraInfoPtr DriverNodelet::getDefaultCameraInfo(int width, int height, double f) const
00598 {
00599 sensor_msgs::CameraInfoPtr info = boost::make_shared<sensor_msgs::CameraInfo>();
00600
00601 info->width = width;
00602 info->height = height;
00603
00604
00605 info->D.resize(5, 0.0);
00606 info->distortion_model = sensor_msgs::distortion_models::PLUMB_BOB;
00607
00608
00609 info->K.assign(0.0);
00610 info->K[0] = info->K[4] = f;
00611 info->K[2] = (width / 2) - 0.5;
00612
00613
00614 info->K[5] = (width * (3./8.)) - 0.5;
00615 info->K[8] = 1.0;
00616
00617
00618 info->R.assign(0.0);
00619 info->R[0] = info->R[4] = info->R[8] = 1.0;
00620
00621
00622 info->P.assign(0.0);
00623 info->P[0] = info->P[5] = f;
00624 info->P[2] = info->K[2];
00625 info->P[6] = info->K[5];
00626 info->P[10] = 1.0;
00627
00628 return info;
00629 }
00630
00632 sensor_msgs::CameraInfoPtr DriverNodelet::getRgbCameraInfo(const ImageBuffer& image, ros::Time time) const
00633 {
00634 sensor_msgs::CameraInfoPtr info;
00635
00636 if (rgb_info_manager_->isCalibrated())
00637 {
00638 info = boost::make_shared<sensor_msgs::CameraInfo>(rgb_info_manager_->getCameraInfo());
00639 }
00640 else
00641 {
00642
00643 info = getDefaultCameraInfo(image.metadata.width, image.metadata.height, image.focal_length);
00644 }
00645
00646
00647 info->header.stamp = time;
00648 info->header.frame_id = rgb_frame_id_;
00649
00650 return info;
00651 }
00652
00653 sensor_msgs::CameraInfoPtr DriverNodelet::getIrCameraInfo(
00654 const ImageBuffer& image, ros::Time time) const {
00655 sensor_msgs::CameraInfoPtr info;
00656
00657 if (ir_info_manager_->isCalibrated())
00658 {
00659 info = boost::make_shared<sensor_msgs::CameraInfo>(ir_info_manager_->getCameraInfo());
00660 }
00661 else
00662 {
00663
00664 info = getDefaultCameraInfo(image.metadata.width, image.metadata.height, image.focal_length);
00665 }
00666
00667
00668 info->header.stamp = time;
00669 info->header.frame_id = depth_frame_id_;
00670
00671 return info;
00672 }
00673
00674 sensor_msgs::CameraInfoPtr DriverNodelet::getDepthCameraInfo(
00675 const ImageBuffer& image, ros::Time time) const {
00676
00677
00678
00679
00680 sensor_msgs::CameraInfoPtr info = getIrCameraInfo(image, time);
00681 info->K[2] -= depth_ir_offset_x_;
00682 info->K[5] -= depth_ir_offset_y_;
00683 info->P[2] -= depth_ir_offset_x_;
00684 info->P[6] -= depth_ir_offset_y_;
00685
00687 return info;
00688 }
00689
00690 sensor_msgs::CameraInfoPtr DriverNodelet::getProjectorCameraInfo(
00691 const ImageBuffer& image, ros::Time time) const {
00692
00693
00694
00695 sensor_msgs::CameraInfoPtr info = getDepthCameraInfo(image, time);
00696
00697 info->P[3] = -device_->getBaseline() * info->P[0];
00698 return info;
00699 }
00700
00701 void DriverNodelet::configCb(Config &config, uint32_t level)
00702 {
00703 depth_ir_offset_x_ = config.depth_ir_offset_x;
00704 depth_ir_offset_y_ = config.depth_ir_offset_y;
00705 z_offset_mm_ = config.z_offset_mm;
00706
00707
00708 OutputMode old_image_mode, image_mode, compatible_image_mode;
00709 if (device_->hasImageStream ())
00710 {
00711 old_image_mode = device_->getImageOutputMode ();
00712
00713
00714 image_mode = mapConfigMode2OutputMode (config.image_mode);
00715
00716 if (!device_->findCompatibleImageMode (image_mode, compatible_image_mode))
00717 {
00718 OutputMode default_mode = device_->getDefaultImageMode();
00719 NODELET_WARN("Could not find any compatible image output mode for %d. "
00720 "Falling back to default image output mode %d.",
00721 image_mode,
00722 default_mode);
00723
00724 config.image_mode = mapMode2ConfigMode(default_mode);
00725 image_mode = compatible_image_mode = default_mode;
00726 }
00727 }
00728
00729 OutputMode old_depth_mode, depth_mode, compatible_depth_mode;
00730 old_depth_mode = device_->getDepthOutputMode();
00731 depth_mode = mapConfigMode2OutputMode (config.depth_mode);
00732 if (!device_->findCompatibleDepthMode (depth_mode, compatible_depth_mode))
00733 {
00734 OutputMode default_mode = device_->getDefaultDepthMode();
00735 NODELET_WARN("Could not find any compatible depth output mode for %d. "
00736 "Falling back to default depth output mode %d.",
00737 depth_mode,
00738 default_mode);
00739
00740 config.depth_mode = mapMode2ConfigMode(default_mode);
00741 depth_mode = compatible_depth_mode = default_mode;
00742 }
00743
00744
00745 if ( (device_->hasImageStream () && compatible_image_mode != old_image_mode) ||
00746 compatible_depth_mode != old_depth_mode)
00747 {
00748
00749 stopSynchronization();
00750
00751 if (device_->hasImageStream () && compatible_image_mode != old_image_mode)
00752 device_->setImageOutputMode (compatible_image_mode);
00753
00754 if (compatible_depth_mode != old_depth_mode)
00755 device_->setDepthOutputMode (compatible_depth_mode);
00756
00757 startSynchronization ();
00758 }
00759
00760
00761 if (device_->isDepthRegistered () && !config.depth_registration)
00762 {
00763 device_->setDepthRegistration (false);
00764 }
00765 else if (!device_->isDepthRegistered () && config.depth_registration)
00766 {
00767 device_->setDepthRegistration (true);
00768 }
00769
00770
00771 config_ = config;
00772 }
00773
00774 void DriverNodelet::startSynchronization()
00775 {
00776 if (device_->isSynchronizationSupported() &&
00777 !device_->isSynchronized() &&
00778 device_->isImageStreamRunning() &&
00779 device_->isDepthStreamRunning() )
00780 {
00781 device_->setSynchronization(true);
00782 }
00783 }
00784
00785 void DriverNodelet::stopSynchronization()
00786 {
00787 if (device_->isSynchronizationSupported() &&
00788 device_->isSynchronized())
00789 {
00790 device_->setSynchronization(false);
00791 }
00792 }
00793
00794 void DriverNodelet::updateModeMaps ()
00795 {
00796 OutputMode output_mode;
00797
00798 output_mode = FREENECT_RESOLUTION_HIGH;
00799 mode2config_map_[output_mode] = Freenect_SXGA;
00800 config2mode_map_[Freenect_SXGA] = output_mode;
00801
00802 output_mode = FREENECT_RESOLUTION_MEDIUM;
00803 mode2config_map_[output_mode] = Freenect_VGA;
00804 config2mode_map_[Freenect_VGA] = output_mode;
00805 }
00806
00807 int DriverNodelet::mapMode2ConfigMode (const OutputMode& output_mode) const
00808 {
00809 std::map<OutputMode, int>::const_iterator it = mode2config_map_.find (output_mode);
00810
00811 if (it == mode2config_map_.end ())
00812 {
00813 NODELET_ERROR ("mode not be found");
00814 exit (-1);
00815 }
00816 else
00817 return it->second;
00818 }
00819
00820 OutputMode DriverNodelet::mapConfigMode2OutputMode (int mode) const
00821 {
00822 std::map<int, OutputMode>::const_iterator it = config2mode_map_.find (mode);
00823 if (it == config2mode_map_.end ())
00824 {
00825 NODELET_ERROR ("mode %d could not be found", mode);
00826 exit (-1);
00827 }
00828 else
00829 return it->second;
00830 }
00831
00832 void DriverNodelet::watchDog (const ros::TimerEvent& event)
00833 {
00834 bool timed_out = false;
00835 if (!rgb_time_stamp_.isZero() && device_->isImageStreamRunning()) {
00836 ros::Duration duration = ros::Time::now() - rgb_time_stamp_;
00837 timed_out = timed_out || duration.toSec() > time_out_;
00838 }
00839 if (!depth_time_stamp_.isZero() && device_->isDepthStreamRunning()) {
00840 ros::Duration duration = ros::Time::now() - depth_time_stamp_;
00841 timed_out = timed_out || duration.toSec() > time_out_;
00842 }
00843 if (!ir_time_stamp_.isZero() && device_->isIRStreamRunning()) {
00844 ros::Duration duration = ros::Time::now() - ir_time_stamp_;
00845 timed_out = timed_out || duration.toSec() > time_out_;
00846 }
00847
00848 if (timed_out) {
00849 ROS_INFO("Device timed out. Flushing device.");
00850 device_->flushDeviceStreams();
00851 }
00852
00853 }
00854
00855 }
00856
00857
00858 #include <pluginlib/class_list_macros.h>
00859 PLUGINLIB_DECLARE_CLASS (freenect_camera, driver, freenect_camera::DriverNodelet, nodelet::Nodelet);