astra_device.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Willow Garage, Inc.
3  * Copyright (c) 2016, Orbbec Ltd.
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * * Neither the name of the Willow Garage, Inc. nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  *
30  * Author: Tim Liu (liuhua@orbbec.com)
31  */
32 
33 #include "openni2/OpenNI.h"
34 
35 #include <boost/lexical_cast.hpp>
36 #include <boost/algorithm/string/replace.hpp>
37 
43 
44 #include "openni2/PS1080.h"
45 
46 #include <boost/shared_ptr.hpp>
47 #include <boost/make_shared.hpp>
48 
49 #include <string>
50 #include <cmath>
51 
52 namespace astra_wrapper
53 {
54 
55 AstraDevice::AstraDevice(const std::string& device_URI):
56  openni_device_(),
57  ir_video_started_(false),
58  color_video_started_(false),
59  depth_video_started_(false),
60  image_registration_activated_(false),
61  use_device_time_(false)
62 {
64  if (rc != openni::STATUS_OK)
65  THROW_OPENNI_EXCEPTION("Initialize failed\n%s\n", openni::OpenNI::getExtendedError());
66 
67  openni_device_ = boost::make_shared<openni::Device>();
68 
69  if (device_URI.length() > 0)
70  {
71  rc = openni_device_->open(device_URI.c_str());
72  }
73  else
74  {
76  }
77 
78  if (rc != openni::STATUS_OK)
79  THROW_OPENNI_EXCEPTION("Device open failed\n%s\n", openni::OpenNI::getExtendedError());
80 
81  device_info_ = boost::make_shared<openni::DeviceInfo>();
82  *device_info_ = openni_device_->getDeviceInfo();
83 
84  int param_size = sizeof(OBCameraParams);
86  m_ParamsValid = true;
87  if (std::isnan(m_CamParams.l_intr_p[0]) || std::isnan(m_CamParams.l_intr_p[1]) ||
88  std::isnan(m_CamParams.l_intr_p[2]) || std::isnan(m_CamParams.l_intr_p[3]))
89  {
90  m_ParamsValid = false;
91  }
92 
93  int serial_number_size = sizeof(serial_number);
94  memset(serial_number, 0, serial_number_size);
95  openni_device_->getProperty(openni::OBEXTENSION_ID_SERIALNUMBER, (uint8_t*)&serial_number, &serial_number_size);
96 
97  int device_type_size = sizeof(device_type);
98  memset(device_type, 0, device_type_size);
99  openni_device_->getProperty(openni::OBEXTENSION_ID_DEVICETYPE, (uint8_t*)&device_type, &device_type_size);
100  if (strcmp(device_type, OB_STEREO_S) == 0)
101  {
103  }
104  else if (strcmp(device_type, OB_EMBEDDED_S) == 0)
105  {
107  }
108  else if (strcmp(device_type, OB_STEREO_S_U3) == 0)
109  {
111  }
112  else if (strcmp(device_type, OB_ASTRA_PRO) == 0)
113  {
115  }
116  else
117  {
119  }
120 
121  ir_frame_listener = boost::make_shared<AstraFrameListener>();
122  color_frame_listener = boost::make_shared<AstraFrameListener>();
123  depth_frame_listener = boost::make_shared<AstraFrameListener>();
124 
125 }
126 
128 {
129  stopAllStreams();
130 
131  shutdown();
132 
133  openni_device_->close();
134 }
135 
136 const std::string AstraDevice::getUri() const
137 {
138  return std::string(device_info_->getUri());
139 }
140 
141 const std::string AstraDevice::getVendor() const
142 {
143  return std::string(device_info_->getVendor());
144 }
145 
146 const std::string AstraDevice::getName() const
147 {
148  return std::string(device_info_->getName());
149 }
150 
152 {
153  return device_info_->getUsbVendorId();
154 }
155 
157 {
158  return device_info_->getUsbProductId();
159 }
160 
161 const std::string AstraDevice::getStringID() const
162 {
163  std::string ID_str = getName() + "_" + getVendor();
164 
165  boost::replace_all(ID_str, "/", "");
166  boost::replace_all(ID_str, ".", "");
167  boost::replace_all(ID_str, "@", "");
168 
169  return ID_str;
170 }
171 
173 {
174  return (openni_device_.get() != 0) && openni_device_->isValid();
175 }
176 
178 {
179  return m_CamParams;
180 }
181 
183 {
184  return m_ParamsValid;
185 }
186 
188 {
189  return serial_number;
190 }
191 
193 {
194  return device_type;
195 }
196 
198 {
199  return device_type_no;
200 }
201 
203 {
204  int gain = 0;
205  int data_size = 4;
206  openni_device_->getProperty(openni::OBEXTENSION_ID_IR_GAIN, (uint8_t*)&gain, &data_size);
207  return gain;
208 }
209 
211 {
212  int exposure = 0;
213  int data_size = 4;
214  openni_device_->getProperty(openni::OBEXTENSION_ID_IR_EXP, (uint8_t*)&exposure, &data_size);
215  return exposure;
216 }
217 
219 {
220  int data_size = sizeof(OBCameraParams);
221  openni_device_->setProperty(openni::OBEXTENSION_ID_CAM_PARAMS, (uint8_t*)&param, data_size);
222 }
223 
225 {
226  int data_size = 4;
227  openni_device_->setProperty(openni::OBEXTENSION_ID_IR_GAIN, (uint8_t*)&gain, data_size);
228 }
229 
230 void AstraDevice::setIRExposure(int exposure)
231 {
232  int data_size = 4;
233  openni_device_->setProperty(openni::OBEXTENSION_ID_IR_EXP, (uint8_t*)&exposure, data_size);
234 }
235 
236 void AstraDevice::setLaser(bool enable)
237 {
238  int data_size = 4;
239  int laser_enable = 1;
240  if (enable == false)
241  {
242  laser_enable = 0;
243  }
244  openni_device_->setProperty(openni::OBEXTENSION_ID_LASER_EN, (uint8_t*)&laser_enable, data_size);
245 }
246 
247 void AstraDevice::setIRFlood(bool enable)
248 {
249  int data_size = 4;
250  int enable_ = 1;
251  if (enable == false)
252  {
253  enable_ = 0;
254  }
255  openni_device_->setProperty(XN_MODULE_PROPERTY_IRFLOOD_STATE, enable_);
256 }
257 
258 void AstraDevice::setLDP(bool enable)
259 {
260  int data_size = 4;
261  int enable_ = 1;
262  if (enable == false)
263  {
264  enable_ = 0;
265  }
267  {
268  openni_device_->setProperty(XN_MODULE_PROPERTY_LDP_ENABLE, (uint8_t *)&enable_, 4);
269  }
270  else
271  {
274  depth_stream->stop();
275  ir_stream->stop();
276  openni_device_->setProperty(openni::OBEXTENSION_ID_LDP_EN, (uint8_t *)&enable_, 4);
277  depth_stream->start();
278  ir_stream->start();
279  }
280 }
281 
283 {
285  {
286  openni_device_->setProperty(XN_MODULE_PROPERTY_SWITCH_IR, (uint8_t*)&cam, 4);
287  }
288 }
289 
290 float AstraDevice::getIRFocalLength(int output_y_resolution) const
291 {
292  float focal_length = 0.0f;
294 
295  if (stream)
296  {
297  focal_length = (float)output_y_resolution / (2 * tan(stream->getVerticalFieldOfView() / 2));
298  }
299 
300  return focal_length;
301 }
302 
303 float AstraDevice::getColorFocalLength(int output_y_resolution) const
304 {
305  float focal_length = 0.0f;
307 
308  if (stream)
309  {
310  focal_length = (float)output_y_resolution / (2 * tan(stream->getVerticalFieldOfView() / 2));
311  }
312 
313  return focal_length;
314 }
315 
316 float AstraDevice::getDepthFocalLength(int output_y_resolution) const
317 {
318  float focal_length = 0.0f;
320 
321  if (stream)
322  {
323  focal_length = (float)output_y_resolution / (2 * tan(stream->getVerticalFieldOfView() / 2));
324  }
325 
326  return focal_length;
327 }
328 
330 {
331  return 0.075f;
332 }
333 
335 {
337 
338  bool supported = false;
339 
340  std::vector<AstraVideoMode>::const_iterator it = ir_video_modes_.begin();
341  std::vector<AstraVideoMode>::const_iterator it_end = ir_video_modes_.end();
342 
343  while (it != it_end && !supported)
344  {
345  supported = (*it == video_mode);
346  ++it;
347  }
348 
349  return supported;
350 }
351 
353 {
355 
356  bool supported = false;
357 
358  std::vector<AstraVideoMode>::const_iterator it = color_video_modes_.begin();
359  std::vector<AstraVideoMode>::const_iterator it_end = color_video_modes_.end();
360 
361  while (it != it_end && !supported)
362  {
363  supported = (*it == video_mode);
364  ++it;
365  }
366 
367  return supported;
368 }
369 
371 {
373 
374  bool supported = false;
375 
376  std::vector<AstraVideoMode>::const_iterator it = depth_video_modes_.begin();
377  std::vector<AstraVideoMode>::const_iterator it_end = depth_video_modes_.end();
378 
379  while (it != it_end && !supported)
380  {
381  supported = (*it == video_mode);
382  ++it;
383  }
384 
385  return supported;
386 
387 }
388 
390 {
391  return openni_device_->hasSensor(openni::SENSOR_IR);
392 }
393 
395 {
396  return (getUsbProductId()!=0x0403)?openni_device_->hasSensor(openni::SENSOR_COLOR):0;
397 }
398 
400 {
401  return openni_device_->hasSensor(openni::SENSOR_DEPTH);
402 }
403 
405 {
407 
408  if (stream)
409  {
410  stream->setMirroringEnabled(false);
411  stream->start();
412  stream->addNewFrameListener(ir_frame_listener.get());
413  ir_video_started_ = true;
414  }
415 
416 }
417 
419 {
421 
422  if (stream)
423  {
424  stream->setMirroringEnabled(false);
425  stream->start();
426  stream->addNewFrameListener(color_frame_listener.get());
427  color_video_started_ = true;
428  }
429 }
431 {
433 
434  if (stream)
435  {
436  stream->setMirroringEnabled(false);
437  stream->start();
438  stream->addNewFrameListener(depth_frame_listener.get());
439  depth_video_started_ = true;
440  }
441 }
442 
444 {
445  stopIRStream();
446  stopColorStream();
447  stopDepthStream();
448 }
449 
451 {
452  if (ir_video_stream_.get() != 0)
453  {
454  ir_video_started_ = false;
455 
456  ir_video_stream_->removeNewFrameListener(ir_frame_listener.get());
457 
458  ir_video_stream_->stop();
459  }
460 }
462 {
463  if (color_video_stream_.get() != 0)
464  {
465  color_video_started_ = false;
466 
467  color_video_stream_->removeNewFrameListener(color_frame_listener.get());
468 
469  color_video_stream_->stop();
470  }
471 }
473 {
474  if (depth_video_stream_.get() != 0)
475  {
476  depth_video_started_ = false;
477 
478  depth_video_stream_->removeNewFrameListener(depth_frame_listener.get());
479 
480  depth_video_stream_->stop();
481  }
482 }
483 
485 {
486  if (ir_video_stream_.get() != 0)
487  ir_video_stream_->destroy();
488 
489  if (color_video_stream_.get() != 0)
490  color_video_stream_->destroy();
491 
492  if (depth_video_stream_.get() != 0)
493  depth_video_stream_->destroy();
494 
495 }
496 
498 {
499  return ir_video_started_;
500 }
502 {
503  return color_video_started_;
504 }
506 {
507  return depth_video_started_;
508 }
509 
510 const std::vector<AstraVideoMode>& AstraDevice::getSupportedIRVideoModes() const
511 {
513 
514  ir_video_modes_.clear();
515 
516  if (stream)
517  {
518  const openni::SensorInfo& sensor_info = stream->getSensorInfo();
519 
521  }
522 
523  return ir_video_modes_;
524 }
525 
526 const std::vector<AstraVideoMode>& AstraDevice::getSupportedColorVideoModes() const
527 {
529 
530  color_video_modes_.clear();
531 
532  if (stream)
533  {
534  const openni::SensorInfo& sensor_info = stream->getSensorInfo();
535 
537  }
538 
539  return color_video_modes_;
540 }
541 
542 const std::vector<AstraVideoMode>& AstraDevice::getSupportedDepthVideoModes() const
543 {
545 
546  depth_video_modes_.clear();
547 
548  if (stream)
549  {
550  const openni::SensorInfo& sensor_info = stream->getSensorInfo();
551 
553  }
554 
555  return depth_video_modes_;
556 }
557 
559 {
560  return openni_device_->isImageRegistrationModeSupported(openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR);
561 }
562 
564 {
566  {
568  if (enabled)
569  {
571  if (rc != openni::STATUS_OK)
572  THROW_OPENNI_EXCEPTION("Enabling image registration mode failed: \n%s\n", openni::OpenNI::getExtendedError());
573  }
574  else
575  {
576  openni::Status rc = openni_device_->setImageRegistrationMode(openni::IMAGE_REGISTRATION_OFF);
577  if (rc != openni::STATUS_OK)
578  THROW_OPENNI_EXCEPTION("Enabling image registration mode failed: \n%s\n", openni::OpenNI::getExtendedError());
579  }
580  }
581 }
582 
584 {
585  openni::Status rc = openni_device_->setDepthColorSyncEnabled(enabled);
586  if (rc != openni::STATUS_OK)
587  THROW_OPENNI_EXCEPTION("Enabling depth color synchronization failed: \n%s\n", openni::OpenNI::getExtendedError());
588 }
589 
591 {
592  AstraVideoMode ret;
593 
595 
596  if (stream)
597  {
598  openni::VideoMode video_mode = stream->getVideoMode();
599 
600  ret = astra_convert(video_mode);
601  }
602  else
603  THROW_OPENNI_EXCEPTION("Could not create video stream.");
604 
605  return ret;
606 }
607 
609 {
610  AstraVideoMode ret;
611 
613 
614  if (stream)
615  {
616  openni::VideoMode video_mode = stream->getVideoMode();
617 
618  ret = astra_convert(video_mode);
619  }
620  else
621  THROW_OPENNI_EXCEPTION("Could not create video stream.");
622 
623  return ret;
624 }
625 
627 {
628  AstraVideoMode ret;
629 
631 
632  if (stream)
633  {
634  openni::VideoMode video_mode = stream->getVideoMode();
635 
636  ret = astra_convert(video_mode);
637  }
638  else
639  THROW_OPENNI_EXCEPTION("Could not create video stream.");
640 
641  return ret;
642 }
643 
645 {
647 
648  if (stream)
649  {
650  const openni::VideoMode videoMode = astra_convert(video_mode);
651  const openni::Status rc = stream->setVideoMode(videoMode);
652  if (rc != openni::STATUS_OK)
653  THROW_OPENNI_EXCEPTION("Couldn't set IR video mode: \n%s\n", openni::OpenNI::getExtendedError());
654  }
655 }
656 
658 {
660 
661  if (stream)
662  {
663  const openni::VideoMode videoMode = astra_convert(video_mode);
664  const openni::Status rc = stream->setVideoMode(videoMode);
665  if (rc != openni::STATUS_OK)
666  THROW_OPENNI_EXCEPTION("Couldn't set color video mode: \n%s\n", openni::OpenNI::getExtendedError());
667  }
668 }
669 
671 {
673 
674  if (stream)
675  {
676  const openni::VideoMode videoMode = astra_convert(video_mode);
677  const openni::Status rc = stream->setVideoMode(videoMode);
678  if (rc != openni::STATUS_OK)
679  THROW_OPENNI_EXCEPTION("Couldn't set depth video mode: \n%s\n", openni::OpenNI::getExtendedError());
680  }
681 }
682 
684 {
686 
687  if (stream)
688  {
689  openni::CameraSettings* camera_seeting = stream->getCameraSettings();
690  if (camera_seeting)
691  {
692  const openni::Status rc = camera_seeting->setAutoExposureEnabled(enable);
693  if (rc != openni::STATUS_OK)
694  THROW_OPENNI_EXCEPTION("Couldn't set auto exposure: \n%s\n", openni::OpenNI::getExtendedError());
695  }
696 
697  }
698 }
700 {
702 
703  if (stream)
704  {
705  openni::CameraSettings* camera_seeting = stream->getCameraSettings();
706  if (camera_seeting)
707  {
708  const openni::Status rc = camera_seeting->setAutoWhiteBalanceEnabled(enable);
709  if (rc != openni::STATUS_OK)
710  THROW_OPENNI_EXCEPTION("Couldn't set auto white balance: \n%s\n", openni::OpenNI::getExtendedError());
711  }
712 
713  }
714 }
715 
717 {
718  bool ret = false;
719 
721 
722  if (stream)
723  {
724  openni::CameraSettings* camera_seeting = stream->getCameraSettings();
725  if (camera_seeting)
726  ret = camera_seeting->getAutoExposureEnabled();
727  }
728 
729  return ret;
730 }
732 {
733  bool ret = false;
734 
736 
737  if (stream)
738  {
739  openni::CameraSettings* camera_seeting = stream->getCameraSettings();
740  if (camera_seeting)
741  ret = camera_seeting->getAutoWhiteBalanceEnabled();
742  }
743 
744  return ret;
745 }
746 
748 {
749  if (ir_frame_listener)
750  ir_frame_listener->setUseDeviceTimer(enable);
751 
753  color_frame_listener->setUseDeviceTimer(enable);
754 
756  depth_frame_listener->setUseDeviceTimer(enable);
757 }
758 
760 {
761  ir_frame_listener->setCallback(callback);
762 }
763 
765 {
766  color_frame_listener->setCallback(callback);
767 }
768 
770 {
771  depth_frame_listener->setCallback(callback);
772 }
773 
775 {
776  if (ir_video_stream_.get() == 0)
777  {
778  if (hasIRSensor())
779  {
780  ir_video_stream_ = boost::make_shared<openni::VideoStream>();
781 
783  if (rc != openni::STATUS_OK)
784  THROW_OPENNI_EXCEPTION("Couldn't create IR video stream: \n%s\n", openni::OpenNI::getExtendedError());
785  }
786  }
787  return ir_video_stream_;
788 }
789 
791 {
792  if (color_video_stream_.get() == 0)
793  {
794  if (hasColorSensor())
795  {
796  color_video_stream_ = boost::make_shared<openni::VideoStream>();
797 
799  if (rc != openni::STATUS_OK)
800  THROW_OPENNI_EXCEPTION("Couldn't create color video stream: \n%s\n", openni::OpenNI::getExtendedError());
801  }
802  }
803  return color_video_stream_;
804 }
805 
807 {
808  if (depth_video_stream_.get() == 0)
809  {
810  if (hasDepthSensor())
811  {
812  depth_video_stream_ = boost::make_shared<openni::VideoStream>();
813 
815  if (rc != openni::STATUS_OK)
816  THROW_OPENNI_EXCEPTION("Couldn't create depth video stream: \n%s\n", openni::OpenNI::getExtendedError());
817  }
818  }
819  return depth_video_stream_;
820 }
821 
822 std::ostream& operator <<(std::ostream& stream, const AstraDevice& device)
823 {
824 
825  stream << "Device info (" << device.getUri() << ")" << std::endl;
826  stream << " Vendor: " << device.getVendor() << std::endl;
827  stream << " Name: " << device.getName() << std::endl;
828  stream << " USB Vendor ID: " << device.getUsbVendorId() << std::endl;
829  stream << " USB Product ID: " << device.getUsbVendorId() << std::endl << std::endl;
830 
831  if (device.hasIRSensor())
832  {
833  stream << "IR sensor video modes:" << std::endl;
834  const std::vector<AstraVideoMode>& video_modes = device.getSupportedIRVideoModes();
835 
836  std::vector<AstraVideoMode>::const_iterator it = video_modes.begin();
837  std::vector<AstraVideoMode>::const_iterator it_end = video_modes.end();
838  for (; it != it_end; ++it)
839  stream << " - " << *it << std::endl;
840  }
841  else
842  {
843  stream << "No IR sensor available" << std::endl;
844  }
845 
846  if (device.hasColorSensor())
847  {
848  stream << "Color sensor video modes:" << std::endl;
849  const std::vector<AstraVideoMode>& video_modes = device.getSupportedColorVideoModes();
850 
851  std::vector<AstraVideoMode>::const_iterator it = video_modes.begin();
852  std::vector<AstraVideoMode>::const_iterator it_end = video_modes.end();
853  for (; it != it_end; ++it)
854  stream << " - " << *it << std::endl;
855  }
856  else
857  {
858  stream << "No Color sensor available" << std::endl;
859  }
860 
861  if (device.hasDepthSensor())
862  {
863  stream << "Depth sensor video modes:" << std::endl;
864  const std::vector<AstraVideoMode>& video_modes = device.getSupportedDepthVideoModes();
865 
866  std::vector<AstraVideoMode>::const_iterator it = video_modes.begin();
867  std::vector<AstraVideoMode>::const_iterator it_end = video_modes.end();
868  for (; it != it_end; ++it)
869  stream << " - " << *it << std::endl;
870  }
871  else
872  {
873  stream << "No Depth sensor available" << std::endl;
874  }
875 
876  return stream;
877 }
878 
879 }
void setDepthFrameCallback(FrameCallbackFunction callback)
void setDepthVideoMode(const AstraVideoMode &video_mode)
void setLaser(bool enable)
bool getAutoExposureEnabled() const
Definition: OpenNI.h:1900
struct OBCameraParams OBCameraParams
boost::shared_ptr< AstraFrameListener > ir_frame_listener
Definition: astra_device.h:165
Status setAutoWhiteBalanceEnabled(bool enabled)
Definition: OpenNI.h:1895
boost::shared_ptr< AstraFrameListener > depth_frame_listener
Definition: astra_device.h:167
void setUseDeviceTimer(bool enable)
boost::shared_ptr< openni::VideoStream > depth_video_stream_
Definition: astra_device.h:171
void setCameraParams(OBCameraParams param)
unsigned short uint16_t
void setIRFrameCallback(FrameCallbackFunction callback)
bool isImageRegistrationModeSupported() const
boost::shared_ptr< AstraFrameListener > color_frame_listener
Definition: astra_device.h:166
void setAutoExposure(bool enable)
float l_intr_p[4]
Definition: OniCTypes.h:87
bool isDepthVideoModeSupported(const AstraVideoMode &video_mode) const
float getColorFocalLength(int output_y_resolution) const
bool getAutoWhiteBalanceEnabled() const
Definition: OpenNI.h:1907
const std::string getName() const
boost::shared_ptr< openni::VideoStream > getColorVideoStream() const
std::vector< AstraVideoMode > ir_video_modes_
Definition: astra_device.h:173
#define THROW_OPENNI_EXCEPTION(format,...)
OBCameraParams m_CamParams
Definition: astra_device.h:185
unsigned char uint8_t
const AstraVideoMode getIRVideoMode()
void setColorVideoMode(const AstraVideoMode &video_mode)
std::vector< AstraVideoMode > color_video_modes_
Definition: astra_device.h:174
#define OB_EMBEDDED_S
Status
Definition: OniEnums.h:28
const std::vector< AstraVideoMode > & getSupportedColorVideoModes() const
void setColorFrameCallback(FrameCallbackFunction callback)
const AstraVideoMode getColorVideoMode()
static Status initialize()
Definition: OpenNI.h:2144
#define OB_STEREO_S
boost::shared_ptr< openni::VideoStream > color_video_stream_
Definition: astra_device.h:170
bool isIRVideoModeSupported(const AstraVideoMode &video_mode) const
AstraDevice(const std::string &device_URI)
const std::vector< AstraVideoMode > & getSupportedIRVideoModes() const
float getIRFocalLength(int output_y_resolution) const
const AstraVideoMode getDepthVideoMode()
static const char * getExtendedError()
Definition: OpenNI.h:2179
void setImageRegistrationMode(bool enabled)
boost::shared_ptr< openni::VideoStream > getIRVideoStream() const
Status setAutoExposureEnabled(bool enabled)
Definition: OpenNI.h:1891
const std::string getUri() const
void setIRFlood(bool enable)
void setLDP(bool enable)
boost::function< void(sensor_msgs::ImagePtr image)> FrameCallbackFunction
Definition: astra_device.h:64
boost::shared_ptr< openni::VideoStream > ir_video_stream_
Definition: astra_device.h:169
bool isColorVideoModeSupported(const AstraVideoMode &video_mode) const
OB_DEVICE_NO
std::ostream & operator<<(std::ostream &stream, const AstraDevice &device)
uint16_t getUsbVendorId() const
bool getAutoWhiteBalance() const
OBCameraParams getCameraParams() const
boost::shared_ptr< openni::VideoStream > getDepthVideoStream() const
uint16_t getUsbProductId() const
std::vector< AstraVideoMode > depth_video_modes_
Definition: astra_device.h:175
const std::vector< AstraVideoMode > & getSupportedDepthVideoModes() const
const std::string getVendor() const
void setIRExposure(int exposure)
#define OB_STEREO_S_U3
const std::string getStringID() const
float getDepthFocalLength(int output_y_resolution) const
boost::shared_ptr< openni::Device > openni_device_
Definition: astra_device.h:162
boost::shared_ptr< openni::DeviceInfo > device_info_
Definition: astra_device.h:163
const Array< VideoMode > & getSupportedVideoModes() const
Definition: OpenNI.h:348
const AstraDeviceInfo astra_convert(const openni::DeviceInfo *pInfo)
OB_DEVICE_NO getDeviceTypeNo()
#define OB_ASTRA_PRO
void setDepthColorSync(bool enabled)
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
void setAutoWhiteBalance(bool enable)
void setIRVideoMode(const AstraVideoMode &video_mode)
static const _NullString ANY_DEVICE
Definition: OpenNI.h:111


astra_camera
Author(s): Tim Liu
autogenerated on Wed Dec 16 2020 03:54:34