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  _depthDecimation(1)
79 #endif
80 {
81 }
82 
84 {
85 #ifdef RTABMAP_OPENNI2
86  _color->stop();
87  _color->destroy();
88  _depth->stop();
89  _depth->destroy();
90  _device->close();
91  openni::OpenNI::shutdown();
92 
93  delete _device;
94  delete _color;
95  delete _depth;
96 #endif
97 }
98 
100 {
101 #ifdef RTABMAP_OPENNI2
102  if(_color && _color->getCameraSettings())
103  {
104  return _color->getCameraSettings()->setAutoWhiteBalanceEnabled(enabled) == openni::STATUS_OK;
105  }
106 #else
107  UERROR("CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
108 #endif
109  return false;
110 }
111 
113 {
114 #ifdef RTABMAP_OPENNI2
115  if(_color && _color->getCameraSettings())
116  {
117  return _color->getCameraSettings()->setAutoExposureEnabled(enabled) == openni::STATUS_OK;
118  }
119 #else
120  UERROR("CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
121 #endif
122  return false;
123 }
124 
126 {
127 #ifdef RTABMAP_OPENNI2
128 #if ONI_VERSION_MAJOR > 2 || (ONI_VERSION_MAJOR==2 && ONI_VERSION_MINOR >= 2)
129  if(_color && _color->getCameraSettings())
130  {
131  return _color->getCameraSettings()->setExposure(value) == openni::STATUS_OK;
132  }
133 #else
134  UERROR("CameraOpenNI2: OpenNI >= 2.2 required to use this method.");
135 #endif
136 #else
137  UERROR("CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
138 #endif
139  return false;
140 }
141 
142 bool CameraOpenNI2::setGain(int value)
143 {
144 #ifdef RTABMAP_OPENNI2
145 #if ONI_VERSION_MAJOR > 2 || (ONI_VERSION_MAJOR==2 && ONI_VERSION_MINOR >= 2)
146  if(_color && _color->getCameraSettings())
147  {
148  return _color->getCameraSettings()->setGain(value) == openni::STATUS_OK;
149  }
150 #else
151  UERROR("CameraOpenNI2: OpenNI >= 2.2 required to use this method.");
152 #endif
153 #else
154  UERROR("CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
155 #endif
156  return false;
157 }
158 
159 bool CameraOpenNI2::setMirroring(bool enabled)
160 {
161 #ifdef RTABMAP_OPENNI2
162  if(_color->isValid() && _depth->isValid())
163  {
164  return _depth->setMirroringEnabled(enabled) == openni::STATUS_OK &&
165  _color->setMirroringEnabled(enabled) == openni::STATUS_OK;
166  }
167 #endif
168  return false;
169 }
170 
172 {
173 #ifdef RTABMAP_OPENNI2
174  _openNI2StampsAndIDsUsed = used;
175 #endif
176 }
177 
178 void CameraOpenNI2::setIRDepthShift(int horizontal, int vertical)
179 {
180 #ifdef RTABMAP_OPENNI2
181  _depthHShift = horizontal;
182  _depthVShift = vertical;
183 #endif
184 }
185 
187 {
188 #ifdef RTABMAP_OPENNI2
189  UASSERT(decimation >= 1);
190  _depthDecimation = decimation;
191 #endif
192 }
193 
194 bool CameraOpenNI2::init(const std::string & calibrationFolder, const std::string & cameraName)
195 {
196 #ifdef RTABMAP_OPENNI2
197  openni::OpenNI::initialize();
198 
199  openni::Array<openni::DeviceInfo> devices;
200  openni::OpenNI::enumerateDevices(&devices);
201  for(int i=0; i<devices.getSize(); ++i)
202  {
203  UINFO("Device %d: Name=%s URI=%s Vendor=%s",
204  i,
205  devices[i].getName(),
206  devices[i].getUri(),
207  devices[i].getVendor());
208  }
209  if(_deviceId.empty() && devices.getSize() == 0)
210  {
211  UERROR("CameraOpenNI2: No device detected!");
212  return false;
213  }
214 
215  openni::Status error = _device->open(_deviceId.empty()?openni::ANY_DEVICE:_deviceId.c_str());
216  if(error != openni::STATUS_OK)
217  {
218  if(!_deviceId.empty())
219  {
220  UERROR("CameraOpenNI2: Cannot open device \"%s\" (error=%d).", _deviceId.c_str(), error);
221  }
222  else
223  {
224 #ifdef _WIN32
225  UERROR("CameraOpenNI2: Cannot open device \"%s\" (error=%d).", devices[0].getName(), error);
226 #else
227  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());
228 #endif
229  }
230 
231  _device->close();
232  openni::OpenNI::shutdown();
233  return false;
234  }
235 
236  // look for calibration files
237  _stereoModel = StereoCameraModel();
238  bool hardwareRegistration = true;
239  if(!calibrationFolder.empty())
240  {
241  // we need the serial
242  std::string calibrationName = _device->getDeviceInfo().getName();
243  if(!cameraName.empty())
244  {
245  calibrationName = cameraName;
246  }
247  _stereoModel.setName(calibrationName, "depth", "rgb");
248  hardwareRegistration = !_stereoModel.load(calibrationFolder, calibrationName, false);
249 
250  if(_type != kTypeColorDepth)
251  {
252  hardwareRegistration = false;
253  }
254 
255 
256  if((_type != kTypeColorDepth && !_stereoModel.left().isValidForRectification()) ||
257  (_type == kTypeColorDepth && !_stereoModel.right().isValidForRectification()))
258  {
259  UWARN("Missing calibration files for camera \"%s\" in \"%s\" folder, default calibration used.",
260  calibrationName.c_str(), calibrationFolder.c_str());
261  }
262  else if(_type == kTypeColorDepth && _stereoModel.right().isValidForRectification() && hardwareRegistration)
263  {
264  UWARN("Missing extrinsic calibration file for camera \"%s\" in \"%s\" folder, default registration is used even if rgb is rectified!",
265  calibrationName.c_str(), calibrationFolder.c_str());
266  }
267  else if(_type == kTypeColorDepth && _stereoModel.right().isValidForRectification() && !hardwareRegistration)
268  {
269  UINFO("Custom calibration files for \"%s\" were found in \"%s\" folder. To use "
270  "factory calibration, remove the corresponding files from that directory.", calibrationName.c_str(), calibrationFolder.c_str());
271  }
272  }
273 
274  if(UFile::getExtension(_deviceId).compare("oni")==0)
275  {
276  if(_device->getPlaybackControl() &&
277  _device->getPlaybackControl()->setRepeatEnabled(false) != openni::STATUS_OK)
278  {
279  UERROR("CameraOpenNI2: Cannot set repeat mode to false.");
280  _device->close();
281  openni::OpenNI::shutdown();
282  return false;
283  }
284  }
285  else if(_type==kTypeColorDepth && hardwareRegistration &&
286  !_device->isImageRegistrationModeSupported(openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR))
287  {
288  UERROR("CameraOpenNI2: Device doesn't support depth/color registration.");
289  _device->close();
290  openni::OpenNI::shutdown();
291  return false;
292  }
293 
294  if(_device->getSensorInfo(openni::SENSOR_DEPTH) == NULL ||
295  _device->getSensorInfo(_type==kTypeColorDepth?openni::SENSOR_COLOR:openni::SENSOR_IR) == NULL)
296  {
297  UERROR("CameraOpenNI2: Cannot get sensor info for depth and %s.", _type==kTypeColorDepth?"color":"ir");
298  _device->close();
299  openni::OpenNI::shutdown();
300  return false;
301  }
302 
303  if(_depth->create(*_device, openni::SENSOR_DEPTH) != openni::STATUS_OK)
304  {
305  UERROR("CameraOpenNI2: Cannot create depth stream.");
306  _device->close();
307  openni::OpenNI::shutdown();
308  return false;
309  }
310 
311  if(_color->create(*_device, _type==kTypeColorDepth?openni::SENSOR_COLOR:openni::SENSOR_IR) != openni::STATUS_OK)
312  {
313  UERROR("CameraOpenNI2: Cannot create %s stream.", _type==kTypeColorDepth?"color":"ir");
314  _depth->destroy();
315  _device->close();
316  openni::OpenNI::shutdown();
317  return false;
318  }
319 
320  if(_type==kTypeColorDepth && hardwareRegistration &&
321  _device->setImageRegistrationMode(openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR ) != openni::STATUS_OK)
322  {
323  UERROR("CameraOpenNI2: Failed to set depth/color registration.");
324  }
325 
326  if (_device->setDepthColorSyncEnabled(true) != openni::STATUS_OK)
327  {
328  UERROR("CameraOpenNI2: Failed to set depth color sync");
329  }
330 
331  _depth->setMirroringEnabled(false);
332  _color->setMirroringEnabled(false);
333 
334  const openni::Array<openni::VideoMode>& depthVideoModes = _depth->getSensorInfo().getSupportedVideoModes();
335  for(int i=0; i<depthVideoModes.getSize(); ++i)
336  {
337  UINFO("CameraOpenNI2: Depth video mode %d: fps=%d, pixel=%d, w=%d, h=%d",
338  i,
339  depthVideoModes[i].getFps(),
340  depthVideoModes[i].getPixelFormat(),
341  depthVideoModes[i].getResolutionX(),
342  depthVideoModes[i].getResolutionY());
343  }
344 
345  const openni::Array<openni::VideoMode>& colorVideoModes = _color->getSensorInfo().getSupportedVideoModes();
346  for(int i=0; i<colorVideoModes.getSize(); ++i)
347  {
348  UINFO("CameraOpenNI2: %s video mode %d: fps=%d, pixel=%d, w=%d, h=%d",
349  _type==kTypeColorDepth?"color":"ir",
350  i,
351  colorVideoModes[i].getFps(),
352  colorVideoModes[i].getPixelFormat(),
353  colorVideoModes[i].getResolutionX(),
354  colorVideoModes[i].getResolutionY());
355  }
356 
357  openni::VideoMode mMode;
358  mMode.setFps(30);
359  mMode.setResolution(640,480);
360  mMode.setPixelFormat(openni::PIXEL_FORMAT_DEPTH_1_MM);
361  _depth->setVideoMode(mMode);
362 
363  openni::VideoMode mModeColor;
364  mModeColor.setFps(30);
365  mModeColor.setResolution(640,480);
366  mModeColor.setPixelFormat(openni::PIXEL_FORMAT_RGB888);
367  _color->setVideoMode(mModeColor);
368 
369  UINFO("CameraOpenNI2: Using depth video mode: fps=%d, pixel=%d, w=%d, h=%d, H-FOV=%f rad, V-FOV=%f rad",
370  _depth->getVideoMode().getFps(),
371  _depth->getVideoMode().getPixelFormat(),
372  _depth->getVideoMode().getResolutionX(),
373  _depth->getVideoMode().getResolutionY(),
374  _depth->getHorizontalFieldOfView(),
375  _depth->getVerticalFieldOfView());
376  UINFO("CameraOpenNI2: Using %s video mode: fps=%d, pixel=%d, w=%d, h=%d, H-FOV=%f rad, V-FOV=%f rad",
377  _type==kTypeColorDepth?"color":"ir",
378  _color->getVideoMode().getFps(),
379  _color->getVideoMode().getPixelFormat(),
380  _color->getVideoMode().getResolutionX(),
381  _color->getVideoMode().getResolutionY(),
382  _color->getHorizontalFieldOfView(),
383  _color->getVerticalFieldOfView());
384 
385  if(_depth->getVideoMode().getResolutionX() != 640 ||
386  _depth->getVideoMode().getResolutionY() != 480 ||
387  _depth->getVideoMode().getPixelFormat() != openni::PIXEL_FORMAT_DEPTH_1_MM)
388  {
389  UERROR("Could not set depth format to 640x480 pixel=%d(mm)!",
390  openni::PIXEL_FORMAT_DEPTH_1_MM);
391  _depth->destroy();
392  _color->destroy();
393  _device->close();
394  openni::OpenNI::shutdown();
395  return false;
396  }
397  if(_color->getVideoMode().getResolutionX() != 640 ||
398  _color->getVideoMode().getResolutionY() != 480 ||
399  _color->getVideoMode().getPixelFormat() != openni::PIXEL_FORMAT_RGB888)
400  {
401  UERROR("Could not set %s format to 640x480 pixel=%d!",
402  _type==kTypeColorDepth?"color":"ir",
403  openni::PIXEL_FORMAT_RGB888);
404  _depth->destroy();
405  _color->destroy();
406  _device->close();
407  openni::OpenNI::shutdown();
408  return false;
409  }
410 
411  if(_color->getCameraSettings())
412  {
413  UINFO("CameraOpenNI2: AutoWhiteBalanceEnabled = %d", _color->getCameraSettings()->getAutoWhiteBalanceEnabled()?1:0);
414  UINFO("CameraOpenNI2: AutoExposureEnabled = %d", _color->getCameraSettings()->getAutoExposureEnabled()?1:0);
415 #if ONI_VERSION_MAJOR > 2 || (ONI_VERSION_MAJOR==2 && ONI_VERSION_MINOR >= 2)
416  UINFO("CameraOpenNI2: Exposure = %d", _color->getCameraSettings()->getExposure());
417  UINFO("CameraOpenNI2: GAIN = %d", _color->getCameraSettings()->getGain());
418 #endif
419  }
420 
421  if(_type==kTypeColorDepth && hardwareRegistration)
422  {
423  _depthFx = float(_color->getVideoMode().getResolutionX()/2) / std::tan(_color->getHorizontalFieldOfView()/2.0f);
424  _depthFy = float(_color->getVideoMode().getResolutionY()/2) / std::tan(_color->getVerticalFieldOfView()/2.0f);
425  }
426  else
427  {
428  _depthFx = float(_depth->getVideoMode().getResolutionX()/2) / std::tan(_depth->getHorizontalFieldOfView()/2.0f);
429  _depthFy = float(_depth->getVideoMode().getResolutionY()/2) / std::tan(_depth->getVerticalFieldOfView()/2.0f);
430  }
431  UINFO("depth fx=%f fy=%f", _depthFx, _depthFy);
432 
433  if(_type == kTypeIR)
434  {
435  UWARN("With type IR-only, depth stream will not be started");
436  }
437 
438  if((_type != kTypeIR && _depth->start() != openni::STATUS_OK) ||
439  _color->start() != openni::STATUS_OK)
440  {
441  UERROR("CameraOpenNI2: Cannot start depth and/or color streams.");
442  _depth->stop();
443  _color->stop();
444  _depth->destroy();
445  _color->destroy();
446  _device->close();
447  openni::OpenNI::shutdown();
448  return false;
449  }
450 
451  uSleep(3000); // just to make sure the sensor is correctly initialized and exposure is set
452 
453  return true;
454 #else
455  UERROR("CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
456  return false;
457 #endif
458 }
459 
461 {
462  return true;
463 }
464 
465 std::string CameraOpenNI2::getSerial() const
466 {
467 #ifdef RTABMAP_OPENNI2
468  if(_device)
469  {
470  return _device->getDeviceInfo().getName();
471  }
472 #endif
473  return "";
474 }
475 
477 {
479 #ifdef RTABMAP_OPENNI2
480  int readyStream = -1;
481  if(_device->isValid() &&
482  _depth->isValid() &&
483  _color->isValid() &&
484  _device->getSensorInfo(openni::SENSOR_DEPTH) != NULL &&
485  _device->getSensorInfo(_type==kTypeColorDepth?openni::SENSOR_COLOR:openni::SENSOR_IR) != NULL)
486  {
487  openni::VideoStream* depthStream[] = {_depth};
488  openni::VideoStream* colorStream[] = {_color};
489  if((_type != kTypeIR && openni::OpenNI::waitForAnyStream(depthStream, 1, &readyStream, 5000) != openni::STATUS_OK) ||
490  openni::OpenNI::waitForAnyStream(colorStream, 1, &readyStream, 5000) != openni::STATUS_OK)
491  {
492  UWARN("No frames received since the last 5 seconds, end of stream is reached!");
493  }
494  else
495  {
496  openni::VideoFrameRef depthFrame, colorFrame;
497  if(_type != kTypeIR)
498  {
499  _depth->readFrame(&depthFrame);
500  }
501  _color->readFrame(&colorFrame);
502  cv::Mat depth, rgb;
503  if((_type == kTypeIR || depthFrame.isValid()) && colorFrame.isValid())
504  {
505  int h,w;
506  if(_type != kTypeIR)
507  {
508  h=depthFrame.getHeight();
509  w=depthFrame.getWidth();
510  depth = cv::Mat(h, w, CV_16U, (void*)depthFrame.getData()).clone();
511  }
512  h=colorFrame.getHeight();
513  w=colorFrame.getWidth();
514  cv::Mat tmp(h, w, CV_8UC3, (void *)colorFrame.getData());
515  if(_type==kTypeColorDepth)
516  {
517  cv::cvtColor(tmp, rgb, CV_RGB2BGR);
518  }
519  else // IR
520  {
521  rgb = tmp.clone();
522  }
523  }
524  UASSERT(_depthFx != 0.0f && _depthFy != 0.0f);
525  if(!rgb.empty() && (_type == kTypeIR || !depth.empty()))
526  {
527  // default calibration
529  _depthFx, //fx
530  _depthFy, //fy
531  float(rgb.cols/2) - 0.5f, //cx
532  float(rgb.rows/2) - 0.5f, //cy
533  this->getLocalTransform(),
534  0,
535  rgb.size());
536 
537  if(_type==kTypeColorDepth)
538  {
539  if (_depthHShift != 0 || _depthVShift != 0)
540  {
541  cv::Mat out = cv::Mat::zeros(depth.size(), depth.type());
542  depth(cv::Rect(
543  _depthHShift>0?_depthHShift:0,
544  _depthVShift>0?_depthVShift:0,
545  depth.cols - abs(_depthHShift),
546  depth.rows - abs(_depthVShift))).copyTo(
547  out(cv::Rect(
548  _depthHShift<0?-_depthHShift:0,
549  _depthVShift<0?-_depthVShift:0,
550  depth.cols - abs(_depthHShift),
551  depth.rows - abs(_depthVShift))));
552  depth = out;
553  }
554 
555  if(_stereoModel.right().isValidForRectification())
556  {
557  rgb = _stereoModel.right().rectifyImage(rgb);
558  model = _stereoModel.right();
559 
560  if(_stereoModel.left().isValidForRectification() && !_stereoModel.stereoTransform().isNull())
561  {
562  depth = _stereoModel.left().rectifyImage(depth, 0);
563  CameraModel depthModel = _stereoModel.left().scaled(1.0 / double(_depthDecimation));
564  depth = util2d::decimate(depth, _depthDecimation);
565  depth = util2d::registerDepth(depth, depthModel.K(), rgb.size()/_depthDecimation, _stereoModel.right().scaled(1.0/double(_depthDecimation)).K(), _stereoModel.stereoTransform());
566  }
567  else if (_depthDecimation > 1)
568  {
569  depth = util2d::decimate(depth, _depthDecimation);
570  }
571  }
572  else if (_depthDecimation > 1)
573  {
574  depth = util2d::decimate(depth, _depthDecimation);
575  }
576  }
577  else // IR
578  {
579  if(_stereoModel.left().isValidForRectification())
580  {
581  rgb = _stereoModel.left().rectifyImage(rgb);
582  if(_type!=kTypeIR)
583  {
584  depth = _stereoModel.left().rectifyImage(depth, 0);
585  }
586  model = _stereoModel.left();
587  }
588  }
589  model.setLocalTransform(this->getLocalTransform());
590 
591  if(_openNI2StampsAndIDsUsed)
592  {
593  data = SensorData(rgb, depth, model, depthFrame.getFrameIndex(), double(depthFrame.getTimestamp()) / 1000000.0);
594  }
595  else
596  {
597  data = SensorData(rgb, depth, model, this->getNextSeqID(), UTimer::now());
598  }
599  }
600  }
601  }
602  else
603  {
604  ULOGGER_WARN("The camera must be initialized before requesting an image.");
605  }
606 #else
607  UERROR("CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
608 #endif
609  return data;
610 }
611 
612 } // namespace rtabmap
#define NULL
bool setAutoExposure(bool enabled)
CameraModel scaled(double scale) const
f
data
ROSCONSOLE_CONSOLE_IMPL_DECL 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
virtual bool isCalibrated() const
void setOpenNI2StampsAndIDsUsed(bool used)
#define UASSERT(condition)
virtual SensorData captureImage(CameraInfo *info=0)
cv::Mat RTABMAP_EXP decimate(const cv::Mat &image, int d)
Definition: util2d.cpp:1201
cv::Mat K() const
Definition: CameraModel.h:110
GLM_FUNC_DECL genType abs(genType const &x)
bool setGain(int value)
bool setExposure(int value)
void setIRDepthShift(int horizontal, int vertical)
const Transform & getLocalTransform() const
Definition: Camera.h:65
bool setMirroring(bool enabled)
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:86
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
model
Definition: trace.py:4
void setDepthDecimation(int decimation)
CameraOpenNI2(const std::string &deviceId="", Type type=kTypeColorDepth, float imageRate=0, const Transform &localTransform=Transform::getIdentity())
static bool exposureGainAvailable()
bool setAutoWhiteBalance(bool enabled)
virtual std::string getSerial() const
#define UINFO(...)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:28