CameraOpenNI2.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
18 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
19 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
20 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
21 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
22 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
23 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
24 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
25 */
26 
28 #include <rtabmap/utilite/UTimer.h>
29 #include <rtabmap/utilite/UFile.h>
31 #include <rtabmap/core/util2d.h>
32 #include <opencv2/imgproc/types_c.h>
33 
34 #ifdef RTABMAP_OPENNI2
35 #include <OniVersion.h>
36 #include <OpenNI.h>
37 #endif
38 
39 namespace rtabmap
40 {
41 
43 {
44 #ifdef RTABMAP_OPENNI2
45  return true;
46 #else
47  return false;
48 #endif
49 }
50 
52 {
53 #if ONI_VERSION_MAJOR > 2 || (ONI_VERSION_MAJOR==2 && ONI_VERSION_MINOR >= 2)
54  return true;
55 #else
56  return false;
57 #endif
58 }
59 
61  const std::string & deviceId,
62  Type type,
63  float imageRate,
64  const rtabmap::Transform & localTransform) :
65  Camera(imageRate, localTransform)
66 #ifdef RTABMAP_OPENNI2
67  ,
68  _type(type),
69  _device(new openni::Device()),
70  _color(new openni::VideoStream()),
71  _depth(new openni::VideoStream()),
72  _depthFx(0.0f),
73  _depthFy(0.0f),
74  _deviceId(deviceId),
75  _openNI2StampsAndIDsUsed(false),
76  _depthHShift(0),
77  _depthVShift(0)
78 #endif
79 {
80 }
81 
83 {
84 #ifdef RTABMAP_OPENNI2
85  _color->stop();
86  _color->destroy();
87  _depth->stop();
88  _depth->destroy();
89  _device->close();
90  openni::OpenNI::shutdown();
91 
92  delete _device;
93  delete _color;
94  delete _depth;
95 #endif
96 }
97 
99 {
100 #ifdef RTABMAP_OPENNI2
101  if(_color && _color->getCameraSettings())
102  {
103  return _color->getCameraSettings()->setAutoWhiteBalanceEnabled(enabled) == openni::STATUS_OK;
104  }
105 #else
106  UERROR("CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
107 #endif
108  return false;
109 }
110 
112 {
113 #ifdef RTABMAP_OPENNI2
114  if(_color && _color->getCameraSettings())
115  {
116  return _color->getCameraSettings()->setAutoExposureEnabled(enabled) == openni::STATUS_OK;
117  }
118 #else
119  UERROR("CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
120 #endif
121  return false;
122 }
123 
125 {
126 #ifdef RTABMAP_OPENNI2
127 #if ONI_VERSION_MAJOR > 2 || (ONI_VERSION_MAJOR==2 && ONI_VERSION_MINOR >= 2)
128  if(_color && _color->getCameraSettings())
129  {
130  return _color->getCameraSettings()->setExposure(value) == openni::STATUS_OK;
131  }
132 #else
133  UERROR("CameraOpenNI2: OpenNI >= 2.2 required to use this method.");
134 #endif
135 #else
136  UERROR("CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
137 #endif
138  return false;
139 }
140 
141 bool CameraOpenNI2::setGain(int value)
142 {
143 #ifdef RTABMAP_OPENNI2
144 #if ONI_VERSION_MAJOR > 2 || (ONI_VERSION_MAJOR==2 && ONI_VERSION_MINOR >= 2)
145  if(_color && _color->getCameraSettings())
146  {
147  return _color->getCameraSettings()->setGain(value) == openni::STATUS_OK;
148  }
149 #else
150  UERROR("CameraOpenNI2: OpenNI >= 2.2 required to use this method.");
151 #endif
152 #else
153  UERROR("CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
154 #endif
155  return false;
156 }
157 
158 bool CameraOpenNI2::setMirroring(bool enabled)
159 {
160 #ifdef RTABMAP_OPENNI2
161  if(_color->isValid() && _depth->isValid())
162  {
163  return _depth->setMirroringEnabled(enabled) == openni::STATUS_OK &&
164  _color->setMirroringEnabled(enabled) == openni::STATUS_OK;
165  }
166 #endif
167  return false;
168 }
169 
171 {
172 #ifdef RTABMAP_OPENNI2
173  _openNI2StampsAndIDsUsed = used;
174 #endif
175 }
176 
177 void CameraOpenNI2::setIRDepthShift(int horizontal, int vertical)
178 {
179 #ifdef RTABMAP_OPENNI2
180  UASSERT(horizontal >= 0);
181  UASSERT(vertical >= 0);
182  _depthHShift = horizontal;
183  _depthVShift = vertical;
184 #endif
185 }
186 
187 bool CameraOpenNI2::init(const std::string & calibrationFolder, const std::string & cameraName)
188 {
189 #ifdef RTABMAP_OPENNI2
190  openni::OpenNI::initialize();
191 
192  openni::Array<openni::DeviceInfo> devices;
193  openni::OpenNI::enumerateDevices(&devices);
194  for(int i=0; i<devices.getSize(); ++i)
195  {
196  UINFO("Device %d: Name=%s URI=%s Vendor=%s",
197  i,
198  devices[i].getName(),
199  devices[i].getUri(),
200  devices[i].getVendor());
201  }
202  if(_deviceId.empty() && devices.getSize() == 0)
203  {
204  UERROR("CameraOpenNI2: No device detected!");
205  return false;
206  }
207 
208  openni::Status error = _device->open(_deviceId.empty()?openni::ANY_DEVICE:_deviceId.c_str());
209  if(error != openni::STATUS_OK)
210  {
211  if(!_deviceId.empty())
212  {
213  UERROR("CameraOpenNI2: Cannot open device \"%s\" (error=%d).", _deviceId.c_str(), error);
214  }
215  else
216  {
217 #ifdef _WIN32
218  UERROR("CameraOpenNI2: Cannot open device \"%s\" (error=%d).", devices[0].getName(), error);
219 #else
220  UERROR("CameraOpenNI2: Cannot open device \"%s\" (error=%d). Verify if \"%s\" is in udev rules: \"/lib/udev/rules.d/40-libopenni2-0.rules\". If not, add it and reboot.", devices[0].getName(), error, devices[0].getUri());
221 #endif
222  }
223 
224  _device->close();
225  openni::OpenNI::shutdown();
226  return false;
227  }
228 
229  // look for calibration files
230  _stereoModel = StereoCameraModel();
231  bool hardwareRegistration = true;
232  if(!calibrationFolder.empty())
233  {
234  // we need the serial
235  std::string calibrationName = _device->getDeviceInfo().getName();
236  if(!cameraName.empty())
237  {
238  calibrationName = cameraName;
239  }
240  _stereoModel.setName(calibrationName, "depth", "rgb");
241  hardwareRegistration = !_stereoModel.load(calibrationFolder, calibrationName, false);
242 
243  if(_type != kTypeColorDepth)
244  {
245  hardwareRegistration = false;
246  }
247 
248 
249  if((_type != kTypeColorDepth && !_stereoModel.left().isValidForRectification()) ||
250  (_type == kTypeColorDepth && !_stereoModel.right().isValidForRectification()))
251  {
252  UWARN("Missing calibration files for camera \"%s\" in \"%s\" folder, default calibration used.",
253  calibrationName.c_str(), calibrationFolder.c_str());
254  }
255  else if(_type == kTypeColorDepth && _stereoModel.right().isValidForRectification() && hardwareRegistration)
256  {
257  UWARN("Missing extrinsic calibration file for camera \"%s\" in \"%s\" folder, default registration is used even if rgb is rectified!",
258  calibrationName.c_str(), calibrationFolder.c_str());
259  }
260  else if(_type == kTypeColorDepth && _stereoModel.right().isValidForRectification() && !hardwareRegistration)
261  {
262  UINFO("Custom calibration files for \"%s\" were found in \"%s\" folder. To use "
263  "factory calibration, remove the corresponding files from that directory.", calibrationName.c_str(), calibrationFolder.c_str());
264  }
265  }
266 
267  if(UFile::getExtension(_deviceId).compare("oni")==0)
268  {
269  if(_device->getPlaybackControl() &&
270  _device->getPlaybackControl()->setRepeatEnabled(false) != openni::STATUS_OK)
271  {
272  UERROR("CameraOpenNI2: Cannot set repeat mode to false.");
273  _device->close();
274  openni::OpenNI::shutdown();
275  return false;
276  }
277  }
278  else if(_type==kTypeColorDepth && hardwareRegistration &&
279  !_device->isImageRegistrationModeSupported(openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR))
280  {
281  UERROR("CameraOpenNI2: Device doesn't support depth/color registration.");
282  _device->close();
283  openni::OpenNI::shutdown();
284  return false;
285  }
286 
287  if(_device->getSensorInfo(openni::SENSOR_DEPTH) == NULL ||
288  _device->getSensorInfo(_type==kTypeColorDepth?openni::SENSOR_COLOR:openni::SENSOR_IR) == NULL)
289  {
290  UERROR("CameraOpenNI2: Cannot get sensor info for depth and %s.", _type==kTypeColorDepth?"color":"ir");
291  _device->close();
292  openni::OpenNI::shutdown();
293  return false;
294  }
295 
296  if(_depth->create(*_device, openni::SENSOR_DEPTH) != openni::STATUS_OK)
297  {
298  UERROR("CameraOpenNI2: Cannot create depth stream.");
299  _device->close();
300  openni::OpenNI::shutdown();
301  return false;
302  }
303 
304  if(_color->create(*_device, _type==kTypeColorDepth?openni::SENSOR_COLOR:openni::SENSOR_IR) != openni::STATUS_OK)
305  {
306  UERROR("CameraOpenNI2: Cannot create %s stream.", _type==kTypeColorDepth?"color":"ir");
307  _depth->destroy();
308  _device->close();
309  openni::OpenNI::shutdown();
310  return false;
311  }
312 
313  if(_type==kTypeColorDepth && hardwareRegistration &&
314  _device->setImageRegistrationMode(openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR ) != openni::STATUS_OK)
315  {
316  UERROR("CameraOpenNI2: Failed to set depth/color registration.");
317  }
318 
319  if (_device->setDepthColorSyncEnabled(true) != openni::STATUS_OK)
320  {
321  UERROR("CameraOpenNI2: Failed to set depth color sync");
322  }
323 
324  _depth->setMirroringEnabled(false);
325  _color->setMirroringEnabled(false);
326 
327  const openni::Array<openni::VideoMode>& depthVideoModes = _depth->getSensorInfo().getSupportedVideoModes();
328  for(int i=0; i<depthVideoModes.getSize(); ++i)
329  {
330  UINFO("CameraOpenNI2: Depth video mode %d: fps=%d, pixel=%d, w=%d, h=%d",
331  i,
332  depthVideoModes[i].getFps(),
333  depthVideoModes[i].getPixelFormat(),
334  depthVideoModes[i].getResolutionX(),
335  depthVideoModes[i].getResolutionY());
336  }
337 
338  const openni::Array<openni::VideoMode>& colorVideoModes = _color->getSensorInfo().getSupportedVideoModes();
339  for(int i=0; i<colorVideoModes.getSize(); ++i)
340  {
341  UINFO("CameraOpenNI2: %s video mode %d: fps=%d, pixel=%d, w=%d, h=%d",
342  _type==kTypeColorDepth?"color":"ir",
343  i,
344  colorVideoModes[i].getFps(),
345  colorVideoModes[i].getPixelFormat(),
346  colorVideoModes[i].getResolutionX(),
347  colorVideoModes[i].getResolutionY());
348  }
349 
350  openni::VideoMode mMode;
351  mMode.setFps(30);
352  mMode.setResolution(640,480);
353  mMode.setPixelFormat(openni::PIXEL_FORMAT_DEPTH_1_MM);
354  _depth->setVideoMode(mMode);
355 
356  openni::VideoMode mModeColor;
357  mModeColor.setFps(30);
358  mModeColor.setResolution(640,480);
359  mModeColor.setPixelFormat(openni::PIXEL_FORMAT_RGB888);
360  _color->setVideoMode(mModeColor);
361 
362  UINFO("CameraOpenNI2: Using depth video mode: fps=%d, pixel=%d, w=%d, h=%d, H-FOV=%f rad, V-FOV=%f rad",
363  _depth->getVideoMode().getFps(),
364  _depth->getVideoMode().getPixelFormat(),
365  _depth->getVideoMode().getResolutionX(),
366  _depth->getVideoMode().getResolutionY(),
367  _depth->getHorizontalFieldOfView(),
368  _depth->getVerticalFieldOfView());
369  UINFO("CameraOpenNI2: Using %s video mode: fps=%d, pixel=%d, w=%d, h=%d, H-FOV=%f rad, V-FOV=%f rad",
370  _type==kTypeColorDepth?"color":"ir",
371  _color->getVideoMode().getFps(),
372  _color->getVideoMode().getPixelFormat(),
373  _color->getVideoMode().getResolutionX(),
374  _color->getVideoMode().getResolutionY(),
375  _color->getHorizontalFieldOfView(),
376  _color->getVerticalFieldOfView());
377 
378  if(_depth->getVideoMode().getResolutionX() != 640 ||
379  _depth->getVideoMode().getResolutionY() != 480 ||
380  _depth->getVideoMode().getPixelFormat() != openni::PIXEL_FORMAT_DEPTH_1_MM)
381  {
382  UERROR("Could not set depth format to 640x480 pixel=%d(mm)!",
383  openni::PIXEL_FORMAT_DEPTH_1_MM);
384  _depth->destroy();
385  _color->destroy();
386  _device->close();
387  openni::OpenNI::shutdown();
388  return false;
389  }
390  if(_color->getVideoMode().getResolutionX() != 640 ||
391  _color->getVideoMode().getResolutionY() != 480 ||
392  _color->getVideoMode().getPixelFormat() != openni::PIXEL_FORMAT_RGB888)
393  {
394  UERROR("Could not set %s format to 640x480 pixel=%d!",
395  _type==kTypeColorDepth?"color":"ir",
396  openni::PIXEL_FORMAT_RGB888);
397  _depth->destroy();
398  _color->destroy();
399  _device->close();
400  openni::OpenNI::shutdown();
401  return false;
402  }
403 
404  if(_color->getCameraSettings())
405  {
406  UINFO("CameraOpenNI2: AutoWhiteBalanceEnabled = %d", _color->getCameraSettings()->getAutoWhiteBalanceEnabled()?1:0);
407  UINFO("CameraOpenNI2: AutoExposureEnabled = %d", _color->getCameraSettings()->getAutoExposureEnabled()?1:0);
408 #if ONI_VERSION_MAJOR > 2 || (ONI_VERSION_MAJOR==2 && ONI_VERSION_MINOR >= 2)
409  UINFO("CameraOpenNI2: Exposure = %d", _color->getCameraSettings()->getExposure());
410  UINFO("CameraOpenNI2: GAIN = %d", _color->getCameraSettings()->getGain());
411 #endif
412  }
413 
414  if(_type==kTypeColorDepth && hardwareRegistration)
415  {
416  _depthFx = float(_color->getVideoMode().getResolutionX()/2) / std::tan(_color->getHorizontalFieldOfView()/2.0f);
417  _depthFy = float(_color->getVideoMode().getResolutionY()/2) / std::tan(_color->getVerticalFieldOfView()/2.0f);
418  }
419  else
420  {
421  _depthFx = float(_depth->getVideoMode().getResolutionX()/2) / std::tan(_depth->getHorizontalFieldOfView()/2.0f);
422  _depthFy = float(_depth->getVideoMode().getResolutionY()/2) / std::tan(_depth->getVerticalFieldOfView()/2.0f);
423  }
424  UINFO("depth fx=%f fy=%f", _depthFx, _depthFy);
425 
426  if(_type == kTypeIR)
427  {
428  UWARN("With type IR-only, depth stream will not be started");
429  }
430 
431  if((_type != kTypeIR && _depth->start() != openni::STATUS_OK) ||
432  _color->start() != openni::STATUS_OK)
433  {
434  UERROR("CameraOpenNI2: Cannot start depth and/or color streams.");
435  _depth->stop();
436  _color->stop();
437  _depth->destroy();
438  _color->destroy();
439  _device->close();
440  openni::OpenNI::shutdown();
441  return false;
442  }
443 
444  uSleep(3000); // just to make sure the sensor is correctly initialized and exposure is set
445 
446  return true;
447 #else
448  UERROR("CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
449  return false;
450 #endif
451 }
452 
454 {
455  return true;
456 }
457 
458 std::string CameraOpenNI2::getSerial() const
459 {
460 #ifdef RTABMAP_OPENNI2
461  if(_device)
462  {
463  return _device->getDeviceInfo().getName();
464  }
465 #endif
466  return "";
467 }
468 
470 {
471  SensorData data;
472 #ifdef RTABMAP_OPENNI2
473  int readyStream = -1;
474  if(_device->isValid() &&
475  _depth->isValid() &&
476  _color->isValid() &&
477  _device->getSensorInfo(openni::SENSOR_DEPTH) != NULL &&
478  _device->getSensorInfo(_type==kTypeColorDepth?openni::SENSOR_COLOR:openni::SENSOR_IR) != NULL)
479  {
480  openni::VideoStream* depthStream[] = {_depth};
481  openni::VideoStream* colorStream[] = {_color};
482  if((_type != kTypeIR && openni::OpenNI::waitForAnyStream(depthStream, 1, &readyStream, 5000) != openni::STATUS_OK) ||
483  openni::OpenNI::waitForAnyStream(colorStream, 1, &readyStream, 5000) != openni::STATUS_OK)
484  {
485  UWARN("No frames received since the last 5 seconds, end of stream is reached!");
486  }
487  else
488  {
489  openni::VideoFrameRef depthFrame, colorFrame;
490  if(_type != kTypeIR)
491  {
492  _depth->readFrame(&depthFrame);
493  }
494  _color->readFrame(&colorFrame);
495  cv::Mat depth, rgb;
496  if((_type == kTypeIR || depthFrame.isValid()) && colorFrame.isValid())
497  {
498  int h,w;
499  if(_type != kTypeIR)
500  {
501  h=depthFrame.getHeight();
502  w=depthFrame.getWidth();
503  depth = cv::Mat(h, w, CV_16U, (void*)depthFrame.getData()).clone();
504  }
505  h=colorFrame.getHeight();
506  w=colorFrame.getWidth();
507  cv::Mat tmp(h, w, CV_8UC3, (void *)colorFrame.getData());
508  if(_type==kTypeColorDepth)
509  {
510  cv::cvtColor(tmp, rgb, CV_RGB2BGR);
511  }
512  else // IR
513  {
514  rgb = tmp.clone();
515  }
516  }
517  UASSERT(_depthFx != 0.0f && _depthFy != 0.0f);
518  if(!rgb.empty() && (_type == kTypeIR || !depth.empty()))
519  {
520  // default calibration
521  CameraModel model(
522  _depthFx, //fx
523  _depthFy, //fy
524  float(rgb.cols/2) - 0.5f, //cx
525  float(rgb.rows/2) - 0.5f, //cy
526  this->getLocalTransform(),
527  0,
528  rgb.size());
529 
530  if(_type==kTypeColorDepth)
531  {
532  if(_stereoModel.right().isValidForRectification())
533  {
534  rgb = _stereoModel.right().rectifyImage(rgb);
535  model = _stereoModel.right();
536 
537  if(_stereoModel.left().isValidForRectification() && !_stereoModel.stereoTransform().isNull())
538  {
539  if (_depthHShift > 0 || _depthVShift > 0)
540  {
541  cv::Mat out = cv::Mat::zeros(depth.size(), depth.type());
542  depth(cv::Rect(_depthHShift, _depthVShift, depth.cols - _depthHShift, depth.rows - _depthVShift)).copyTo(out(cv::Rect(0, 0, depth.cols - _depthHShift, depth.rows - _depthVShift)));
543  depth = out;
544  }
545  depth = _stereoModel.left().rectifyImage(depth, 0);
546  depth = util2d::registerDepth(depth, _stereoModel.left().K(), rgb.size(), _stereoModel.right().K(), _stereoModel.stereoTransform());
547  }
548  }
549  }
550  else // IR
551  {
552  if(_stereoModel.left().isValidForRectification())
553  {
554  rgb = _stereoModel.left().rectifyImage(rgb);
555  if(_type!=kTypeIR)
556  {
557  depth = _stereoModel.left().rectifyImage(depth, 0);
558  }
559  model = _stereoModel.left();
560  }
561  }
562  model.setLocalTransform(this->getLocalTransform());
563 
564  if(_openNI2StampsAndIDsUsed)
565  {
566  data = SensorData(rgb, depth, model, depthFrame.getFrameIndex(), double(depthFrame.getTimestamp()) / 1000000.0);
567  }
568  else
569  {
570  data = SensorData(rgb, depth, model, this->getNextSeqID(), UTimer::now());
571  }
572  }
573  }
574  }
575  else
576  {
577  ULOGGER_WARN("The camera must be initialized before requesting an image.");
578  }
579 #else
580  UERROR("CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
581 #endif
582  return data;
583 }
584 
585 } // namespace rtabmap
#define NULL
bool setAutoExposure(bool enabled)
f
virtual std::string getSerial() const
const Transform & getLocalTransform() const
Definition: Camera.h:64
virtual bool isCalibrated() const
std::string getName(void *handle)
cv::Mat RTABMAP_EXP registerDepth(const cv::Mat &depth, const cv::Mat &depthK, const cv::Size &colorSize, const cv::Mat &colorK, const rtabmap::Transform &transform)
Definition: util2d.cpp:1362
std::string getExtension()
Definition: UFile.h:140
void setOpenNI2StampsAndIDsUsed(bool used)
#define UASSERT(condition)
virtual SensorData captureImage(CameraInfo *info=0)
CameraOpenNI2(const std::string &deviceId="", Type type=kTypeColorDepth, float imageRate=0, const Transform &localTransform=CameraModel::opticalRotation())
bool setGain(int value)
bool setExposure(int value)
void setIRDepthShift(int horizontal, int vertical)
bool setMirroring(bool enabled)
cv::Mat rectifyImage(const cv::Mat &raw, int interpolation=cv::INTER_LINEAR) const
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
#define false
Definition: ConvertUTF.c:56
void uSleep(unsigned int ms)
int getNextSeqID()
Definition: Camera.h:84
GLM_FUNC_DECL genType tan(genType const &angle)
#define UERROR(...)
#define ULOGGER_WARN(...)
Definition: ULogger.h:55
#define UWARN(...)
static double now()
Definition: UTimer.cpp:80
static bool exposureGainAvailable()
bool setAutoWhiteBalance(bool enabled)
#define UINFO(...)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:34:58