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 #include <pcl/point_cloud.h>
00039 #include <pcl/point_types.h>
00040 #include <pcl/common/time.h>
00041 #include <pcl/io/openni_grabber.h>
00042 #include <boost/thread/condition.hpp>
00043 #include <boost/circular_buffer.hpp>
00044 #include <csignal>
00045 #include <limits>
00046 #include <pcl/io/lzf_image_io.h>
00047 #include <pcl/visualization/boost.h>
00048 #include <pcl/visualization/common/float_image_utils.h>
00049 #include <pcl/visualization/image_viewer.h>
00050 #include <pcl/io/openni_camera/openni_driver.h>
00051 #include <pcl/console/parse.h>
00052 #include <pcl/console/time.h>
00053 #include <pcl/visualization/mouse_event.h>
00054
00055 using namespace std;
00056 using namespace pcl;
00057 using namespace pcl::console;
00058
00059 bool global_visualize = true, is_done = false, save_data = false, toggle_one_frame_capture = false, visualize = true;
00060 boost::mutex io_mutex;
00061 int nr_frames_total = 0;
00062
00063 #if defined(__linux__)
00064 #include <unistd.h>
00065
00066
00067 size_t
00068 getTotalSystemMemory ()
00069 {
00070 uint64_t pages = sysconf (_SC_AVPHYS_PAGES);
00071 uint64_t page_size = sysconf (_SC_PAGE_SIZE);
00072 print_info ("Total available memory size: %lluMB.\n", (pages * page_size) / 1048576);
00073 if (pages * page_size > uint64_t (std::numeric_limits<size_t>::max ()))
00074 {
00075 return std::numeric_limits<size_t>::max ();
00076 }
00077 else
00078 {
00079 return size_t (pages * page_size);
00080 }
00081 }
00082
00083 const int BUFFER_SIZE = int (getTotalSystemMemory () / (640 * 480) / 2);
00084 #else
00085
00086 const int BUFFER_SIZE = 200;
00087 #endif
00088
00089 int buff_size = BUFFER_SIZE;
00090
00091 #define FPS_CALC_WRITER(_WHAT_, buff) \
00092 do \
00093 { \
00094 static unsigned count = 0;\
00095 static double last = getTime ();\
00096 double now = getTime (); \
00097 ++count; \
00098 if (now - last >= 1.0) \
00099 { \
00100 cerr << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz. Queue size: " << buff.getSize () << ", number of frames written so far: " << nr_frames_total << "\n"; \
00101 count = 0; \
00102 last = now; \
00103 } \
00104 }while(false)
00105
00106 #define FPS_CALC_VIEWER(_WHAT_, buff) \
00107 do \
00108 { \
00109 static unsigned count = 0;\
00110 static double last = getTime ();\
00111 double now = getTime (); \
00112 ++count; \
00113 if (now - last >= 1.0) \
00114 { \
00115 cerr << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz. Queue size: " << buff.getSize () << "\n"; \
00116 count = 0; \
00117 last = now; \
00118 } \
00119 }while(false)
00120
00121 #define FPS_CALC_DRIVER(_WHAT_, buff1, buff2) \
00122 do \
00123 { \
00124 static unsigned count = 0;\
00125 static double last = getTime ();\
00126 double now = getTime (); \
00127 ++count; \
00128 if (now - last >= 1.0) \
00129 { \
00130 if (visualize && global_visualize) \
00131 cerr << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz. Queue size: " << buff1.getSize () << " (w) / " << buff2.getSize () << " (v)\n"; \
00132 else \
00133 cerr << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz. Queue size: " << buff1.getSize () << " (w)\n"; \
00134 count = 0; \
00135 last = now; \
00136 } \
00137 }while(false)
00138
00140 struct Frame
00141 {
00142 typedef boost::shared_ptr<Frame> Ptr;
00143 typedef boost::shared_ptr<const Frame> ConstPtr;
00144
00145 Frame (const boost::shared_ptr<openni_wrapper::Image> &_image,
00146 const boost::shared_ptr<openni_wrapper::DepthImage> &_depth_image,
00147 const io::CameraParameters &_parameters_rgb,
00148 const io::CameraParameters &_parameters_depth,
00149 const boost::posix_time::ptime &_time)
00150 : image (_image)
00151 , depth_image (_depth_image)
00152 , parameters_rgb (_parameters_rgb)
00153 , parameters_depth (_parameters_depth)
00154 , time (_time)
00155 {}
00156
00157 const boost::shared_ptr<openni_wrapper::Image> image;
00158 const boost::shared_ptr<openni_wrapper::DepthImage> depth_image;
00159
00160 io::CameraParameters parameters_rgb, parameters_depth;
00161
00162 boost::posix_time::ptime time;
00163 };
00164
00166 class Buffer
00167 {
00168 public:
00169 Buffer () {}
00170
00171 bool
00172 pushBack (Frame::ConstPtr frame)
00173 {
00174 bool retVal = false;
00175 {
00176 boost::mutex::scoped_lock buff_lock (bmutex_);
00177 if (!buffer_.full ())
00178 retVal = true;
00179 buffer_.push_back (frame);
00180 }
00181 buff_empty_.notify_one ();
00182 return (retVal);
00183 }
00184
00185 Frame::ConstPtr
00186 popFront ()
00187 {
00188 Frame::ConstPtr cloud;
00189 {
00190 boost::mutex::scoped_lock buff_lock (bmutex_);
00191 while (buffer_.empty ())
00192 {
00193 if (is_done)
00194 break;
00195 {
00196 boost::mutex::scoped_lock io_lock (io_mutex);
00197
00198 }
00199 buff_empty_.wait (buff_lock);
00200 }
00201 cloud = buffer_.front ();
00202 buffer_.pop_front ();
00203 }
00204 return (cloud);
00205 }
00206
00207 inline bool
00208 isFull ()
00209 {
00210 boost::mutex::scoped_lock buff_lock (bmutex_);
00211 return (buffer_.full ());
00212 }
00213
00214 inline bool
00215 isEmpty ()
00216 {
00217 boost::mutex::scoped_lock buff_lock (bmutex_);
00218 return (buffer_.empty ());
00219 }
00220
00221 inline int
00222 getSize ()
00223 {
00224 boost::mutex::scoped_lock buff_lock (bmutex_);
00225 return (int (buffer_.size ()));
00226 }
00227
00228 inline int
00229 getCapacity ()
00230 {
00231 return (int (buffer_.capacity ()));
00232 }
00233
00234 inline void
00235 setCapacity (int buff_size)
00236 {
00237 boost::mutex::scoped_lock buff_lock (bmutex_);
00238 buffer_.set_capacity (buff_size);
00239 }
00240
00241 inline void
00242 clear ()
00243 {
00244 boost::mutex::scoped_lock buff_lock (bmutex_);
00245 buffer_.clear ();
00246 }
00247
00248 private:
00249 Buffer (const Buffer&);
00250 Buffer& operator =(const Buffer&);
00251
00252 boost::mutex bmutex_;
00253 boost::condition_variable buff_empty_;
00254 boost::circular_buffer<Frame::ConstPtr> buffer_;
00255 };
00256
00258 class Writer
00259 {
00260 private:
00262 void
00263 writeToDisk (const Frame::ConstPtr& frame)
00264 {
00265 if (!frame)
00266 return;
00267
00268 FPS_CALC_WRITER ("data write ", buf_);
00269 nr_frames_total++;
00270
00271 stringstream ss1, ss2, ss3;
00272
00273 string time_string = boost::posix_time::to_iso_string (frame->time);
00274
00275 ss1 << "frame_" << time_string << "_rgb.pclzf";
00276 switch (frame->image->getEncoding ())
00277 {
00278 case openni_wrapper::Image::YUV422:
00279 {
00280 io::LZFYUV422ImageWriter lrgb;
00281 lrgb.write (reinterpret_cast<const char*> (&frame->image->getMetaData ().Data ()[0]), frame->image->getWidth (), frame->image->getHeight (), ss1.str ());
00282 break;
00283 }
00284 case openni_wrapper::Image::RGB:
00285 {
00286 io::LZFRGB24ImageWriter lrgb;
00287 lrgb.write (reinterpret_cast<const char*> (&frame->image->getMetaData ().Data ()[0]), frame->image->getWidth (), frame->image->getHeight (), ss1.str ());
00288 break;
00289 }
00290 case openni_wrapper::Image::BAYER_GRBG:
00291 {
00292 io::LZFBayer8ImageWriter lrgb;
00293 lrgb.write (reinterpret_cast<const char*> (&frame->image->getMetaData ().Data ()[0]), frame->image->getWidth (), frame->image->getHeight (), ss1.str ());
00294 break;
00295 }
00296 }
00297
00298
00299 ss2 << "frame_" + time_string + "_depth.pclzf";
00300 io::LZFDepth16ImageWriter ld;
00301
00302 ld.write (reinterpret_cast<const char*> (&frame->depth_image->getDepthMetaData ().Data ()[0]), frame->depth_image->getWidth (), frame->depth_image->getHeight (), ss2.str ());
00303
00304
00305 ss3 << "frame_" << time_string << ".xml";
00306
00307 io::LZFRGB24ImageWriter lrgb;
00308 lrgb.writeParameters (frame->parameters_rgb, ss3.str ());
00309 ld.writeParameters (frame->parameters_depth, ss3.str ());
00310
00311
00312
00313
00314 toggle_one_frame_capture = false;
00315 }
00316
00318 void
00319 receiveAndProcess ()
00320 {
00321 while (!is_done)
00322 {
00323 if (save_data || toggle_one_frame_capture)
00324 writeToDisk (buf_.popFront ());
00325 else
00326 boost::this_thread::sleep (boost::posix_time::microseconds (100));
00327 }
00328
00329 if (save_data && buf_.getSize () > 0)
00330 {
00331 {
00332 boost::mutex::scoped_lock io_lock (io_mutex);
00333 print_info ("Writing remaing %ld clouds in the buffer to disk...\n", buf_.getSize ());
00334 }
00335 while (!buf_.isEmpty ())
00336 {
00337 {
00338 boost::mutex::scoped_lock io_lock (io_mutex);
00339 print_info ("Clearing buffer... %ld remaining...\n", buf_.getSize ());
00340 }
00341 writeToDisk (buf_.popFront ());
00342 }
00343 }
00344 }
00345
00346 public:
00347 Writer (Buffer &buf)
00348 : buf_ (buf)
00349 {
00350 thread_.reset (new boost::thread (boost::bind (&Writer::receiveAndProcess, this)));
00351 }
00352
00354 void
00355 stop ()
00356 {
00357 thread_->join ();
00358 boost::mutex::scoped_lock io_lock (io_mutex);
00359 print_highlight ("Writer done.\n");
00360 }
00361
00362 private:
00363 Buffer &buf_;
00364 boost::shared_ptr<boost::thread> thread_;
00365 };
00366
00367
00369 class Driver
00370 {
00371 private:
00373 void
00374 image_callback (const boost::shared_ptr<openni_wrapper::Image> &image,
00375 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image,
00376 float)
00377 {
00378 boost::posix_time::ptime time = boost::posix_time::microsec_clock::local_time ();
00379 FPS_CALC_DRIVER ("driver ", buf_write_, buf_vis_);
00380
00381
00382 io::CameraParameters parameters_rgb;
00383 parameters_rgb.focal_length_x = parameters_rgb.focal_length_y = grabber_.getDevice ()->getImageFocalLength (depth_image->getWidth ());
00384 parameters_rgb.principal_point_x = image->getWidth () >> 1;
00385 parameters_rgb.principal_point_y = image->getHeight () >> 1;
00386
00387 io::CameraParameters parameters_depth;
00388 parameters_depth.focal_length_x = parameters_depth.focal_length_y = grabber_.getDevice ()->getDepthFocalLength (depth_image->getWidth ());
00389 parameters_depth.principal_point_x = depth_image->getWidth () >> 1;
00390 parameters_depth.principal_point_y = depth_image->getHeight () >> 1;
00391
00392
00393 Frame::ConstPtr frame (new Frame (image, depth_image,
00394 parameters_rgb, parameters_depth,
00395 time));
00396
00397 if ((save_data || toggle_one_frame_capture) && !buf_write_.pushBack (frame))
00398 {
00399 boost::mutex::scoped_lock io_lock (io_mutex);
00400 print_warn ("Warning! Write buffer was full, overwriting data!\n");
00401 }
00402
00403 if (global_visualize && visualize && !buf_vis_.pushBack (frame))
00404 {
00405 boost::mutex::scoped_lock io_lock (io_mutex);
00406 print_warn ("Warning! Visualization buffer was full, overwriting data!\n");
00407 }
00408 }
00409
00411 void
00412 grabAndSend ()
00413 {
00414 boost::function<void (const boost::shared_ptr<openni_wrapper::Image>&, const boost::shared_ptr<openni_wrapper::DepthImage>&, float) > image_cb = boost::bind (&Driver::image_callback, this, _1, _2, _3);
00415 boost::signals2::connection image_connection = grabber_.registerCallback (image_cb);
00416
00417 grabber_.start ();
00418
00419 while (!is_done)
00420 {
00421 boost::this_thread::sleep (boost::posix_time::seconds (1));
00422 }
00423 grabber_.stop ();
00424 image_connection.disconnect ();
00425 }
00426
00427 public:
00428 Driver (OpenNIGrabber& grabber, Buffer &buf_write, Buffer &buf_vis)
00429 : grabber_ (grabber)
00430 , buf_write_ (buf_write)
00431 , buf_vis_ (buf_vis)
00432 {
00433 thread_.reset (new boost::thread (boost::bind (&Driver::grabAndSend, this)));
00434 }
00435
00437 void
00438 stop ()
00439 {
00440 thread_->join ();
00441 boost::mutex::scoped_lock io_lock (io_mutex);
00442 print_highlight ("Grabber done.\n");
00443 }
00444
00445 private:
00446
00447 OpenNIGrabber& grabber_;
00448 Buffer &buf_write_, &buf_vis_;
00449 boost::shared_ptr<boost::thread> thread_;
00450 };
00451
00453 class Viewer
00454 {
00455 private:
00457 void
00458 receiveAndView ()
00459 {
00460 string mouseMsg2D ("Mouse coordinates in image viewer");
00461 string keyMsg2D ("Key event for image viewer");
00462
00463 image_viewer_->registerMouseCallback (&Viewer::mouse_callback, *this, static_cast<void*> (&mouseMsg2D));
00464 image_viewer_->registerKeyboardCallback(&Viewer::keyboard_callback, *this, static_cast<void*> (&keyMsg2D));
00465 depth_image_viewer_->registerMouseCallback (&Viewer::mouse_callback, *this, static_cast<void*> (&mouseMsg2D));
00466 depth_image_viewer_->registerKeyboardCallback(&Viewer::keyboard_callback, *this, static_cast<void*> (&keyMsg2D));
00467
00468
00469 if (!image_cld_init_)
00470 {
00471 image_viewer_->setPosition (0, 0);
00472 image_cld_init_ = !image_cld_init_;
00473 }
00474
00475
00476 while (!image_viewer_->wasStopped () &&
00477 !depth_image_viewer_->wasStopped () &&
00478 !is_done)
00479 {
00480 boost::this_thread::sleep (boost::posix_time::microseconds (100));
00481
00482 if (!visualize)
00483 {
00484 image_viewer_->spinOnce ();
00485 depth_image_viewer_->spinOnce ();
00486 continue;
00487 }
00488
00489 while (!buf_.isEmpty () && !is_done)
00490 {
00491 Frame::ConstPtr frame = buf_.popFront ();
00492
00493 FPS_CALC_VIEWER ("visualization", buf_);
00494
00495 if (frame->image)
00496 {
00497
00498 static vector<unsigned char> rgb_data (frame->image->getWidth () * frame->image->getHeight () * 3);
00499 if (frame->image->getEncoding () != openni_wrapper::Image::RGB)
00500 {
00501 frame->image->fillRGB (frame->image->getWidth (),
00502 frame->image->getHeight (),
00503 &rgb_data[0]);
00504 }
00505 else
00506 memcpy (&rgb_data[0],
00507 frame->image->getMetaData ().Data (),
00508 rgb_data.size ());
00509
00510 image_viewer_->addRGBImage (reinterpret_cast<unsigned char*> (&rgb_data[0]),
00511 frame->image->getWidth (),
00512 frame->image->getHeight ());
00513 }
00514
00515 if (frame->depth_image)
00516 {
00517 unsigned char* data = visualization::FloatImageUtils::getVisualImage (
00518 reinterpret_cast<const unsigned short*> (&frame->depth_image->getDepthMetaData ().Data ()[0]),
00519 frame->depth_image->getWidth (), frame->depth_image->getHeight (),
00520 numeric_limits<unsigned short>::min (),
00521
00522 numeric_limits<unsigned short>::max () / 10,
00523 true);
00524
00525 depth_image_viewer_->addRGBImage (data,
00526 frame->depth_image->getWidth (),
00527 frame->depth_image->getHeight ());
00528 if (!depth_image_cld_init_)
00529 {
00530 depth_image_viewer_->setPosition (frame->depth_image->getWidth (), 0);
00531 depth_image_cld_init_ = !depth_image_cld_init_;
00532 }
00533 delete[] data;
00534 }
00535 image_viewer_->spinOnce ();
00536 depth_image_viewer_->spinOnce ();
00537 }
00538 }
00539 }
00540
00541 public:
00543 Viewer (Buffer &buf)
00544 : buf_ (buf)
00545 , image_cld_init_ (false), depth_image_cld_init_ (false)
00546 {
00547 image_viewer_.reset (new visualization::ImageViewer ("PCL/OpenNI RGB image viewer"));
00548 depth_image_viewer_.reset (new visualization::ImageViewer ("PCL/OpenNI depth image viewer"));
00549
00550 receiveAndView ();
00551 }
00552
00554 void
00555 stop ()
00556 {
00557 boost::mutex::scoped_lock io_lock (io_mutex);
00558 print_highlight ("Viewer done.\n");
00559 }
00560
00562 void
00563 keyboard_callback (const visualization::KeyboardEvent& event, void*)
00564 {
00565
00566 if (event.getKeySym () == "space")
00567 {
00568 if (event.keyDown ())
00569 {
00570 save_data = !save_data;
00571 PCL_INFO ("Toggled recording state: %s.\n", save_data ? "enabled" : "disabled");
00572 }
00573 return;
00574 }
00575
00576
00577 if (event.getKeyCode () == 'v' && event.keyDown ())
00578 {
00579 visualize = !visualize;
00580 if (!visualize)
00581 buf_.clear ();
00582 PCL_INFO ("Visualization state: %s.\n", (visualize ? "on" : "off"));
00583 return;
00584 }
00585
00586
00587 if (event.getKeyCode () == 's' && event.keyDown ())
00588 {
00589 toggle_one_frame_capture = true;
00590 PCL_INFO ("Toggled single frame capture state.\n");
00591 return;
00592 }
00593
00594
00595 if (event.getKeyCode () == 'q')
00596 {
00597 is_done = true;
00598 return;
00599 }
00600 }
00601
00603 void
00604 mouse_callback (const visualization::MouseEvent& mouse_event, void*)
00605 {
00606 if (mouse_event.getType () == visualization::MouseEvent::MouseButtonPress && mouse_event.getButton () == visualization::MouseEvent::LeftButton)
00607 {
00608 toggle_one_frame_capture = true;
00609 PCL_INFO ("Toggled single frame capture state.\n");
00610 }
00611 }
00612
00613 Buffer &buf_;
00614 boost::shared_ptr<visualization::ImageViewer> image_viewer_;
00615 boost::shared_ptr<visualization::ImageViewer> depth_image_viewer_;
00616 bool image_cld_init_, depth_image_cld_init_;
00617 };
00618
00619 void
00620 usage (char ** argv)
00621 {
00622 cout << "usage: " << argv[0] << " [(<device_id> [-visualize | -imagemode <mode>] | [-depthmode <mode>] | [-depthformat <format>] | -l [<device_id>]| -h | --help)]\n";
00623 cout << argv[0] << " -h | --help : shows this help\n";
00624 cout << argv[0] << " -l : list all available devices\n";
00625 cout << argv[0] << " -buf X : use a buffer size of X frames (default: " << buff_size << ")\n";
00626 cout << argv[0] << " -visualize 0/1 : turn the visualization off/on (WARNING: when visualization is disabled, data writing is enabled by default!)\n";
00627 cout << argv[0] << " -l <device-id> : list all available modes for specified device\n";
00628
00629 cout << " device_id may be #1, #2, ... for the first, second etc device in the list"
00630 #ifndef _WIN32
00631 << " or" << endl
00632 << " bus@address for the device connected to a specific usb-bus / address combination or" << endl
00633 << " <serial-number>"
00634 #endif
00635 << endl;
00636 cout << endl;
00637 cout << "examples:" << endl;
00638 cout << argv[0] << " \"#1\"" << endl;
00639 cout << " uses the first device." << endl;
00640 cout << argv[0] << " -l" << endl;
00641 cout << " lists all available devices." << endl;
00642 cout << argv[0] << " -l \"#2\"" << endl;
00643 cout << " lists all available modes for the second device" << endl;
00644 #ifndef _WIN32
00645 cout << argv[0] << " A00361800903049A" << endl;
00646 cout << " uses the device with the serial number \'A00361800903049A\'." << endl;
00647 cout << argv[0] << " 1@16" << endl;
00648 cout << " uses the device on address 16 at USB bus 1." << endl;
00649 #endif
00650 }
00651
00653 void
00654 ctrlC (int)
00655 {
00656 boost::mutex::scoped_lock io_lock (io_mutex);
00657 print_info ("\nCtrl-C detected, exit condition set to true.\n");
00658 is_done = true;
00659 }
00660
00662 int
00663 main (int argc, char ** argv)
00664 {
00665 print_highlight ("PCL OpenNI Image Viewer/Recorder. See %s -h for options.\n", argv[0]);
00666 bool debug = false;
00667 console::parse_argument (argc, argv, "-debug", debug);
00668 if (debug)
00669 console::setVerbosityLevel (console::L_DEBUG);
00670
00671 if (parse_argument (argc, argv, "-buf", buff_size) != -1)
00672 print_highlight ("Setting buffer size to %d frames.\n", buff_size);
00673 else
00674 print_highlight ("Using default buffer size of %d frames.\n", buff_size);
00675
00676 string device_id ("");
00677 OpenNIGrabber::Mode image_mode = OpenNIGrabber::OpenNI_Default_Mode;
00678 OpenNIGrabber::Mode depth_mode = OpenNIGrabber::OpenNI_Default_Mode;
00679
00680 if (argc >= 2)
00681 {
00682 device_id = argv[1];
00683 if (device_id == "--help" || device_id == "-h")
00684 {
00685 usage (argv);
00686 return (0);
00687 }
00688 else if (device_id == "-l")
00689 {
00690 if (argc >= 3)
00691 {
00692 OpenNIGrabber grabber (argv[2]);
00693 boost::shared_ptr<openni_wrapper::OpenNIDevice> device = grabber.getDevice ();
00694 vector<pair<int, XnMapOutputMode> > modes;
00695
00696 if (device->hasImageStream ())
00697 {
00698 cout << endl << "Supported image modes for device: " << device->getVendorName () << " , " << device->getProductName () << endl;
00699 modes = grabber.getAvailableImageModes ();
00700 for (vector<pair<int, XnMapOutputMode> >::const_iterator it = modes.begin (); it != modes.end (); ++it)
00701 {
00702 cout << it->first << " = " << it->second.nXRes << " x " << it->second.nYRes << " @ " << it->second.nFPS << endl;
00703 }
00704 if (device->hasDepthStream ())
00705 {
00706 cout << endl << "Supported depth modes for device: " << device->getVendorName () << " , " << device->getProductName () << endl;
00707 modes = grabber.getAvailableDepthModes ();
00708 for (vector<pair<int, XnMapOutputMode> >::const_iterator it = modes.begin (); it != modes.end (); ++it)
00709 {
00710 cout << it->first << " = " << it->second.nXRes << " x " << it->second.nYRes << " @ " << it->second.nFPS << endl;
00711 }
00712 }
00713 }
00714 }
00715 else
00716 {
00717 openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00718 if (driver.getNumberDevices () > 0)
00719 {
00720 for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00721 {
00722 cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00723 << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00724 }
00725
00726 }
00727 else
00728 cout << "No devices connected." << endl;
00729
00730 cout <<"Virtual Devices available: ONI player" << endl;
00731 }
00732 return (0);
00733 }
00734 }
00735 else
00736 {
00737 openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00738 if (driver.getNumberDevices() > 0)
00739 cout << "Device Id not set, using first device." << endl;
00740 }
00741
00742 unsigned mode;
00743 if (console::parse (argc, argv, "-imagemode", mode) != -1)
00744 image_mode = static_cast<OpenNIGrabber::Mode> (mode);
00745 if (console::parse (argc, argv, "-depthmode", mode) != -1)
00746 depth_mode = static_cast<OpenNIGrabber::Mode> (mode);
00747
00748 int depthformat = openni_wrapper::OpenNIDevice::OpenNI_12_bit_depth;
00749 console::parse_argument (argc, argv, "-depthformat", depthformat);
00750 console::parse_argument (argc, argv, "-visualize", global_visualize);
00751
00752 OpenNIGrabber ni_grabber (device_id, depth_mode, image_mode);
00753
00754 ni_grabber.getDevice ()->setDepthOutputFormat (static_cast<openni_wrapper::OpenNIDevice::DepthMode> (depthformat));
00755
00756
00757
00758
00759 Buffer buf_write, buf_vis;
00760 buf_write.setCapacity (buff_size);
00761 buf_vis.setCapacity (buff_size);
00762
00763 signal (SIGINT, ctrlC);
00764
00765 Driver driver (ni_grabber, buf_write, buf_vis);
00766 Writer writer (buf_write);
00767 boost::shared_ptr<Viewer> viewer;
00768 if (global_visualize)
00769 viewer.reset (new Viewer (buf_vis));
00770 else
00771 save_data = true;
00772
00773
00774 driver.stop ();
00775 if (global_visualize)
00776 viewer->stop ();
00777 writer.stop ();
00778
00779 print_highlight ("Total number of frames written: %d.\n", nr_frames_total);
00780 return (0);
00781 }