$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2011 Willow Garage, Inc. 00005 * Suat Gedikli <gedikli@willowgarage.com> 00006 * Patrick Michelich <michelich@willowgarage.com> 00007 * Radu Bogdan Rusu <rusu@willowgarage.com> 00008 * 00009 * All rights reserved. 00010 * 00011 * Redistribution and use in source and binary forms, with or without 00012 * modification, are permitted provided that the following conditions 00013 * are met: 00014 * 00015 * * Redistributions of source code must retain the above copyright 00016 * notice, this list of conditions and the following disclaimer. 00017 * * Redistributions in binary form must reproduce the above 00018 * copyright notice, this list of conditions and the following 00019 * disclaimer in the documentation and/or other materials provided 00020 * with the distribution. 00021 * * Neither the name of Willow Garage, Inc. nor the names of its 00022 * contributors may be used to endorse or promote products derived 00023 * from this software without specific prior written permission. 00024 * 00025 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00026 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00027 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00028 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00029 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00030 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00031 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00032 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00033 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00034 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00035 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00036 * POSSIBILITY OF SUCH DAMAGE. 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 <sensor_msgs/image_encodings.h> 00045 #include <sensor_msgs/distortion_models.h> 00046 #include <boost/algorithm/string/replace.hpp> 00047 00048 using namespace std; 00049 using namespace openni_wrapper; 00050 namespace openni_camera 00051 { 00052 inline bool operator == (const XnMapOutputMode& mode1, const XnMapOutputMode& mode2) 00053 { 00054 return (mode1.nXRes == mode2.nXRes && mode1.nYRes == mode2.nYRes && mode1.nFPS == mode2.nFPS); 00055 } 00056 inline bool operator != (const XnMapOutputMode& mode1, const XnMapOutputMode& mode2) 00057 { 00058 return !(mode1 == mode2); 00059 } 00060 00061 DriverNodelet::~DriverNodelet () 00062 { 00063 // If we're still stuck in initialization (e.g. can't connect to device), break out 00064 init_thread_.interrupt(); 00065 init_thread_.join(); 00066 00067 // Join OpenNI wrapper threads, which call into rgbCb() etc. Those may use device_ methods, 00068 // so make sure they've finished before destroying device_. 00069 if (device_) 00070 device_->shutdown(); 00071 00074 } 00075 00076 void DriverNodelet::onInit () 00077 { 00078 // Setting up device can take awhile but onInit shouldn't block, so we spawn a 00079 // new thread to do all the initialization 00080 init_thread_ = boost::thread(boost::bind(&DriverNodelet::onInitImpl, this)); 00081 } 00082 00083 void DriverNodelet::onInitImpl () 00084 { 00085 ros::NodeHandle& nh = getNodeHandle(); // topics 00086 ros::NodeHandle& param_nh = getPrivateNodeHandle(); // parameters 00087 00088 // Allow remapping namespaces rgb, ir, depth, depth_registered 00089 image_transport::ImageTransport it(nh); 00090 ros::NodeHandle rgb_nh(nh, "rgb"); 00091 image_transport::ImageTransport rgb_it(rgb_nh); 00092 ros::NodeHandle ir_nh(nh, "ir"); 00093 image_transport::ImageTransport ir_it(ir_nh); 00094 ros::NodeHandle depth_nh(nh, "depth"); 00095 image_transport::ImageTransport depth_it(depth_nh); 00096 ros::NodeHandle depth_registered_nh(nh, "depth_registered"); 00097 image_transport::ImageTransport depth_registered_it(depth_registered_nh); 00098 ros::NodeHandle projector_nh(nh, "projector"); 00099 00100 rgb_frame_counter_ = depth_frame_counter_ = ir_frame_counter_ = 0; 00101 publish_rgb_ = publish_ir_ = publish_depth_ = true; 00102 00103 // Initialize the sensor, but don't start any streams yet. That happens in the connection callbacks. 00104 updateModeMaps(); 00105 setupDevice(); 00106 00107 // Initialize dynamic reconfigure 00108 reconfigure_server_.reset( new ReconfigureServer(param_nh) ); 00109 reconfigure_server_->setCallback(boost::bind(&DriverNodelet::configCb, this, _1, _2)); 00110 00111 // Camera TF frames 00112 param_nh.param("rgb_frame_id", rgb_frame_id_, string("/openni_rgb_optical_frame")); 00113 param_nh.param("depth_frame_id", depth_frame_id_, string("/openni_depth_optical_frame")); 00114 NODELET_INFO("rgb_frame_id = '%s' ", rgb_frame_id_.c_str()); 00115 NODELET_INFO("depth_frame_id = '%s' ", depth_frame_id_.c_str()); 00116 00117 // Pixel offset between depth and IR images. 00118 // By default assume offset of (5,4) from 9x7 correlation window. 00119 // NOTE: These are now (temporarily?) dynamically reconfigurable, to allow tweaking. 00120 //param_nh.param("depth_ir_offset_x", depth_ir_offset_x_, 5.0); 00121 //param_nh.param("depth_ir_offset_y", depth_ir_offset_y_, 4.0); 00122 00123 // The camera names are set to [rgb|depth]_[serial#], e.g. depth_B00367707227042B. 00124 // camera_info_manager substitutes this for ${NAME} in the URL. 00125 std::string serial_number = device_->getSerialNumber(); 00126 std::string rgb_name, ir_name; 00127 if (serial_number.empty()) 00128 { 00129 rgb_name = "rgb"; 00130 ir_name = "depth"; 00131 } 00132 else 00133 { 00134 rgb_name = "rgb_" + serial_number; 00135 ir_name = "depth_" + serial_number; 00136 } 00137 00138 std::string rgb_info_url, ir_info_url; 00139 param_nh.param("rgb_camera_info_url", rgb_info_url, std::string()); 00140 param_nh.param("depth_camera_info_url", ir_info_url, std::string()); 00141 00142 // Suppress some of the output from loading camera calibrations (kinda hacky) 00143 log4cxx::LoggerPtr logger_ccp = log4cxx::Logger::getLogger("ros.camera_calibration_parsers"); 00144 log4cxx::LoggerPtr logger_cim = log4cxx::Logger::getLogger("ros.camera_info_manager"); 00145 logger_ccp->setLevel(log4cxx::Level::getFatal()); 00146 logger_cim->setLevel(log4cxx::Level::getWarn()); 00147 // Also suppress sync warnings from image_transport::CameraSubscriber. When subscribing to 00148 // depth_registered/foo with OpenNI registration disabled, the rectify nodelet for depth_registered/ 00149 // will complain because it receives depth_registered/camera_info (from the register nodelet), but 00150 // the driver is not publishing depth_registered/image_raw. 00151 log4cxx::LoggerPtr logger_its = log4cxx::Logger::getLogger("ros.image_transport.sync"); 00152 logger_its->setLevel(log4cxx::Level::getError()); 00153 ros::console::notifyLoggerLevelsChanged(); 00154 00155 // Load the saved calibrations, if they exist 00156 rgb_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(rgb_nh, rgb_name, rgb_info_url); 00157 ir_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(ir_nh, ir_name, ir_info_url); 00158 00159 if (!rgb_info_manager_->isCalibrated()) 00160 NODELET_WARN("Using default parameters for RGB camera calibration."); 00161 if (!ir_info_manager_->isCalibrated()) 00162 NODELET_WARN("Using default parameters for IR camera calibration."); 00163 00164 // Advertise all published topics 00165 { 00166 // Prevent connection callbacks from executing until we've set all the publishers. Otherwise 00167 // connectCb() can fire while we're advertising (say) "depth/image_raw", but before we actually 00168 // assign to pub_depth_. Then pub_depth_.getNumSubscribers() returns 0, and we fail to start 00169 // the depth generator. 00170 boost::lock_guard<boost::mutex> lock(connect_mutex_); 00171 00172 // Asus Xtion PRO does not have an RGB camera 00173 if (device_->hasImageStream()) 00174 { 00175 image_transport::SubscriberStatusCallback itssc = boost::bind(&DriverNodelet::rgbConnectCb, this); 00176 ros::SubscriberStatusCallback rssc = boost::bind(&DriverNodelet::rgbConnectCb, this); 00177 pub_rgb_ = rgb_it.advertiseCamera("image_raw", 1, itssc, itssc, rssc, rssc); 00178 } 00179 00180 if (device_->hasIRStream()) 00181 { 00182 image_transport::SubscriberStatusCallback itssc = boost::bind(&DriverNodelet::irConnectCb, this); 00183 ros::SubscriberStatusCallback rssc = boost::bind(&DriverNodelet::irConnectCb, this); 00184 pub_ir_ = ir_it.advertiseCamera("image_raw", 1, itssc, itssc, rssc, rssc); 00185 } 00186 00187 if (device_->hasDepthStream()) 00188 { 00189 image_transport::SubscriberStatusCallback itssc = boost::bind(&DriverNodelet::depthConnectCb, this); 00190 ros::SubscriberStatusCallback rssc = boost::bind(&DriverNodelet::depthConnectCb, this); 00191 pub_depth_ = depth_it.advertiseCamera("image_raw", 1, itssc, itssc, rssc, rssc); 00192 pub_projector_info_ = projector_nh.advertise<sensor_msgs::CameraInfo>("camera_info", 1, rssc, rssc); 00193 00194 if (device_->isDepthRegistrationSupported()) 00195 pub_depth_registered_ = depth_registered_it.advertiseCamera("image_raw", 1, itssc, itssc, rssc, rssc); 00196 } 00197 } 00198 00199 // Create watch dog timer callback 00200 if (param_nh.getParam("time_out", time_out_) && time_out_ > 0.0) 00201 { 00202 time_stamp_ = ros::Time(0,0); 00203 watch_dog_timer_ = nh.createTimer(ros::Duration(time_out_), &DriverNodelet::watchDog, this); 00204 } 00205 } 00206 00207 void DriverNodelet::setupDevice () 00208 { 00209 // Initialize the openni device 00210 OpenNIDriver& driver = OpenNIDriver::getInstance (); 00211 00212 do { 00213 driver.updateDeviceList (); 00214 00215 if (driver.getNumberDevices () == 0) 00216 { 00217 NODELET_INFO ("No devices connected.... waiting for devices to be connected"); 00218 boost::this_thread::sleep(boost::posix_time::seconds(3)); 00219 continue; 00220 } 00221 00222 NODELET_INFO ("Number devices connected: %d", driver.getNumberDevices ()); 00223 for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx) 00224 { 00225 NODELET_INFO("%u. device on bus %03u:%02u is a %s (%03x) from %s (%03x) with serial id \'%s\'", 00226 deviceIdx + 1, driver.getBus(deviceIdx), driver.getAddress(deviceIdx), 00227 driver.getProductName(deviceIdx), driver.getProductID(deviceIdx), 00228 driver.getVendorName(deviceIdx), driver.getVendorID(deviceIdx), 00229 driver.getSerialNumber(deviceIdx)); 00230 } 00231 00232 try { 00233 string device_id; 00234 if (!getPrivateNodeHandle().getParam("device_id", device_id)) 00235 { 00236 NODELET_WARN ("~device_id is not set! Using first device."); 00237 device_ = driver.getDeviceByIndex (0); 00238 } 00239 else if (device_id.find ('@') != string::npos) 00240 { 00241 size_t pos = device_id.find ('@'); 00242 unsigned bus = atoi (device_id.substr (0, pos).c_str ()); 00243 unsigned address = atoi (device_id.substr (pos + 1, device_id.length () - pos - 1).c_str ()); 00244 NODELET_INFO ("Searching for device with bus@address = %d@%d", bus, address); 00245 device_ = driver.getDeviceByAddress (bus, address); 00246 } 00247 else if (device_id[0] == '#') 00248 { 00249 unsigned index = atoi (device_id.c_str () + 1); 00250 NODELET_INFO ("Searching for device with index = %d", index); 00251 device_ = driver.getDeviceByIndex (index - 1); 00252 } 00253 else 00254 { 00255 NODELET_INFO ("Searching for device with serial number = '%s'", device_id.c_str ()); 00256 device_ = driver.getDeviceBySerialNumber (device_id); 00257 } 00258 } 00259 catch (const OpenNIException& exception) 00260 { 00261 if (!device_) 00262 { 00263 NODELET_INFO ("No matching device found.... waiting for devices. Reason: %s", exception.what ()); 00264 boost::this_thread::sleep(boost::posix_time::seconds(3)); 00265 continue; 00266 } 00267 else 00268 { 00269 NODELET_ERROR ("Could not retrieve device. Reason: %s", exception.what ()); 00270 exit (-1); 00271 } 00272 } 00273 } while (!device_); 00274 00275 NODELET_INFO ("Opened '%s' on bus %d:%d with serial number '%s'", device_->getProductName (), 00276 device_->getBus (), device_->getAddress (), device_->getSerialNumber ()); 00277 00278 device_->registerImageCallback(&DriverNodelet::rgbCb, *this); 00279 device_->registerDepthCallback(&DriverNodelet::depthCb, *this); 00280 device_->registerIRCallback (&DriverNodelet::irCb, *this); 00281 } 00282 00283 void DriverNodelet::rgbConnectCb() 00284 { 00285 boost::lock_guard<boost::mutex> lock(connect_mutex_); 00286 bool need_rgb = pub_rgb_.getNumSubscribers() > 0; 00287 00288 if (need_rgb && !device_->isImageStreamRunning()) 00289 { 00290 // Can't stream IR and RGB at the same time. Give RGB preference. 00291 if (device_->isIRStreamRunning()) 00292 { 00293 NODELET_ERROR("Cannot stream RGB and IR at the same time. Streaming RGB only."); 00294 device_->stopIRStream(); 00295 } 00296 00297 device_->startImageStream(); 00298 startSynchronization(); 00299 time_stamp_ = ros::Time(0,0); // starting an additional stream blocks for a while, could upset watchdog 00300 } 00301 else if (!need_rgb && device_->isImageStreamRunning()) 00302 { 00303 stopSynchronization(); 00304 device_->stopImageStream(); 00305 00306 // Start IR if it's been blocked on RGB subscribers 00307 bool need_ir = pub_ir_.getNumSubscribers() > 0; 00308 if (need_ir && !device_->isIRStreamRunning()) 00309 { 00310 device_->startIRStream(); 00311 time_stamp_ = ros::Time(0,0); 00312 } 00313 } 00314 } 00315 00316 void DriverNodelet::depthConnectCb() 00317 { 00318 boost::lock_guard<boost::mutex> lock(connect_mutex_); 00320 bool need_depth = 00321 device_->isDepthRegistered() ? pub_depth_registered_.getNumSubscribers() > 0 : pub_depth_.getNumSubscribers() > 0; 00323 00324 if (need_depth && !device_->isDepthStreamRunning()) 00325 { 00326 device_->startDepthStream(); 00327 startSynchronization(); 00328 time_stamp_ = ros::Time(0,0); // starting an additional stream blocks for a while, could upset watchdog 00329 } 00330 else if (!need_depth && device_->isDepthStreamRunning()) 00331 { 00332 stopSynchronization(); 00333 device_->stopDepthStream(); 00334 } 00335 } 00336 00337 void DriverNodelet::irConnectCb() 00338 { 00339 boost::lock_guard<boost::mutex> lock(connect_mutex_); 00340 bool need_ir = pub_ir_.getNumSubscribers() > 0; 00341 00342 if (need_ir && !device_->isIRStreamRunning()) 00343 { 00344 // Can't stream IR and RGB at the same time 00345 if (device_->isImageStreamRunning()) 00346 { 00347 NODELET_ERROR("Cannot stream RGB and IR at the same time. Streaming RGB only."); 00348 } 00349 else 00350 { 00351 device_->startIRStream(); 00352 time_stamp_ = ros::Time(0,0); // starting an additional stream blocks for a while, could upset watchdog 00353 } 00354 } 00355 else if (!need_ir) 00356 { 00357 device_->stopIRStream(); 00358 } 00359 } 00360 00361 // If any stream is ready, publish next available image from all streams 00362 // This publishes all available data with a maximum time offset of one frame between any two sources 00363 // Need to have lock to call this, since callbacks can be in different threads 00364 void DriverNodelet::checkFrameCounters() 00365 { 00366 if (max(rgb_frame_counter_, max(depth_frame_counter_, ir_frame_counter_)) > config_.data_skip) { 00367 // Reset all counters after we trigger publish 00368 rgb_frame_counter_ = 0; 00369 depth_frame_counter_ = 0; 00370 ir_frame_counter_ = 0; 00371 00372 // Trigger publish on all topics 00373 publish_rgb_ = true; 00374 publish_depth_ = true; 00375 publish_ir_ = true; 00376 } 00377 } 00378 00379 void DriverNodelet::rgbCb(boost::shared_ptr<openni_wrapper::Image> image, void* cookie) 00380 { 00381 ros::Time time = ros::Time::now () + ros::Duration(config_.image_time_offset); 00382 time_stamp_ = time; // for watchdog 00383 00384 bool publish = false; 00385 { 00386 boost::unique_lock<boost::mutex> counter_lock(counter_mutex_); 00387 rgb_frame_counter_++; 00388 checkFrameCounters(); 00389 publish = publish_rgb_; 00390 00391 if (publish) 00392 rgb_frame_counter_ = 0; // Reset counter if we publish this message to avoid under-throttling 00393 } 00394 00395 if (publish) 00396 publishRgbImage(*image, time); 00397 00398 publish_rgb_ = false; 00399 } 00400 00401 void DriverNodelet::depthCb(boost::shared_ptr<openni_wrapper::DepthImage> depth_image, void* cookie) 00402 { 00403 ros::Time time = ros::Time::now () + ros::Duration(config_.depth_time_offset); 00404 time_stamp_ = time; // for watchdog 00405 00406 bool publish = false; 00407 { 00408 boost::unique_lock<boost::mutex> counter_lock(counter_mutex_); 00409 depth_frame_counter_++; 00410 checkFrameCounters(); 00411 publish = publish_depth_; 00412 00413 if (publish) 00414 depth_frame_counter_ = 0; // Reset counter if we publish this message to avoid under-throttling 00415 } 00416 00417 if (publish) 00418 publishDepthImage(*depth_image, time); 00419 00420 publish_depth_ = false; 00421 } 00422 00423 void DriverNodelet::irCb(boost::shared_ptr<openni_wrapper::IRImage> ir_image, void* cookie) 00424 { 00425 ros::Time time = ros::Time::now() + ros::Duration(config_.depth_time_offset); 00426 time_stamp_ = time; // for watchdog 00427 00428 bool publish = false; 00429 { 00430 boost::unique_lock<boost::mutex> counter_lock(counter_mutex_); 00431 ir_frame_counter_++; 00432 checkFrameCounters(); 00433 publish = publish_ir_; 00434 00435 if (publish) 00436 ir_frame_counter_ = 0; // Reset counter if we publish this message to avoid under-throttling 00437 } 00438 00439 if (publish) 00440 publishIrImage(*ir_image, time); 00441 publish_ir_ = false; 00442 } 00443 00444 void DriverNodelet::publishRgbImage(const openni_wrapper::Image& image, ros::Time time) const 00445 { 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 if (image.getEncoding() == openni_wrapper::Image::BAYER_GRBG) 00451 { 00452 rgb_msg->encoding = sensor_msgs::image_encodings::BAYER_GRBG8; 00453 rgb_msg->step = image_width_; 00454 } 00455 else if (image.getEncoding() == openni_wrapper::Image::YUV422) 00456 { 00457 rgb_msg->encoding = sensor_msgs::image_encodings::YUV422; 00458 rgb_msg->step = image_width_ * 2; // 4 bytes for 2 pixels 00459 } 00460 rgb_msg->height = image_height_; 00461 rgb_msg->width = image_width_; 00462 rgb_msg->data.resize(rgb_msg->height * rgb_msg->step); 00463 00464 image.fillRaw(&rgb_msg->data[0]); 00465 00466 pub_rgb_.publish(rgb_msg, getRgbCameraInfo(time)); 00467 } 00468 00469 void DriverNodelet::publishDepthImage(const openni_wrapper::DepthImage& depth, ros::Time time) const 00470 { 00471 bool registered = device_->isDepthRegistered(); 00472 00474 sensor_msgs::ImagePtr depth_msg = boost::make_shared<sensor_msgs::Image>(); 00475 depth_msg->header.stamp = time; 00476 depth_msg->encoding = sensor_msgs::image_encodings::TYPE_16UC1; 00477 depth_msg->height = depth_height_; 00478 depth_msg->width = depth_width_; 00479 depth_msg->step = depth_msg->width * sizeof(short); 00480 depth_msg->data.resize(depth_msg->height * depth_msg->step); 00481 00482 depth.fillDepthImageRaw(depth_width_, depth_height_, reinterpret_cast<unsigned short*>(&depth_msg->data[0]), 00483 depth_msg->step); 00484 00485 if (z_offset_mm_ != 0) 00486 { 00487 uint16_t* data = reinterpret_cast<uint16_t*>(&depth_msg->data[0]); 00488 for (unsigned int i = 0; i < depth_msg->width * depth_msg->height; ++i) 00489 if (data[i] != 0) 00490 data[i] += z_offset_mm_; 00491 } 00492 00493 if (registered) 00494 { 00495 // Publish RGB camera info and raw depth image to depth_registered/ ns 00496 depth_msg->header.frame_id = rgb_frame_id_; 00497 pub_depth_registered_.publish(depth_msg, getRgbCameraInfo(time)); 00498 } 00499 else 00500 { 00501 // Publish depth camera info and raw depth image to depth/ ns 00502 depth_msg->header.frame_id = depth_frame_id_; 00503 pub_depth_.publish(depth_msg, getDepthCameraInfo(time)); 00504 } 00505 00506 // Projector "info" probably only useful for working with disparity images 00507 if (pub_projector_info_.getNumSubscribers() > 0) 00508 { 00509 pub_projector_info_.publish(getProjectorCameraInfo(time)); 00510 } 00511 } 00512 00513 void DriverNodelet::publishIrImage(const openni_wrapper::IRImage& ir, ros::Time time) const 00514 { 00515 sensor_msgs::ImagePtr ir_msg = boost::make_shared<sensor_msgs::Image>(); 00516 ir_msg->header.stamp = time; 00517 ir_msg->header.frame_id = depth_frame_id_; 00518 ir_msg->encoding = sensor_msgs::image_encodings::MONO16; 00519 ir_msg->height = ir.getHeight(); 00520 ir_msg->width = ir.getWidth(); 00521 ir_msg->step = ir_msg->width * sizeof(uint16_t); 00522 ir_msg->data.resize(ir_msg->height * ir_msg->step); 00523 00524 ir.fillRaw(ir.getWidth(), ir.getHeight(), reinterpret_cast<unsigned short*>(&ir_msg->data[0])); 00525 00526 pub_ir_.publish(ir_msg, getIrCameraInfo(time)); 00527 } 00528 00529 sensor_msgs::CameraInfoPtr DriverNodelet::getDefaultCameraInfo(int width, int height, double f) const 00530 { 00531 sensor_msgs::CameraInfoPtr info = boost::make_shared<sensor_msgs::CameraInfo>(); 00532 00533 info->width = width; 00534 info->height = height; 00535 00536 // No distortion 00537 info->D.resize(5, 0.0); 00538 info->distortion_model = sensor_msgs::distortion_models::PLUMB_BOB; 00539 00540 // Simple camera matrix: square pixels (fx = fy), principal point at center 00541 info->K.assign(0.0); 00542 info->K[0] = info->K[4] = f; 00543 info->K[2] = (width / 2) - 0.5; 00544 // Aspect ratio for the camera center on Kinect (and other devices?) is 4/3 00545 // This formula keeps the principal point the same in VGA and SXGA modes 00546 info->K[5] = (width * (3./8.)) - 0.5; 00547 info->K[8] = 1.0; 00548 00549 // No separate rectified image plane, so R = I 00550 info->R.assign(0.0); 00551 info->R[0] = info->R[4] = info->R[8] = 1.0; 00552 00553 // Then P=K(I|0) = (K|0) 00554 info->P.assign(0.0); 00555 info->P[0] = info->P[5] = f; // fx, fy 00556 info->P[2] = info->K[2]; // cx 00557 info->P[6] = info->K[5]; // cy 00558 info->P[10] = 1.0; 00559 00560 return info; 00561 } 00562 00564 sensor_msgs::CameraInfoPtr DriverNodelet::getRgbCameraInfo(ros::Time time) const 00565 { 00566 sensor_msgs::CameraInfoPtr info; 00567 00568 if (rgb_info_manager_->isCalibrated()) 00569 { 00570 info = boost::make_shared<sensor_msgs::CameraInfo>(rgb_info_manager_->getCameraInfo()); 00571 } 00572 else 00573 { 00574 // If uncalibrated, fill in default values 00575 info = getDefaultCameraInfo(image_width_, image_height_, device_->getImageFocalLength(image_width_)); 00576 } 00577 00578 // Fill in header 00579 info->header.stamp = time; 00580 info->header.frame_id = rgb_frame_id_; 00581 00582 return info; 00583 } 00584 00585 sensor_msgs::CameraInfoPtr DriverNodelet::getIrCameraInfo(ros::Time time) const 00586 { 00587 sensor_msgs::CameraInfoPtr info; 00588 00589 if (ir_info_manager_->isCalibrated()) 00590 { 00591 info = boost::make_shared<sensor_msgs::CameraInfo>(ir_info_manager_->getCameraInfo()); 00592 } 00593 else 00594 { 00595 // If uncalibrated, fill in default values 00596 info = getDefaultCameraInfo(depth_width_, depth_height_, device_->getDepthFocalLength(depth_width_)); 00597 } 00598 00599 // Fill in header 00600 info->header.stamp = time; 00601 info->header.frame_id = depth_frame_id_; 00602 00603 return info; 00604 } 00605 00606 sensor_msgs::CameraInfoPtr DriverNodelet::getDepthCameraInfo(ros::Time time) const 00607 { 00608 // The depth image has essentially the same intrinsics as the IR image, BUT the 00609 // principal point is offset by half the size of the hardware correlation window 00610 // (probably 9x9 or 9x7). See http://www.ros.org/wiki/kinect_calibration/technical 00611 00612 sensor_msgs::CameraInfoPtr info = getIrCameraInfo(time); 00613 info->K[2] -= depth_ir_offset_x_; // cx 00614 info->K[5] -= depth_ir_offset_y_; // cy 00615 info->P[2] -= depth_ir_offset_x_; // cx 00616 info->P[6] -= depth_ir_offset_y_; // cy 00617 00619 return info; 00620 } 00621 00622 sensor_msgs::CameraInfoPtr DriverNodelet::getProjectorCameraInfo(ros::Time time) const 00623 { 00624 // The projector info is simply the depth info with the baseline encoded in the P matrix. 00625 // It's only purpose is to be the "right" camera info to the depth camera's "left" for 00626 // processing disparity images. 00627 sensor_msgs::CameraInfoPtr info = getDepthCameraInfo(time); 00628 // Tx = -baseline * fx 00629 info->P[3] = -device_->getBaseline() * info->P[0]; 00630 return info; 00631 } 00632 00633 void DriverNodelet::configCb(Config &config, uint32_t level) 00634 { 00635 depth_ir_offset_x_ = config.depth_ir_offset_x; 00636 depth_ir_offset_y_ = config.depth_ir_offset_y; 00637 z_offset_mm_ = config.z_offset_mm; 00638 00639 XnMapOutputMode old_depth_mode = device_->getDepthOutputMode (); 00640 00641 // We need this for the ASUS Xtion Pro 00642 XnMapOutputMode old_image_mode = old_depth_mode, image_mode, compatible_image_mode; 00643 if (device_->hasImageStream ()) 00644 { 00645 old_image_mode = device_->getImageOutputMode (); 00646 00647 // does the device support the new image mode? 00648 image_mode = mapConfigMode2XnMode (config.image_mode); 00649 00650 if (!device_->findCompatibleImageMode (image_mode, compatible_image_mode)) 00651 { 00652 XnMapOutputMode default_mode = device_->getDefaultImageMode(); 00653 NODELET_WARN("Could not find any compatible image output mode for %d x %d @ %d. " 00654 "Falling back to default image output mode %d x %d @ %d.", 00655 image_mode.nXRes, image_mode.nYRes, image_mode.nFPS, 00656 default_mode.nXRes, default_mode.nYRes, default_mode.nFPS); 00657 00658 config.image_mode = mapXnMode2ConfigMode(default_mode); 00659 image_mode = compatible_image_mode = default_mode; 00660 } 00661 } 00662 00663 XnMapOutputMode depth_mode, compatible_depth_mode; 00664 depth_mode = mapConfigMode2XnMode (config.depth_mode); 00665 if (!device_->findCompatibleDepthMode (depth_mode, compatible_depth_mode)) 00666 { 00667 XnMapOutputMode default_mode = device_->getDefaultDepthMode(); 00668 NODELET_WARN ("Could not find any compatible depth output mode for %d x %d @ %d. " 00669 "Falling back to default depth output mode %d x %d @ %d.", 00670 depth_mode.nXRes, depth_mode.nYRes, depth_mode.nFPS, 00671 default_mode.nXRes, default_mode.nYRes, default_mode.nFPS); 00672 00673 config.depth_mode = mapXnMode2ConfigMode(default_mode); 00674 depth_mode = compatible_depth_mode = default_mode; 00675 } 00676 00677 // here everything is fine. Now make the changes 00678 if ( (device_->hasImageStream () && compatible_image_mode != old_image_mode) || 00679 compatible_depth_mode != old_depth_mode) 00680 { 00681 // streams need to be reset! 00682 stopSynchronization(); 00683 00684 if (device_->hasImageStream () && compatible_image_mode != old_image_mode) 00685 device_->setImageOutputMode (compatible_image_mode); 00686 00687 if (compatible_depth_mode != old_depth_mode) 00688 device_->setDepthOutputMode (compatible_depth_mode); 00689 00690 startSynchronization (); 00691 } 00692 00693 // Desired dimensions may require decimation from the hardware-compatible ones 00694 image_width_ = image_mode.nXRes; 00695 image_height_ = image_mode.nYRes; 00696 depth_width_ = depth_mode.nXRes; 00697 depth_height_ = depth_mode.nYRes; 00698 00700 if (device_->isDepthRegistered () && !config.depth_registration) 00701 { 00702 device_->setDepthRegistration (false); 00703 } 00704 else if (!device_->isDepthRegistered () && config.depth_registration) 00705 { 00706 device_->setDepthRegistration (true); 00707 } 00708 00709 // now we can copy 00710 config_ = config; 00711 } 00712 00713 void DriverNodelet::startSynchronization() 00714 { 00715 if (device_->isSynchronizationSupported() && 00716 !device_->isSynchronized() && 00717 device_->getImageOutputMode().nFPS == device_->getDepthOutputMode().nFPS && 00718 device_->isImageStreamRunning() && 00719 device_->isDepthStreamRunning() ) 00720 { 00721 device_->setSynchronization(true); 00722 } 00723 } 00724 00725 void DriverNodelet::stopSynchronization() 00726 { 00727 if (device_->isSynchronizationSupported() && 00728 device_->isSynchronized()) 00729 { 00730 device_->setSynchronization(false); 00731 } 00732 } 00733 00734 void DriverNodelet::updateModeMaps () 00735 { 00736 XnMapOutputMode output_mode; 00737 00738 output_mode.nXRes = XN_SXGA_X_RES; 00739 output_mode.nYRes = XN_SXGA_Y_RES; 00740 output_mode.nFPS = 15; 00741 xn2config_map_[output_mode] = OpenNIUnstable_SXGA_15Hz; 00742 config2xn_map_[OpenNIUnstable_SXGA_15Hz] = output_mode; 00743 00744 output_mode.nXRes = XN_VGA_X_RES; 00745 output_mode.nYRes = XN_VGA_Y_RES; 00746 output_mode.nFPS = 25; 00747 xn2config_map_[output_mode] = OpenNIUnstable_VGA_25Hz; 00748 config2xn_map_[OpenNIUnstable_VGA_25Hz] = output_mode; 00749 output_mode.nFPS = 30; 00750 xn2config_map_[output_mode] = OpenNIUnstable_VGA_30Hz; 00751 config2xn_map_[OpenNIUnstable_VGA_30Hz] = output_mode; 00752 00753 output_mode.nXRes = XN_QVGA_X_RES; 00754 output_mode.nYRes = XN_QVGA_Y_RES; 00755 output_mode.nFPS = 25; 00756 xn2config_map_[output_mode] = OpenNIUnstable_QVGA_25Hz; 00757 config2xn_map_[OpenNIUnstable_QVGA_25Hz] = output_mode; 00758 output_mode.nFPS = 30; 00759 xn2config_map_[output_mode] = OpenNIUnstable_QVGA_30Hz; 00760 config2xn_map_[OpenNIUnstable_QVGA_30Hz] = output_mode; 00761 output_mode.nFPS = 60; 00762 xn2config_map_[output_mode] = OpenNIUnstable_QVGA_60Hz; 00763 config2xn_map_[OpenNIUnstable_QVGA_60Hz] = output_mode; 00764 00765 output_mode.nXRes = XN_QQVGA_X_RES; 00766 output_mode.nYRes = XN_QQVGA_Y_RES; 00767 output_mode.nFPS = 25; 00768 xn2config_map_[output_mode] = OpenNIUnstable_QQVGA_25Hz; 00769 config2xn_map_[OpenNIUnstable_QQVGA_25Hz] = output_mode; 00770 output_mode.nFPS = 30; 00771 xn2config_map_[output_mode] = OpenNIUnstable_QQVGA_30Hz; 00772 config2xn_map_[OpenNIUnstable_QQVGA_30Hz] = output_mode; 00773 output_mode.nFPS = 60; 00774 xn2config_map_[output_mode] = OpenNIUnstable_QQVGA_60Hz; 00775 config2xn_map_[OpenNIUnstable_QQVGA_60Hz] = output_mode; 00776 } 00777 00778 int DriverNodelet::mapXnMode2ConfigMode (const XnMapOutputMode& output_mode) const 00779 { 00780 std::map<XnMapOutputMode, int, modeComp>::const_iterator it = xn2config_map_.find (output_mode); 00781 00782 if (it == xn2config_map_.end ()) 00783 { 00784 NODELET_ERROR ("mode %dx%d@%d could not be found", output_mode.nXRes, output_mode.nYRes, output_mode.nFPS); 00785 exit (-1); 00786 } 00787 else 00788 return it->second; 00789 } 00790 00791 XnMapOutputMode DriverNodelet::mapConfigMode2XnMode (int mode) const 00792 { 00793 std::map<int, XnMapOutputMode>::const_iterator it = config2xn_map_.find (mode); 00794 if (it == config2xn_map_.end ()) 00795 { 00796 NODELET_ERROR ("mode %d could not be found", mode); 00797 exit (-1); 00798 } 00799 else 00800 return it->second; 00801 } 00802 00803 void DriverNodelet::watchDog (const ros::TimerEvent& event) 00804 { 00806 if ( !time_stamp_.isZero() && (device_->isDepthStreamRunning() || device_->isImageStreamRunning()) ) 00807 { 00808 ros::Duration duration = ros::Time::now() - time_stamp_; 00809 if (duration.toSec() >= time_out_) 00810 { 00811 NODELET_ERROR("Timeout"); 00812 watch_dog_timer_.stop(); 00813 throw std::runtime_error("Timeout occured in DriverNodelet"); 00814 } 00815 } 00816 } 00817 00818 } 00819 00820 // Register as nodelet 00821 #include <pluginlib/class_list_macros.h> 00822 PLUGINLIB_DECLARE_CLASS (openni_camera, driver, openni_camera::DriverNodelet, nodelet::Nodelet);