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