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