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 #include "openni2/OpenNI.h"
00034
00035 #include <boost/lexical_cast.hpp>
00036 #include <boost/algorithm/string/replace.hpp>
00037
00038 #include "astra_camera/astra_driver.h"
00039 #include "astra_camera/astra_device.h"
00040 #include "astra_camera/astra_exception.h"
00041 #include "astra_camera/astra_convert.h"
00042 #include "astra_camera/astra_frame_listener.h"
00043 #include "astra_camera/astra_device_type.h"
00044
00045 #include "openni2/PS1080.h"
00046
00047 #include <boost/shared_ptr.hpp>
00048 #include <boost/make_shared.hpp>
00049
00050 #include <string>
00051
00052 namespace astra_wrapper
00053 {
00054
00055 AstraDevice::AstraDevice(const std::string& device_URI):
00056 openni_device_(),
00057 ir_video_started_(false),
00058 color_video_started_(false),
00059 depth_video_started_(false),
00060 image_registration_activated_(false),
00061 use_device_time_(false)
00062 {
00063 openni::Status rc = openni::OpenNI::initialize();
00064 if (rc != openni::STATUS_OK)
00065 THROW_OPENNI_EXCEPTION("Initialize failed\n%s\n", openni::OpenNI::getExtendedError());
00066
00067 openni_device_ = boost::make_shared<openni::Device>();
00068
00069 if (device_URI.length() > 0)
00070 {
00071 rc = openni_device_->open(device_URI.c_str());
00072 }
00073 else
00074 {
00075 rc = openni_device_->open(openni::ANY_DEVICE);
00076 }
00077
00078 if (rc != openni::STATUS_OK)
00079 THROW_OPENNI_EXCEPTION("Device open failed\n%s\n", openni::OpenNI::getExtendedError());
00080
00081 device_info_ = boost::make_shared<openni::DeviceInfo>();
00082 *device_info_ = openni_device_->getDeviceInfo();
00083
00084 int param_size = sizeof(OBCameraParams);
00085 openni_device_->getProperty(openni::OBEXTENSION_ID_CAM_PARAMS, (uint8_t*)&m_CamParams, ¶m_size);
00086
00087 int serial_number_size = sizeof(serial_number);
00088 memset(serial_number, 0, serial_number_size);
00089 openni_device_->getProperty(openni::OBEXTENSION_ID_SERIALNUMBER, (uint8_t*)&serial_number, &serial_number_size);
00090
00091 int device_type_size = sizeof(device_type);
00092 memset(device_type, 0, device_type_size);
00093 openni_device_->getProperty(openni::OBEXTENSION_ID_DEVICETYPE, (uint8_t*)&device_type, &device_type_size);
00094 if (strcmp(device_type, OB_STEREO_S) == 0)
00095 {
00096 device_type_no = OB_STEREO_S_NO;
00097 }
00098 else if (strcmp(device_type, OB_EMBEDDED_S) == 0)
00099 {
00100 device_type_no = OB_EMBEDDED_S_NO;
00101 }
00102 else if (strcmp(device_type, OB_ASTRA_PRO) == 0)
00103 {
00104 device_type_no = OB_ASTRA_PRO_NO;
00105 }
00106 else
00107 {
00108 device_type_no = OB_ASTRA_NO;
00109 }
00110
00111 ir_frame_listener = boost::make_shared<AstraFrameListener>();
00112 color_frame_listener = boost::make_shared<AstraFrameListener>();
00113 depth_frame_listener = boost::make_shared<AstraFrameListener>();
00114
00115 }
00116
00117 AstraDevice::~AstraDevice()
00118 {
00119 stopAllStreams();
00120
00121 shutdown();
00122
00123 openni_device_->close();
00124 }
00125
00126 const std::string AstraDevice::getUri() const
00127 {
00128 return std::string(device_info_->getUri());
00129 }
00130
00131 const std::string AstraDevice::getVendor() const
00132 {
00133 return std::string(device_info_->getVendor());
00134 }
00135
00136 const std::string AstraDevice::getName() const
00137 {
00138 return std::string(device_info_->getName());
00139 }
00140
00141 uint16_t AstraDevice::getUsbVendorId() const
00142 {
00143 return device_info_->getUsbVendorId();
00144 }
00145
00146 uint16_t AstraDevice::getUsbProductId() const
00147 {
00148 return device_info_->getUsbProductId();
00149 }
00150
00151 const std::string AstraDevice::getStringID() const
00152 {
00153 std::string ID_str = getName() + "_" + getVendor();
00154
00155 boost::replace_all(ID_str, "/", "");
00156 boost::replace_all(ID_str, ".", "");
00157 boost::replace_all(ID_str, "@", "");
00158
00159 return ID_str;
00160 }
00161
00162 bool AstraDevice::isValid() const
00163 {
00164 return (openni_device_.get() != 0) && openni_device_->isValid();
00165 }
00166
00167 OBCameraParams AstraDevice::getCameraParams() const
00168 {
00169 return m_CamParams;
00170 }
00171
00172 char* AstraDevice::getSerialNumber()
00173 {
00174 return serial_number;
00175 }
00176
00177 char* AstraDevice::getDeviceType()
00178 {
00179 return device_type;
00180 }
00181
00182 int AstraDevice::getDeviceTypeNo()
00183 {
00184 return device_type_no;
00185 }
00186
00187 int AstraDevice::getIRGain() const
00188 {
00189 int gain = 0;
00190 int data_size = 4;
00191 openni_device_->getProperty(openni::OBEXTENSION_ID_IR_GAIN, (uint8_t*)&gain, &data_size);
00192 return gain;
00193 }
00194
00195 int AstraDevice::getIRExposure() const
00196 {
00197 int exposure = 0;
00198 int data_size = 4;
00199 openni_device_->getProperty(openni::OBEXTENSION_ID_IR_EXP, (uint8_t*)&exposure, &data_size);
00200 return exposure;
00201 }
00202
00203 void AstraDevice::setCameraParams(OBCameraParams param)
00204 {
00205 int data_size = sizeof(OBCameraParams);
00206 openni_device_->setProperty(openni::OBEXTENSION_ID_CAM_PARAMS, (uint8_t*)¶m, data_size);
00207 }
00208
00209 void AstraDevice::setIRGain(int gain)
00210 {
00211 int data_size = 4;
00212 openni_device_->setProperty(openni::OBEXTENSION_ID_IR_GAIN, (uint8_t*)&gain, data_size);
00213 }
00214
00215 void AstraDevice::setIRExposure(int exposure)
00216 {
00217 int data_size = 4;
00218 openni_device_->setProperty(openni::OBEXTENSION_ID_IR_EXP, (uint8_t*)&exposure, data_size);
00219 }
00220
00221 void AstraDevice::setLaser(bool enable)
00222 {
00223 int data_size = 4;
00224 int laser_enable = 1;
00225 if (enable == false)
00226 {
00227 laser_enable = 0;
00228 }
00229 openni_device_->setProperty(openni::OBEXTENSION_ID_LASER_EN, (uint8_t*)&laser_enable, data_size);
00230 }
00231
00232 void AstraDevice::setIRFlood(bool enable)
00233 {
00234 int data_size = 4;
00235 int enable_ = 1;
00236 if (enable == false)
00237 {
00238 enable_ = 0;
00239 }
00240 openni_device_->setProperty(XN_MODULE_PROPERTY_IRFLOOD_STATE, enable_);
00241 }
00242
00243 float AstraDevice::getIRFocalLength(int output_y_resolution) const
00244 {
00245 float focal_length = 0.0f;
00246 boost::shared_ptr<openni::VideoStream> stream = getIRVideoStream();
00247
00248 if (stream)
00249 {
00250 focal_length = (float)output_y_resolution / (2 * tan(stream->getVerticalFieldOfView() / 2));
00251 }
00252
00253 return focal_length;
00254 }
00255
00256 float AstraDevice::getColorFocalLength(int output_y_resolution) const
00257 {
00258 float focal_length = 0.0f;
00259 boost::shared_ptr<openni::VideoStream> stream = getColorVideoStream();
00260
00261 if (stream)
00262 {
00263 focal_length = (float)output_y_resolution / (2 * tan(stream->getVerticalFieldOfView() / 2));
00264 }
00265
00266 return focal_length;
00267 }
00268
00269 float AstraDevice::getDepthFocalLength(int output_y_resolution) const
00270 {
00271 float focal_length = 0.0f;
00272 boost::shared_ptr<openni::VideoStream> stream = getDepthVideoStream();
00273
00274 if (stream)
00275 {
00276 focal_length = (float)output_y_resolution / (2 * tan(stream->getVerticalFieldOfView() / 2));
00277 }
00278
00279 return focal_length;
00280 }
00281
00282 float AstraDevice::getBaseline() const
00283 {
00284 return 0.075f;
00285 }
00286
00287 bool AstraDevice::isIRVideoModeSupported(const AstraVideoMode& video_mode) const
00288 {
00289 getSupportedIRVideoModes();
00290
00291 bool supported = false;
00292
00293 std::vector<AstraVideoMode>::const_iterator it = ir_video_modes_.begin();
00294 std::vector<AstraVideoMode>::const_iterator it_end = ir_video_modes_.end();
00295
00296 while (it != it_end && !supported)
00297 {
00298 supported = (*it == video_mode);
00299 ++it;
00300 }
00301
00302 return supported;
00303 }
00304
00305 bool AstraDevice::isColorVideoModeSupported(const AstraVideoMode& video_mode) const
00306 {
00307 getSupportedColorVideoModes();
00308
00309 bool supported = false;
00310
00311 std::vector<AstraVideoMode>::const_iterator it = color_video_modes_.begin();
00312 std::vector<AstraVideoMode>::const_iterator it_end = color_video_modes_.end();
00313
00314 while (it != it_end && !supported)
00315 {
00316 supported = (*it == video_mode);
00317 ++it;
00318 }
00319
00320 return supported;
00321 }
00322
00323 bool AstraDevice::isDepthVideoModeSupported(const AstraVideoMode& video_mode) const
00324 {
00325 getSupportedDepthVideoModes();
00326
00327 bool supported = false;
00328
00329 std::vector<AstraVideoMode>::const_iterator it = depth_video_modes_.begin();
00330 std::vector<AstraVideoMode>::const_iterator it_end = depth_video_modes_.end();
00331
00332 while (it != it_end && !supported)
00333 {
00334 supported = (*it == video_mode);
00335 ++it;
00336 }
00337
00338 return supported;
00339
00340 }
00341
00342 bool AstraDevice::hasIRSensor() const
00343 {
00344 return openni_device_->hasSensor(openni::SENSOR_IR);
00345 }
00346
00347 bool AstraDevice::hasColorSensor() const
00348 {
00349 return (getUsbProductId()!=0x0403)?openni_device_->hasSensor(openni::SENSOR_COLOR):0;
00350 }
00351
00352 bool AstraDevice::hasDepthSensor() const
00353 {
00354 return openni_device_->hasSensor(openni::SENSOR_DEPTH);
00355 }
00356
00357 void AstraDevice::startIRStream()
00358 {
00359 boost::shared_ptr<openni::VideoStream> stream = getIRVideoStream();
00360
00361 if (stream)
00362 {
00363 stream->setMirroringEnabled(false);
00364 stream->start();
00365 stream->addNewFrameListener(ir_frame_listener.get());
00366 ir_video_started_ = true;
00367 }
00368
00369 }
00370
00371 void AstraDevice::startColorStream()
00372 {
00373 boost::shared_ptr<openni::VideoStream> stream = getColorVideoStream();
00374
00375 if (stream)
00376 {
00377 stream->setMirroringEnabled(false);
00378 stream->start();
00379 stream->addNewFrameListener(color_frame_listener.get());
00380 color_video_started_ = true;
00381 }
00382 }
00383 void AstraDevice::startDepthStream()
00384 {
00385 boost::shared_ptr<openni::VideoStream> stream = getDepthVideoStream();
00386
00387 if (stream)
00388 {
00389 stream->setMirroringEnabled(false);
00390 stream->start();
00391 stream->addNewFrameListener(depth_frame_listener.get());
00392 depth_video_started_ = true;
00393 }
00394 }
00395
00396 void AstraDevice::stopAllStreams()
00397 {
00398 stopIRStream();
00399 stopColorStream();
00400 stopDepthStream();
00401 }
00402
00403 void AstraDevice::stopIRStream()
00404 {
00405 if (ir_video_stream_.get() != 0)
00406 {
00407 ir_video_started_ = false;
00408
00409 ir_video_stream_->removeNewFrameListener(ir_frame_listener.get());
00410
00411 ir_video_stream_->stop();
00412 }
00413 }
00414 void AstraDevice::stopColorStream()
00415 {
00416 if (color_video_stream_.get() != 0)
00417 {
00418 color_video_started_ = false;
00419
00420 color_video_stream_->removeNewFrameListener(color_frame_listener.get());
00421
00422 color_video_stream_->stop();
00423 }
00424 }
00425 void AstraDevice::stopDepthStream()
00426 {
00427 if (depth_video_stream_.get() != 0)
00428 {
00429 depth_video_started_ = false;
00430
00431 depth_video_stream_->removeNewFrameListener(depth_frame_listener.get());
00432
00433 depth_video_stream_->stop();
00434 }
00435 }
00436
00437 void AstraDevice::shutdown()
00438 {
00439 if (ir_video_stream_.get() != 0)
00440 ir_video_stream_->destroy();
00441
00442 if (color_video_stream_.get() != 0)
00443 color_video_stream_->destroy();
00444
00445 if (depth_video_stream_.get() != 0)
00446 depth_video_stream_->destroy();
00447
00448 }
00449
00450 bool AstraDevice::isIRStreamStarted()
00451 {
00452 return ir_video_started_;
00453 }
00454 bool AstraDevice::isColorStreamStarted()
00455 {
00456 return color_video_started_;
00457 }
00458 bool AstraDevice::isDepthStreamStarted()
00459 {
00460 return depth_video_started_;
00461 }
00462
00463 const std::vector<AstraVideoMode>& AstraDevice::getSupportedIRVideoModes() const
00464 {
00465 boost::shared_ptr<openni::VideoStream> stream = getIRVideoStream();
00466
00467 ir_video_modes_.clear();
00468
00469 if (stream)
00470 {
00471 const openni::SensorInfo& sensor_info = stream->getSensorInfo();
00472
00473 ir_video_modes_ = astra_convert(sensor_info.getSupportedVideoModes());
00474 }
00475
00476 return ir_video_modes_;
00477 }
00478
00479 const std::vector<AstraVideoMode>& AstraDevice::getSupportedColorVideoModes() const
00480 {
00481 boost::shared_ptr<openni::VideoStream> stream = getColorVideoStream();
00482
00483 color_video_modes_.clear();
00484
00485 if (stream)
00486 {
00487 const openni::SensorInfo& sensor_info = stream->getSensorInfo();
00488
00489 color_video_modes_ = astra_convert(sensor_info.getSupportedVideoModes());
00490 }
00491
00492 return color_video_modes_;
00493 }
00494
00495 const std::vector<AstraVideoMode>& AstraDevice::getSupportedDepthVideoModes() const
00496 {
00497 boost::shared_ptr<openni::VideoStream> stream = getDepthVideoStream();
00498
00499 depth_video_modes_.clear();
00500
00501 if (stream)
00502 {
00503 const openni::SensorInfo& sensor_info = stream->getSensorInfo();
00504
00505 depth_video_modes_ = astra_convert(sensor_info.getSupportedVideoModes());
00506 }
00507
00508 return depth_video_modes_;
00509 }
00510
00511 bool AstraDevice::isImageRegistrationModeSupported() const
00512 {
00513 return openni_device_->isImageRegistrationModeSupported(openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR);
00514 }
00515
00516 void AstraDevice::setImageRegistrationMode(bool enabled)
00517 {
00518 if (isImageRegistrationModeSupported())
00519 {
00520 image_registration_activated_ = enabled;
00521 if (enabled)
00522 {
00523 openni::Status rc = openni_device_->setImageRegistrationMode(openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR);
00524 if (rc != openni::STATUS_OK)
00525 THROW_OPENNI_EXCEPTION("Enabling image registration mode failed: \n%s\n", openni::OpenNI::getExtendedError());
00526 }
00527 else
00528 {
00529 openni::Status rc = openni_device_->setImageRegistrationMode(openni::IMAGE_REGISTRATION_OFF);
00530 if (rc != openni::STATUS_OK)
00531 THROW_OPENNI_EXCEPTION("Enabling image registration mode failed: \n%s\n", openni::OpenNI::getExtendedError());
00532 }
00533 }
00534 }
00535
00536 void AstraDevice::setDepthColorSync(bool enabled)
00537 {
00538 openni::Status rc = openni_device_->setDepthColorSyncEnabled(enabled);
00539 if (rc != openni::STATUS_OK)
00540 THROW_OPENNI_EXCEPTION("Enabling depth color synchronization failed: \n%s\n", openni::OpenNI::getExtendedError());
00541 }
00542
00543 const AstraVideoMode AstraDevice::getIRVideoMode()
00544 {
00545 AstraVideoMode ret;
00546
00547 boost::shared_ptr<openni::VideoStream> stream = getIRVideoStream();
00548
00549 if (stream)
00550 {
00551 openni::VideoMode video_mode = stream->getVideoMode();
00552
00553 ret = astra_convert(video_mode);
00554 }
00555 else
00556 THROW_OPENNI_EXCEPTION("Could not create video stream.");
00557
00558 return ret;
00559 }
00560
00561 const AstraVideoMode AstraDevice::getColorVideoMode()
00562 {
00563 AstraVideoMode ret;
00564
00565 boost::shared_ptr<openni::VideoStream> stream = getColorVideoStream();
00566
00567 if (stream)
00568 {
00569 openni::VideoMode video_mode = stream->getVideoMode();
00570
00571 ret = astra_convert(video_mode);
00572 }
00573 else
00574 THROW_OPENNI_EXCEPTION("Could not create video stream.");
00575
00576 return ret;
00577 }
00578
00579 const AstraVideoMode AstraDevice::getDepthVideoMode()
00580 {
00581 AstraVideoMode ret;
00582
00583 boost::shared_ptr<openni::VideoStream> stream = getDepthVideoStream();
00584
00585 if (stream)
00586 {
00587 openni::VideoMode video_mode = stream->getVideoMode();
00588
00589 ret = astra_convert(video_mode);
00590 }
00591 else
00592 THROW_OPENNI_EXCEPTION("Could not create video stream.");
00593
00594 return ret;
00595 }
00596
00597 void AstraDevice::setIRVideoMode(const AstraVideoMode& video_mode)
00598 {
00599 boost::shared_ptr<openni::VideoStream> stream = getIRVideoStream();
00600
00601 if (stream)
00602 {
00603 const openni::VideoMode videoMode = astra_convert(video_mode);
00604 const openni::Status rc = stream->setVideoMode(videoMode);
00605 if (rc != openni::STATUS_OK)
00606 THROW_OPENNI_EXCEPTION("Couldn't set IR video mode: \n%s\n", openni::OpenNI::getExtendedError());
00607 }
00608 }
00609
00610 void AstraDevice::setColorVideoMode(const AstraVideoMode& video_mode)
00611 {
00612 boost::shared_ptr<openni::VideoStream> stream = getColorVideoStream();
00613
00614 if (stream)
00615 {
00616 const openni::VideoMode videoMode = astra_convert(video_mode);
00617 const openni::Status rc = stream->setVideoMode(videoMode);
00618 if (rc != openni::STATUS_OK)
00619 THROW_OPENNI_EXCEPTION("Couldn't set color video mode: \n%s\n", openni::OpenNI::getExtendedError());
00620 }
00621 }
00622
00623 void AstraDevice::setDepthVideoMode(const AstraVideoMode& video_mode)
00624 {
00625 boost::shared_ptr<openni::VideoStream> stream = getDepthVideoStream();
00626
00627 if (stream)
00628 {
00629 const openni::VideoMode videoMode = astra_convert(video_mode);
00630 const openni::Status rc = stream->setVideoMode(videoMode);
00631 if (rc != openni::STATUS_OK)
00632 THROW_OPENNI_EXCEPTION("Couldn't set depth video mode: \n%s\n", openni::OpenNI::getExtendedError());
00633 }
00634 }
00635
00636 void AstraDevice::setAutoExposure(bool enable)
00637 {
00638 boost::shared_ptr<openni::VideoStream> stream = getColorVideoStream();
00639
00640 if (stream)
00641 {
00642 openni::CameraSettings* camera_seeting = stream->getCameraSettings();
00643 if (camera_seeting)
00644 {
00645 const openni::Status rc = camera_seeting->setAutoExposureEnabled(enable);
00646 if (rc != openni::STATUS_OK)
00647 THROW_OPENNI_EXCEPTION("Couldn't set auto exposure: \n%s\n", openni::OpenNI::getExtendedError());
00648 }
00649
00650 }
00651 }
00652 void AstraDevice::setAutoWhiteBalance(bool enable)
00653 {
00654 boost::shared_ptr<openni::VideoStream> stream = getColorVideoStream();
00655
00656 if (stream)
00657 {
00658 openni::CameraSettings* camera_seeting = stream->getCameraSettings();
00659 if (camera_seeting)
00660 {
00661 const openni::Status rc = camera_seeting->setAutoWhiteBalanceEnabled(enable);
00662 if (rc != openni::STATUS_OK)
00663 THROW_OPENNI_EXCEPTION("Couldn't set auto white balance: \n%s\n", openni::OpenNI::getExtendedError());
00664 }
00665
00666 }
00667 }
00668
00669 bool AstraDevice::getAutoExposure() const
00670 {
00671 bool ret = false;
00672
00673 boost::shared_ptr<openni::VideoStream> stream = getColorVideoStream();
00674
00675 if (stream)
00676 {
00677 openni::CameraSettings* camera_seeting = stream->getCameraSettings();
00678 if (camera_seeting)
00679 ret = camera_seeting->getAutoExposureEnabled();
00680 }
00681
00682 return ret;
00683 }
00684 bool AstraDevice::getAutoWhiteBalance() const
00685 {
00686 bool ret = false;
00687
00688 boost::shared_ptr<openni::VideoStream> stream = getColorVideoStream();
00689
00690 if (stream)
00691 {
00692 openni::CameraSettings* camera_seeting = stream->getCameraSettings();
00693 if (camera_seeting)
00694 ret = camera_seeting->getAutoWhiteBalanceEnabled();
00695 }
00696
00697 return ret;
00698 }
00699
00700 void AstraDevice::setUseDeviceTimer(bool enable)
00701 {
00702 if (ir_frame_listener)
00703 ir_frame_listener->setUseDeviceTimer(enable);
00704
00705 if (color_frame_listener)
00706 color_frame_listener->setUseDeviceTimer(enable);
00707
00708 if (depth_frame_listener)
00709 depth_frame_listener->setUseDeviceTimer(enable);
00710 }
00711
00712 void AstraDevice::setIRFrameCallback(FrameCallbackFunction callback)
00713 {
00714 ir_frame_listener->setCallback(callback);
00715 }
00716
00717 void AstraDevice::setColorFrameCallback(FrameCallbackFunction callback)
00718 {
00719 color_frame_listener->setCallback(callback);
00720 }
00721
00722 void AstraDevice::setDepthFrameCallback(FrameCallbackFunction callback)
00723 {
00724 depth_frame_listener->setCallback(callback);
00725 }
00726
00727 boost::shared_ptr<openni::VideoStream> AstraDevice::getIRVideoStream() const
00728 {
00729 if (ir_video_stream_.get() == 0)
00730 {
00731 if (hasIRSensor())
00732 {
00733 ir_video_stream_ = boost::make_shared<openni::VideoStream>();
00734
00735 const openni::Status rc = ir_video_stream_->create(*openni_device_, openni::SENSOR_IR);
00736 if (rc != openni::STATUS_OK)
00737 THROW_OPENNI_EXCEPTION("Couldn't create IR video stream: \n%s\n", openni::OpenNI::getExtendedError());
00738 }
00739 }
00740 return ir_video_stream_;
00741 }
00742
00743 boost::shared_ptr<openni::VideoStream> AstraDevice::getColorVideoStream() const
00744 {
00745 if (color_video_stream_.get() == 0)
00746 {
00747 if (hasColorSensor())
00748 {
00749 color_video_stream_ = boost::make_shared<openni::VideoStream>();
00750
00751 const openni::Status rc = color_video_stream_->create(*openni_device_, openni::SENSOR_COLOR);
00752 if (rc != openni::STATUS_OK)
00753 THROW_OPENNI_EXCEPTION("Couldn't create color video stream: \n%s\n", openni::OpenNI::getExtendedError());
00754 }
00755 }
00756 return color_video_stream_;
00757 }
00758
00759 boost::shared_ptr<openni::VideoStream> AstraDevice::getDepthVideoStream() const
00760 {
00761 if (depth_video_stream_.get() == 0)
00762 {
00763 if (hasDepthSensor())
00764 {
00765 depth_video_stream_ = boost::make_shared<openni::VideoStream>();
00766
00767 const openni::Status rc = depth_video_stream_->create(*openni_device_, openni::SENSOR_DEPTH);
00768 if (rc != openni::STATUS_OK)
00769 THROW_OPENNI_EXCEPTION("Couldn't create depth video stream: \n%s\n", openni::OpenNI::getExtendedError());
00770 }
00771 }
00772 return depth_video_stream_;
00773 }
00774
00775 std::ostream& operator <<(std::ostream& stream, const AstraDevice& device)
00776 {
00777
00778 stream << "Device info (" << device.getUri() << ")" << std::endl;
00779 stream << " Vendor: " << device.getVendor() << std::endl;
00780 stream << " Name: " << device.getName() << std::endl;
00781 stream << " USB Vendor ID: " << device.getUsbVendorId() << std::endl;
00782 stream << " USB Product ID: " << device.getUsbVendorId() << std::endl << std::endl;
00783
00784 if (device.hasIRSensor())
00785 {
00786 stream << "IR sensor video modes:" << std::endl;
00787 const std::vector<AstraVideoMode>& video_modes = device.getSupportedIRVideoModes();
00788
00789 std::vector<AstraVideoMode>::const_iterator it = video_modes.begin();
00790 std::vector<AstraVideoMode>::const_iterator it_end = video_modes.end();
00791 for (; it != it_end; ++it)
00792 stream << " - " << *it << std::endl;
00793 }
00794 else
00795 {
00796 stream << "No IR sensor available" << std::endl;
00797 }
00798
00799 if (device.hasColorSensor())
00800 {
00801 stream << "Color sensor video modes:" << std::endl;
00802 const std::vector<AstraVideoMode>& video_modes = device.getSupportedColorVideoModes();
00803
00804 std::vector<AstraVideoMode>::const_iterator it = video_modes.begin();
00805 std::vector<AstraVideoMode>::const_iterator it_end = video_modes.end();
00806 for (; it != it_end; ++it)
00807 stream << " - " << *it << std::endl;
00808 }
00809 else
00810 {
00811 stream << "No Color sensor available" << std::endl;
00812 }
00813
00814 if (device.hasDepthSensor())
00815 {
00816 stream << "Depth sensor video modes:" << std::endl;
00817 const std::vector<AstraVideoMode>& video_modes = device.getSupportedDepthVideoModes();
00818
00819 std::vector<AstraVideoMode>::const_iterator it = video_modes.begin();
00820 std::vector<AstraVideoMode>::const_iterator it_end = video_modes.end();
00821 for (; it != it_end; ++it)
00822 stream << " - " << *it << std::endl;
00823 }
00824 else
00825 {
00826 stream << "No Depth sensor available" << std::endl;
00827 }
00828
00829 return stream;
00830 }
00831
00832 }