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 #include "openni2_camera/openni2_driver.h"
00033 #include "openni2_camera/openni2_exception.h"
00034
00035 #include <sensor_msgs/image_encodings.h>
00036 #include <sensor_msgs/distortion_models.h>
00037
00038 #include <boost/date_time/posix_time/posix_time.hpp>
00039 #include <boost/thread/thread.hpp>
00040
00041 namespace openni2_wrapper
00042 {
00043
00044 OpenNI2Driver::OpenNI2Driver(ros::NodeHandle& n, ros::NodeHandle& pnh) :
00045 nh_(n),
00046 pnh_(pnh),
00047 device_manager_(OpenNI2DeviceManager::getSingelton()),
00048 config_init_(false),
00049 data_skip_ir_counter_(0),
00050 data_skip_color_counter_(0),
00051 data_skip_depth_counter_ (0),
00052 ir_subscribers_(false),
00053 color_subscribers_(false),
00054 depth_subscribers_(false),
00055 depth_raw_subscribers_(false)
00056 {
00057
00058 genVideoModeTableMap();
00059
00060 readConfigFromParameterServer();
00061
00062 initDevice();
00063
00064
00065 reconfigure_server_.reset(new ReconfigureServer(pnh_));
00066 reconfigure_server_->setCallback(boost::bind(&OpenNI2Driver::configCb, this, _1, _2));
00067
00068 while (!config_init_)
00069 {
00070 ROS_DEBUG("Waiting for dynamic reconfigure configuration.");
00071 boost::this_thread::sleep(boost::posix_time::milliseconds(100));
00072 }
00073 ROS_DEBUG("Dynamic reconfigure configuration received.");
00074
00075 advertiseROSTopics();
00076
00077 }
00078
00079 void OpenNI2Driver::advertiseROSTopics()
00080 {
00081
00082
00083 ros::NodeHandle color_nh(nh_, "rgb");
00084 image_transport::ImageTransport color_it(color_nh);
00085 ros::NodeHandle ir_nh(nh_, "ir");
00086 image_transport::ImageTransport ir_it(ir_nh);
00087 ros::NodeHandle depth_nh(nh_, "depth");
00088 image_transport::ImageTransport depth_it(depth_nh);
00089 ros::NodeHandle depth_raw_nh(nh_, "depth");
00090 image_transport::ImageTransport depth_raw_it(depth_raw_nh);
00091 ros::NodeHandle projector_nh(nh_, "projector");
00092
00093
00094
00095
00096
00097
00098 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00099
00100
00101 if (device_->hasColorSensor())
00102 {
00103 image_transport::SubscriberStatusCallback itssc = boost::bind(&OpenNI2Driver::colorConnectCb, this);
00104 ros::SubscriberStatusCallback rssc = boost::bind(&OpenNI2Driver::colorConnectCb, this);
00105 pub_color_ = color_it.advertiseCamera("image", 1, itssc, itssc, rssc, rssc);
00106 }
00107
00108 if (device_->hasIRSensor())
00109 {
00110 image_transport::SubscriberStatusCallback itssc = boost::bind(&OpenNI2Driver::irConnectCb, this);
00111 ros::SubscriberStatusCallback rssc = boost::bind(&OpenNI2Driver::irConnectCb, this);
00112 pub_ir_ = ir_it.advertiseCamera("image", 1, itssc, itssc, rssc, rssc);
00113 }
00114
00115 if (device_->hasDepthSensor())
00116 {
00117 image_transport::SubscriberStatusCallback itssc = boost::bind(&OpenNI2Driver::depthConnectCb, this);
00118 ros::SubscriberStatusCallback rssc = boost::bind(&OpenNI2Driver::depthConnectCb, this);
00119 pub_depth_raw_ = depth_it.advertiseCamera("image_raw", 1, itssc, itssc, rssc, rssc);
00120 pub_depth_ = depth_raw_it.advertiseCamera("image", 1, itssc, itssc, rssc, rssc);
00121 pub_projector_info_ = projector_nh.advertise<sensor_msgs::CameraInfo>("camera_info", 1, rssc, rssc);
00122 }
00123
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134 std::string serial_number = device_->getStringID();
00135 std::string color_name, ir_name;
00136
00137 color_name = "rgb_" + serial_number;
00138 ir_name = "depth_" + serial_number;
00139
00140
00141 color_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(color_nh, color_name, color_info_url_);
00142 ir_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(ir_nh, ir_name, ir_info_url_);
00143
00144 get_serial_server = nh_.advertiseService("get_serial", &OpenNI2Driver::getSerialCb,this);
00145
00146 }
00147
00148 bool OpenNI2Driver::getSerialCb(openni2_camera::GetSerialRequest& req, openni2_camera::GetSerialResponse& res) {
00149 res.serial = device_manager_->getSerial(device_->getUri());
00150 return true;
00151 }
00152
00153 void OpenNI2Driver::configCb(Config &config, uint32_t level)
00154 {
00155 bool stream_reset = false;
00156
00157 depth_ir_offset_x_ = config.depth_ir_offset_x;
00158 depth_ir_offset_y_ = config.depth_ir_offset_y;
00159 z_offset_mm_ = config.z_offset_mm;
00160 z_scaling_ = config.z_scaling;
00161
00162 ir_time_offset_ = ros::Duration(config.ir_time_offset);
00163 color_time_offset_ = ros::Duration(config.color_time_offset);
00164 depth_time_offset_ = ros::Duration(config.depth_time_offset);
00165
00166 if (lookupVideoModeFromDynConfig(config.ir_mode, ir_video_mode_)<0)
00167 {
00168 ROS_ERROR("Undefined IR video mode received from dynamic reconfigure");
00169 exit(-1);
00170 }
00171
00172 if (lookupVideoModeFromDynConfig(config.color_mode, color_video_mode_)<0)
00173 {
00174 ROS_ERROR("Undefined color video mode received from dynamic reconfigure");
00175 exit(-1);
00176 }
00177
00178 if (lookupVideoModeFromDynConfig(config.depth_mode, depth_video_mode_)<0)
00179 {
00180 ROS_ERROR("Undefined depth video mode received from dynamic reconfigure");
00181 exit(-1);
00182 }
00183
00184
00185
00186 ir_video_mode_.pixel_format_ = PIXEL_FORMAT_GRAY16;
00187 color_video_mode_.pixel_format_ = PIXEL_FORMAT_RGB888;
00188 depth_video_mode_.pixel_format_ = PIXEL_FORMAT_DEPTH_1_MM;
00189
00190 color_depth_synchronization_ = config.color_depth_synchronization;
00191 depth_registration_ = config.depth_registration;
00192
00193 auto_exposure_ = config.auto_exposure;
00194 auto_white_balance_ = config.auto_white_balance;
00195 exposure_ = config.exposure;
00196
00197 use_device_time_ = config.use_device_time;
00198
00199 data_skip_ = config.data_skip+1;
00200
00201 applyConfigToOpenNIDevice();
00202
00203 config_init_ = true;
00204
00205 old_config_ = config;
00206 }
00207
00208 void OpenNI2Driver::setIRVideoMode(const OpenNI2VideoMode& ir_video_mode)
00209 {
00210 if (device_->isIRVideoModeSupported(ir_video_mode))
00211 {
00212 if (ir_video_mode != device_->getIRVideoMode())
00213 {
00214 device_->setIRVideoMode(ir_video_mode);
00215 }
00216
00217 }
00218 else
00219 {
00220 ROS_ERROR_STREAM("Unsupported IR video mode - " << ir_video_mode);
00221 }
00222 }
00223 void OpenNI2Driver::setColorVideoMode(const OpenNI2VideoMode& color_video_mode)
00224 {
00225 if (device_->isColorVideoModeSupported(color_video_mode))
00226 {
00227 if (color_video_mode != device_->getColorVideoMode())
00228 {
00229 device_->setColorVideoMode(color_video_mode);
00230 }
00231 }
00232 else
00233 {
00234 ROS_ERROR_STREAM("Unsupported color video mode - " << color_video_mode);
00235 }
00236 }
00237 void OpenNI2Driver::setDepthVideoMode(const OpenNI2VideoMode& depth_video_mode)
00238 {
00239 if (device_->isDepthVideoModeSupported(depth_video_mode))
00240 {
00241 if (depth_video_mode != device_->getDepthVideoMode())
00242 {
00243 device_->setDepthVideoMode(depth_video_mode);
00244 }
00245 }
00246 else
00247 {
00248 ROS_ERROR_STREAM("Unsupported depth video mode - " << depth_video_mode);
00249 }
00250 }
00251
00252 void OpenNI2Driver::applyConfigToOpenNIDevice()
00253 {
00254
00255 data_skip_ir_counter_ = 0;
00256 data_skip_color_counter_= 0;
00257 data_skip_depth_counter_ = 0;
00258
00259 setIRVideoMode(ir_video_mode_);
00260 setColorVideoMode(color_video_mode_);
00261 setDepthVideoMode(depth_video_mode_);
00262
00263 if (device_->isImageRegistrationModeSupported())
00264 {
00265 try
00266 {
00267 if (!config_init_ || (old_config_.depth_registration != depth_registration_))
00268 device_->setImageRegistrationMode(depth_registration_);
00269 }
00270 catch (const OpenNI2Exception& exception)
00271 {
00272 ROS_ERROR("Could not set image registration. Reason: %s", exception.what());
00273 }
00274 }
00275
00276 try
00277 {
00278 if (!config_init_ || (old_config_.color_depth_synchronization != color_depth_synchronization_))
00279 device_->setDepthColorSync(color_depth_synchronization_);
00280 }
00281 catch (const OpenNI2Exception& exception)
00282 {
00283 ROS_ERROR("Could not set color depth synchronization. Reason: %s", exception.what());
00284 }
00285
00286 try
00287 {
00288 if (!config_init_ || (old_config_.auto_exposure != auto_exposure_))
00289 device_->setAutoExposure(auto_exposure_);
00290 }
00291 catch (const OpenNI2Exception& exception)
00292 {
00293 ROS_ERROR("Could not set auto exposure. Reason: %s", exception.what());
00294 }
00295
00296 try
00297 {
00298 if (!config_init_ || (old_config_.auto_white_balance != auto_white_balance_))
00299 device_->setAutoWhiteBalance(auto_white_balance_);
00300 }
00301 catch (const OpenNI2Exception& exception)
00302 {
00303 ROS_ERROR("Could not set auto white balance. Reason: %s", exception.what());
00304 }
00305
00306 try
00307 {
00308 if (!config_init_ || (old_config_.exposure != exposure_))
00309 device_->setExposure(exposure_);
00310 }
00311 catch (const OpenNI2Exception& exception)
00312 {
00313 ROS_ERROR("Could not set exposure. Reason: %s", exception.what());
00314 }
00315
00316 device_->setUseDeviceTimer(use_device_time_);
00317
00318 }
00319
00320 void OpenNI2Driver::colorConnectCb()
00321 {
00322 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00323
00324 color_subscribers_ = pub_color_.getNumSubscribers() > 0;
00325
00326 if (color_subscribers_ && !device_->isColorStreamStarted())
00327 {
00328
00329 if (device_->isIRStreamStarted())
00330 {
00331 ROS_ERROR("Cannot stream RGB and IR at the same time. Streaming RGB only.");
00332 ROS_INFO("Stopping IR stream.");
00333 device_->stopIRStream();
00334 }
00335
00336 device_->setColorFrameCallback(boost::bind(&OpenNI2Driver::newColorFrameCallback, this, _1));
00337
00338 ROS_INFO("Starting color stream.");
00339 device_->startColorStream();
00340
00341 }
00342 else if (!color_subscribers_ && device_->isColorStreamStarted())
00343 {
00344 ROS_INFO("Stopping color stream.");
00345 device_->stopColorStream();
00346
00347
00348 bool need_ir = pub_ir_.getNumSubscribers() > 0;
00349 if (need_ir && !device_->isIRStreamStarted())
00350 {
00351 device_->setIRFrameCallback(boost::bind(&OpenNI2Driver::newIRFrameCallback, this, _1));
00352
00353 ROS_INFO("Starting IR stream.");
00354 device_->startIRStream();
00355 }
00356 }
00357 }
00358
00359 void OpenNI2Driver::depthConnectCb()
00360 {
00361 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00362
00363 depth_subscribers_ = pub_depth_.getNumSubscribers() > 0;
00364 depth_raw_subscribers_ = pub_depth_raw_.getNumSubscribers() > 0;
00365 projector_info_subscribers_ = pub_projector_info_.getNumSubscribers() > 0;
00366
00367 bool need_depth = depth_subscribers_ || depth_raw_subscribers_;
00368
00369 if (need_depth && !device_->isDepthStreamStarted())
00370 {
00371 device_->setDepthFrameCallback(boost::bind(&OpenNI2Driver::newDepthFrameCallback, this, _1));
00372
00373 ROS_INFO("Starting depth stream.");
00374 device_->startDepthStream();
00375 }
00376 else if (!need_depth && device_->isDepthStreamStarted())
00377 {
00378 ROS_INFO("Stopping depth stream.");
00379 device_->stopDepthStream();
00380 }
00381 }
00382
00383 void OpenNI2Driver::irConnectCb()
00384 {
00385 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00386
00387 ir_subscribers_ = pub_ir_.getNumSubscribers() > 0;
00388
00389 if (ir_subscribers_ && !device_->isIRStreamStarted())
00390 {
00391
00392 if (device_->isColorStreamStarted())
00393 {
00394 ROS_ERROR("Cannot stream RGB and IR at the same time. Streaming RGB only.");
00395 }
00396 else
00397 {
00398 device_->setIRFrameCallback(boost::bind(&OpenNI2Driver::newIRFrameCallback, this, _1));
00399
00400 ROS_INFO("Starting IR stream.");
00401 device_->startIRStream();
00402 }
00403 }
00404 else if (!ir_subscribers_ && device_->isIRStreamStarted())
00405 {
00406 ROS_INFO("Stopping IR stream.");
00407 device_->stopIRStream();
00408 }
00409 }
00410
00411 void OpenNI2Driver::newIRFrameCallback(sensor_msgs::ImagePtr image)
00412 {
00413 if ((++data_skip_ir_counter_)%data_skip_==0)
00414 {
00415 data_skip_ir_counter_ = 0;
00416
00417 if (ir_subscribers_)
00418 {
00419 image->header.frame_id = ir_frame_id_;
00420 image->header.stamp = image->header.stamp + ir_time_offset_;
00421
00422 pub_ir_.publish(image, getIRCameraInfo(image->width, image->height, image->header.stamp));
00423 }
00424 }
00425 }
00426
00427 void OpenNI2Driver::newColorFrameCallback(sensor_msgs::ImagePtr image)
00428 {
00429 if ((++data_skip_color_counter_)%data_skip_==0)
00430 {
00431 data_skip_color_counter_ = 0;
00432
00433 if (color_subscribers_)
00434 {
00435 image->header.frame_id = color_frame_id_;
00436 image->header.stamp = image->header.stamp + color_time_offset_;
00437
00438 pub_color_.publish(image, getColorCameraInfo(image->width, image->height, image->header.stamp));
00439 }
00440 }
00441 }
00442
00443 void OpenNI2Driver::newDepthFrameCallback(sensor_msgs::ImagePtr image)
00444 {
00445 if ((++data_skip_depth_counter_)%data_skip_==0)
00446 {
00447
00448 data_skip_depth_counter_ = 0;
00449
00450 if (depth_raw_subscribers_||depth_subscribers_||projector_info_subscribers_)
00451 {
00452 image->header.stamp = image->header.stamp + depth_time_offset_;
00453
00454 if (z_offset_mm_ != 0)
00455 {
00456 uint16_t* data = reinterpret_cast<uint16_t*>(&image->data[0]);
00457 for (unsigned int i = 0; i < image->width * image->height; ++i)
00458 if (data[i] != 0)
00459 data[i] += z_offset_mm_;
00460 }
00461
00462 if (fabs(z_scaling_ - 1.0) > 1e-6)
00463 {
00464 uint16_t* data = reinterpret_cast<uint16_t*>(&image->data[0]);
00465 for (unsigned int i = 0; i < image->width * image->height; ++i)
00466 if (data[i] != 0)
00467 data[i] = static_cast<uint16_t>(data[i] * z_scaling_);
00468 }
00469
00470 sensor_msgs::CameraInfoPtr cam_info;
00471
00472 if (depth_registration_)
00473 {
00474 image->header.frame_id = color_frame_id_;
00475 cam_info = getColorCameraInfo(image->width,image->height, image->header.stamp);
00476 } else
00477 {
00478 image->header.frame_id = depth_frame_id_;
00479 cam_info = getDepthCameraInfo(image->width,image->height, image->header.stamp);
00480 }
00481
00482 if (depth_raw_subscribers_)
00483 {
00484 pub_depth_raw_.publish(image, cam_info);
00485 }
00486
00487 if (depth_subscribers_ )
00488 {
00489 sensor_msgs::ImageConstPtr floating_point_image = rawToFloatingPointConversion(image);
00490 pub_depth_.publish(floating_point_image, cam_info);
00491 }
00492
00493
00494 if (projector_info_subscribers_)
00495 {
00496 pub_projector_info_.publish(getProjectorCameraInfo(image->width, image->height, image->header.stamp));
00497 }
00498 }
00499 }
00500 }
00501
00502
00503 sensor_msgs::CameraInfoPtr OpenNI2Driver::getDefaultCameraInfo(int width, int height, double f) const
00504 {
00505 sensor_msgs::CameraInfoPtr info = boost::make_shared<sensor_msgs::CameraInfo>();
00506
00507 info->width = width;
00508 info->height = height;
00509
00510
00511 info->D.resize(5, 0.0);
00512 info->distortion_model = sensor_msgs::distortion_models::PLUMB_BOB;
00513
00514
00515 info->K.assign(0.0);
00516 info->K[0] = info->K[4] = f;
00517 info->K[2] = (width / 2) - 0.5;
00518
00519
00520 info->K[5] = (width * (3./8.)) - 0.5;
00521 info->K[8] = 1.0;
00522
00523
00524 info->R.assign(0.0);
00525 info->R[0] = info->R[4] = info->R[8] = 1.0;
00526
00527
00528 info->P.assign(0.0);
00529 info->P[0] = info->P[5] = f;
00530 info->P[2] = info->K[2];
00531 info->P[6] = info->K[5];
00532 info->P[10] = 1.0;
00533
00534 return info;
00535 }
00536
00538 sensor_msgs::CameraInfoPtr OpenNI2Driver::getColorCameraInfo(int width, int height, ros::Time time) const
00539 {
00540 sensor_msgs::CameraInfoPtr info;
00541
00542 if (color_info_manager_->isCalibrated())
00543 {
00544 info = boost::make_shared<sensor_msgs::CameraInfo>(color_info_manager_->getCameraInfo());
00545 if ( info->width != width )
00546 {
00547
00548 ROS_WARN_ONCE("Image resolution doesn't match calibration of the RGB camera. Using default parameters.");
00549 info = getDefaultCameraInfo(width, height, device_->getColorFocalLength(height));
00550 }
00551 }
00552 else
00553 {
00554
00555 info = getDefaultCameraInfo(width, height, device_->getColorFocalLength(height));
00556 }
00557
00558
00559 info->header.stamp = time;
00560 info->header.frame_id = color_frame_id_;
00561
00562 return info;
00563 }
00564
00565
00566 sensor_msgs::CameraInfoPtr OpenNI2Driver::getIRCameraInfo(int width, int height, ros::Time time) const
00567 {
00568 sensor_msgs::CameraInfoPtr info;
00569
00570 if (ir_info_manager_->isCalibrated())
00571 {
00572 info = boost::make_shared<sensor_msgs::CameraInfo>(ir_info_manager_->getCameraInfo());
00573 if ( info->width != width )
00574 {
00575
00576 ROS_WARN_ONCE("Image resolution doesn't match calibration of the IR camera. Using default parameters.");
00577 info = getDefaultCameraInfo(width, height, device_->getIRFocalLength(height));
00578 }
00579 }
00580 else
00581 {
00582
00583 info = getDefaultCameraInfo(width, height, device_->getDepthFocalLength(height));
00584 }
00585
00586
00587 info->header.stamp = time;
00588 info->header.frame_id = depth_frame_id_;
00589
00590 return info;
00591 }
00592
00593 sensor_msgs::CameraInfoPtr OpenNI2Driver::getDepthCameraInfo(int width, int height, ros::Time time) const
00594 {
00595
00596
00597
00598
00599 double scaling = (double)width / 640;
00600
00601 sensor_msgs::CameraInfoPtr info = getIRCameraInfo(width, height, time);
00602 info->K[2] -= depth_ir_offset_x_*scaling;
00603 info->K[5] -= depth_ir_offset_y_*scaling;
00604 info->P[2] -= depth_ir_offset_x_*scaling;
00605 info->P[6] -= depth_ir_offset_y_*scaling;
00606
00608 return info;
00609 }
00610
00611 sensor_msgs::CameraInfoPtr OpenNI2Driver::getProjectorCameraInfo(int width, int height, ros::Time time) const
00612 {
00613
00614
00615
00616 sensor_msgs::CameraInfoPtr info = getDepthCameraInfo(width, height, time);
00617
00618 info->P[3] = -device_->getBaseline() * info->P[0];
00619 return info;
00620 }
00621
00622 void OpenNI2Driver::readConfigFromParameterServer()
00623 {
00624 if (!pnh_.getParam("device_id", device_id_))
00625 {
00626 ROS_WARN ("~device_id is not set! Using first device.");
00627 device_id_ = "#1";
00628 }
00629
00630
00631 pnh_.param("ir_frame_id", ir_frame_id_, std::string("/openni_ir_optical_frame"));
00632 pnh_.param("rgb_frame_id", color_frame_id_, std::string("/openni_rgb_optical_frame"));
00633 pnh_.param("depth_frame_id", depth_frame_id_, std::string("/openni_depth_optical_frame"));
00634
00635 ROS_DEBUG("ir_frame_id = '%s' ", ir_frame_id_.c_str());
00636 ROS_DEBUG("rgb_frame_id = '%s' ", color_frame_id_.c_str());
00637 ROS_DEBUG("depth_frame_id = '%s' ", depth_frame_id_.c_str());
00638
00639 pnh_.param("rgb_camera_info_url", color_info_url_, std::string());
00640 pnh_.param("depth_camera_info_url", ir_info_url_, std::string());
00641
00642 }
00643
00644 std::string OpenNI2Driver::resolveDeviceURI(const std::string& device_id) throw(OpenNI2Exception)
00645 {
00646
00647
00648 boost::shared_ptr<std::vector<std::string> > available_device_URIs =
00649 device_manager_->getConnectedDeviceURIs();
00650
00651
00652 if (device_id.size() > 1 && device_id[0] == '#')
00653 {
00654 std::istringstream device_number_str(device_id.substr(1));
00655 int device_number;
00656 device_number_str >> device_number;
00657 int device_index = device_number - 1;
00658 if (device_index >= available_device_URIs->size() || device_index < 0)
00659 {
00660 THROW_OPENNI_EXCEPTION(
00661 "Invalid device number %i, there are %zu devices connected.",
00662 device_number, available_device_URIs->size());
00663 }
00664 else
00665 {
00666 return available_device_URIs->at(device_index);
00667 }
00668 }
00669
00670
00671
00672
00673 else if (device_id.size() > 1 && device_id.find('@') != std::string::npos && device_id.find('/') == std::string::npos)
00674 {
00675
00676 size_t index = device_id.find('@');
00677 if (index <= 0)
00678 {
00679 THROW_OPENNI_EXCEPTION(
00680 "%s is not a valid device URI, you must give the bus number before the @.",
00681 device_id.c_str());
00682 }
00683 if (index >= device_id.size() - 1)
00684 {
00685 THROW_OPENNI_EXCEPTION(
00686 "%s is not a valid device URI, you must give the device number after the @, specify 0 for any device on this bus",
00687 device_id.c_str());
00688 }
00689
00690
00691 std::istringstream device_number_str(device_id.substr(index+1));
00692 int device_number;
00693 device_number_str >> device_number;
00694
00695
00696 std::string bus = device_id.substr(0, index);
00697 bus.insert(0, "@");
00698
00699 for (size_t i = 0; i < available_device_URIs->size(); ++i)
00700 {
00701 std::string s = (*available_device_URIs)[i];
00702 if (s.find(bus) != std::string::npos)
00703 {
00704
00705 std::ostringstream ss;
00706 ss << bus << '/' << device_number;
00707 if (device_number == 0 || s.find(ss.str()) != std::string::npos)
00708 return s;
00709 }
00710 }
00711
00712 THROW_OPENNI_EXCEPTION("Device not found %s", device_id.c_str());
00713 }
00714 else
00715 {
00716
00717 for(std::vector<std::string>::const_iterator it = available_device_URIs->begin();
00718 it != available_device_URIs->end(); ++it)
00719 {
00720 try {
00721 std::string serial = device_manager_->getSerial(*it);
00722 if (serial.size() > 0 && device_id == serial)
00723 return *it;
00724 }
00725 catch (const OpenNI2Exception& exception)
00726 {
00727 ROS_WARN("Could not query serial number of device \"%s\":", exception.what());
00728 }
00729 }
00730
00731
00732 bool match_found = false;
00733 std::string matched_uri;
00734 for (size_t i = 0; i < available_device_URIs->size(); ++i)
00735 {
00736 std::string s = (*available_device_URIs)[i];
00737 if (s.find(device_id) != std::string::npos)
00738 {
00739 if (!match_found)
00740 {
00741 matched_uri = s;
00742 match_found = true;
00743 }
00744 else
00745 {
00746
00747 THROW_OPENNI_EXCEPTION("Two devices match the given device id '%s': %s and %s.", device_id.c_str(), matched_uri.c_str(), s.c_str());
00748 }
00749 }
00750 }
00751 if (match_found)
00752 return matched_uri;
00753 else
00754 return "INVALID";
00755 }
00756 }
00757
00758 void OpenNI2Driver::initDevice()
00759 {
00760 while (ros::ok() && !device_)
00761 {
00762 try
00763 {
00764 std::string device_URI = resolveDeviceURI(device_id_);
00765 device_ = device_manager_->getDevice(device_URI);
00766 }
00767 catch (const OpenNI2Exception& exception)
00768 {
00769 if (!device_)
00770 {
00771 ROS_INFO("No matching device found.... waiting for devices. Reason: %s", exception.what());
00772 boost::this_thread::sleep(boost::posix_time::seconds(3));
00773 continue;
00774 }
00775 else
00776 {
00777 ROS_ERROR("Could not retrieve device. Reason: %s", exception.what());
00778 exit(-1);
00779 }
00780 }
00781 }
00782
00783 while (ros::ok() && !device_->isValid())
00784 {
00785 ROS_DEBUG("Waiting for device initialization..");
00786 boost::this_thread::sleep(boost::posix_time::milliseconds(100));
00787 }
00788
00789 }
00790
00791 void OpenNI2Driver::genVideoModeTableMap()
00792 {
00793
00794
00795
00796
00797
00798
00799
00800
00801
00802
00803
00804
00805
00806
00807
00808
00809
00810 video_modes_lookup_.clear();
00811
00812 OpenNI2VideoMode video_mode;
00813
00814
00815 video_mode.x_resolution_ = 1280;
00816 video_mode.y_resolution_ = 1024;
00817 video_mode.frame_rate_ = 30;
00818
00819 video_modes_lookup_[1] = video_mode;
00820
00821
00822 video_mode.x_resolution_ = 1280;
00823 video_mode.y_resolution_ = 1024;
00824 video_mode.frame_rate_ = 15;
00825
00826 video_modes_lookup_[2] = video_mode;
00827
00828
00829 video_mode.x_resolution_ = 1280;
00830 video_mode.y_resolution_ = 720;
00831 video_mode.frame_rate_ = 30;
00832
00833 video_modes_lookup_[3] = video_mode;
00834
00835
00836 video_mode.x_resolution_ = 1280;
00837 video_mode.y_resolution_ = 720;
00838 video_mode.frame_rate_ = 15;
00839
00840 video_modes_lookup_[4] = video_mode;
00841
00842
00843 video_mode.x_resolution_ = 640;
00844 video_mode.y_resolution_ = 480;
00845 video_mode.frame_rate_ = 30;
00846
00847 video_modes_lookup_[5] = video_mode;
00848
00849
00850 video_mode.x_resolution_ = 640;
00851 video_mode.y_resolution_ = 480;
00852 video_mode.frame_rate_ = 25;
00853
00854 video_modes_lookup_[6] = video_mode;
00855
00856
00857 video_mode.x_resolution_ = 320;
00858 video_mode.y_resolution_ = 240;
00859 video_mode.frame_rate_ = 25;
00860
00861 video_modes_lookup_[7] = video_mode;
00862
00863
00864 video_mode.x_resolution_ = 320;
00865 video_mode.y_resolution_ = 240;
00866 video_mode.frame_rate_ = 30;
00867
00868 video_modes_lookup_[8] = video_mode;
00869
00870
00871 video_mode.x_resolution_ = 320;
00872 video_mode.y_resolution_ = 240;
00873 video_mode.frame_rate_ = 60;
00874
00875 video_modes_lookup_[9] = video_mode;
00876
00877
00878 video_mode.x_resolution_ = 160;
00879 video_mode.y_resolution_ = 120;
00880 video_mode.frame_rate_ = 25;
00881
00882 video_modes_lookup_[10] = video_mode;
00883
00884
00885 video_mode.x_resolution_ = 160;
00886 video_mode.y_resolution_ = 120;
00887 video_mode.frame_rate_ = 30;
00888
00889 video_modes_lookup_[11] = video_mode;
00890
00891
00892 video_mode.x_resolution_ = 160;
00893 video_mode.y_resolution_ = 120;
00894 video_mode.frame_rate_ = 60;
00895
00896 video_modes_lookup_[12] = video_mode;
00897
00898 }
00899
00900 int OpenNI2Driver::lookupVideoModeFromDynConfig(int mode_nr, OpenNI2VideoMode& video_mode)
00901 {
00902 int ret = -1;
00903
00904 std::map<int, OpenNI2VideoMode>::const_iterator it;
00905
00906 it = video_modes_lookup_.find(mode_nr);
00907
00908 if (it!=video_modes_lookup_.end())
00909 {
00910 video_mode = it->second;
00911 ret = 0;
00912 }
00913
00914 return ret;
00915 }
00916
00917 sensor_msgs::ImageConstPtr OpenNI2Driver::rawToFloatingPointConversion(sensor_msgs::ImageConstPtr raw_image)
00918 {
00919 static const float bad_point = std::numeric_limits<float>::quiet_NaN ();
00920
00921 sensor_msgs::ImagePtr new_image = boost::make_shared<sensor_msgs::Image>();
00922
00923 new_image->header = raw_image->header;
00924 new_image->width = raw_image->width;
00925 new_image->height = raw_image->height;
00926 new_image->is_bigendian = 0;
00927 new_image->encoding = sensor_msgs::image_encodings::TYPE_32FC1;
00928 new_image->step = sizeof(float)*raw_image->width;
00929
00930 std::size_t data_size = new_image->width*new_image->height;
00931 new_image->data.resize(data_size*sizeof(float));
00932
00933 const unsigned short* in_ptr = reinterpret_cast<const unsigned short*>(&raw_image->data[0]);
00934 float* out_ptr = reinterpret_cast<float*>(&new_image->data[0]);
00935
00936 for (std::size_t i = 0; i<data_size; ++i, ++in_ptr, ++out_ptr)
00937 {
00938 if (*in_ptr==0 || *in_ptr==0x7FF)
00939 {
00940 *out_ptr = bad_point;
00941 } else
00942 {
00943 *out_ptr = static_cast<float>(*in_ptr)/1000.0f;
00944 }
00945 }
00946
00947 return new_image;
00948 }
00949
00950 }