32 #include <opencv2/imgproc/types_c.h>
34 #ifdef RTABMAP_OPENNI2
35 #include <OniVersion.h>
44 #ifdef RTABMAP_OPENNI2
53 #if ONI_VERSION_MAJOR > 2 || (ONI_VERSION_MAJOR==2 && ONI_VERSION_MINOR >= 2)
61 const std::string & deviceId,
65 Camera(imageRate, localTransform)
66 #ifdef RTABMAP_OPENNI2
69 _device(new
openni::Device()),
70 _color(new
openni::VideoStream()),
71 _depth(new
openni::VideoStream()),
75 _openNI2StampsAndIDsUsed(
false),
85 #ifdef RTABMAP_OPENNI2
91 openni::OpenNI::shutdown();
101 #ifdef RTABMAP_OPENNI2
102 if(_color && _color->getCameraSettings())
104 return _color->getCameraSettings()->setAutoWhiteBalanceEnabled(enabled) == openni::STATUS_OK;
107 UERROR(
"CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
114 #ifdef RTABMAP_OPENNI2
115 if(_color && _color->getCameraSettings())
117 return _color->getCameraSettings()->setAutoExposureEnabled(enabled) == openni::STATUS_OK;
120 UERROR(
"CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
127 #ifdef RTABMAP_OPENNI2
128 #if ONI_VERSION_MAJOR > 2 || (ONI_VERSION_MAJOR==2 && ONI_VERSION_MINOR >= 2)
129 if(_color && _color->getCameraSettings())
131 return _color->getCameraSettings()->setExposure(
value) == openni::STATUS_OK;
134 UERROR(
"CameraOpenNI2: OpenNI >= 2.2 required to use this method.");
137 UERROR(
"CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
144 #ifdef RTABMAP_OPENNI2
145 #if ONI_VERSION_MAJOR > 2 || (ONI_VERSION_MAJOR==2 && ONI_VERSION_MINOR >= 2)
146 if(_color && _color->getCameraSettings())
148 return _color->getCameraSettings()->setGain(
value) == openni::STATUS_OK;
151 UERROR(
"CameraOpenNI2: OpenNI >= 2.2 required to use this method.");
154 UERROR(
"CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
161 #ifdef RTABMAP_OPENNI2
162 if(_color->isValid() && _depth->isValid())
164 return _depth->setMirroringEnabled(enabled) == openni::STATUS_OK &&
165 _color->setMirroringEnabled(enabled) == openni::STATUS_OK;
173 #ifdef RTABMAP_OPENNI2
174 _openNI2StampsAndIDsUsed = used;
180 #ifdef RTABMAP_OPENNI2
181 _depthHShift = horizontal;
182 _depthVShift = vertical;
188 #ifdef RTABMAP_OPENNI2
190 _depthDecimation = decimation;
196 #ifdef RTABMAP_OPENNI2
197 openni::OpenNI::initialize();
199 openni::Array<openni::DeviceInfo> devices;
200 openni::OpenNI::enumerateDevices(&devices);
201 for(
int i=0;
i<devices.getSize(); ++
i)
203 UINFO(
"Device %d: Name=%s URI=%s Vendor=%s",
207 devices[
i].getVendor());
209 if(_deviceId.empty() && devices.getSize() == 0)
211 UERROR(
"CameraOpenNI2: No device detected!");
215 openni::Status
error = _device->open(_deviceId.empty()?openni::ANY_DEVICE:_deviceId.c_str());
216 if(
error != openni::STATUS_OK)
218 if(!_deviceId.empty())
220 UERROR(
"CameraOpenNI2: Cannot open device \"%s\" (error=%d).", _deviceId.c_str(),
error);
225 UERROR(
"CameraOpenNI2: Cannot open device \"%s\" (error=%d).", devices[0].
getName(),
error);
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());
232 openni::OpenNI::shutdown();
238 bool hardwareRegistration =
true;
239 if(!calibrationFolder.empty())
242 std::string calibrationName = _device->getDeviceInfo().getName();
243 if(!cameraName.empty())
245 calibrationName = cameraName;
247 _stereoModel.setName(calibrationName,
"depth",
"rgb");
248 hardwareRegistration = !_stereoModel.load(calibrationFolder, calibrationName,
false);
252 hardwareRegistration =
false;
256 if((_type !=
kTypeColorDepth && !_stereoModel.left().isValidForRectification()) ||
257 (_type ==
kTypeColorDepth && !_stereoModel.right().isValidForRectification()))
259 UWARN(
"Missing calibration files for camera \"%s\" in \"%s\" folder, default calibration used.",
260 calibrationName.c_str(), calibrationFolder.c_str());
262 else if(_type ==
kTypeColorDepth && _stereoModel.right().isValidForRectification() && hardwareRegistration)
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());
267 else if(_type ==
kTypeColorDepth && _stereoModel.right().isValidForRectification() && !hardwareRegistration)
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());
276 if(_device->getPlaybackControl() &&
277 _device->getPlaybackControl()->setRepeatEnabled(
false) != openni::STATUS_OK)
279 UERROR(
"CameraOpenNI2: Cannot set repeat mode to false.");
281 openni::OpenNI::shutdown();
286 !_device->isImageRegistrationModeSupported(openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR))
288 UERROR(
"CameraOpenNI2: Device doesn't support depth/color registration.");
290 openni::OpenNI::shutdown();
294 if(_device->getSensorInfo(openni::SENSOR_DEPTH) ==
NULL ||
295 _device->getSensorInfo(_type==
kTypeColorDepth?openni::SENSOR_COLOR:openni::SENSOR_IR) ==
NULL)
297 UERROR(
"CameraOpenNI2: Cannot get sensor info for depth and %s.", _type==
kTypeColorDepth?
"color":
"ir");
299 openni::OpenNI::shutdown();
303 if(_depth->create(*_device, openni::SENSOR_DEPTH) != openni::STATUS_OK)
305 UERROR(
"CameraOpenNI2: Cannot create depth stream.");
307 openni::OpenNI::shutdown();
311 if(_color->create(*_device, _type==
kTypeColorDepth?openni::SENSOR_COLOR:openni::SENSOR_IR) != openni::STATUS_OK)
316 openni::OpenNI::shutdown();
321 _device->setImageRegistrationMode(openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR ) != openni::STATUS_OK)
323 UERROR(
"CameraOpenNI2: Failed to set depth/color registration.");
326 if (_device->setDepthColorSyncEnabled(
true) != openni::STATUS_OK)
328 UERROR(
"CameraOpenNI2: Failed to set depth color sync");
331 _depth->setMirroringEnabled(
false);
332 _color->setMirroringEnabled(
false);
334 const openni::Array<openni::VideoMode>& depthVideoModes = _depth->getSensorInfo().getSupportedVideoModes();
335 for(
int i=0;
i<depthVideoModes.getSize(); ++
i)
337 UINFO(
"CameraOpenNI2: Depth video mode %d: fps=%d, pixel=%d, w=%d, h=%d",
339 depthVideoModes[
i].getFps(),
340 depthVideoModes[
i].getPixelFormat(),
341 depthVideoModes[
i].getResolutionX(),
342 depthVideoModes[
i].getResolutionY());
345 const openni::Array<openni::VideoMode>& colorVideoModes = _color->getSensorInfo().getSupportedVideoModes();
346 for(
int i=0;
i<colorVideoModes.getSize(); ++
i)
348 UINFO(
"CameraOpenNI2: %s video mode %d: fps=%d, pixel=%d, w=%d, h=%d",
351 colorVideoModes[
i].getFps(),
352 colorVideoModes[
i].getPixelFormat(),
353 colorVideoModes[
i].getResolutionX(),
354 colorVideoModes[
i].getResolutionY());
357 openni::VideoMode mMode;
359 mMode.setResolution(640,480);
360 mMode.setPixelFormat(openni::PIXEL_FORMAT_DEPTH_1_MM);
361 _depth->setVideoMode(mMode);
363 openni::VideoMode mModeColor;
364 mModeColor.setFps(30);
365 mModeColor.setResolution(640,480);
366 mModeColor.setPixelFormat(openni::PIXEL_FORMAT_RGB888);
367 _color->setVideoMode(mModeColor);
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",
378 _color->getVideoMode().getFps(),
379 _color->getVideoMode().getPixelFormat(),
380 _color->getVideoMode().getResolutionX(),
381 _color->getVideoMode().getResolutionY(),
382 _color->getHorizontalFieldOfView(),
383 _color->getVerticalFieldOfView());
385 if(_depth->getVideoMode().getResolutionX() != 640 ||
386 _depth->getVideoMode().getResolutionY() != 480 ||
387 _depth->getVideoMode().getPixelFormat() != openni::PIXEL_FORMAT_DEPTH_1_MM)
389 UERROR(
"Could not set depth format to 640x480 pixel=%d(mm)!",
390 openni::PIXEL_FORMAT_DEPTH_1_MM);
394 openni::OpenNI::shutdown();
397 if(_color->getVideoMode().getResolutionX() != 640 ||
398 _color->getVideoMode().getResolutionY() != 480 ||
399 _color->getVideoMode().getPixelFormat() != openni::PIXEL_FORMAT_RGB888)
401 UERROR(
"Could not set %s format to 640x480 pixel=%d!",
403 openni::PIXEL_FORMAT_RGB888);
407 openni::OpenNI::shutdown();
411 if(_color->getCameraSettings())
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());
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);
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);
431 UINFO(
"depth fx=%f fy=%f", _depthFx, _depthFy);
435 UWARN(
"With type IR-only, depth stream will not be started");
438 if((_type !=
kTypeIR && _depth->start() != openni::STATUS_OK) ||
439 _color->start() != openni::STATUS_OK)
441 UERROR(
"CameraOpenNI2: Cannot start depth and/or color streams.");
447 openni::OpenNI::shutdown();
455 UERROR(
"CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
467 #ifdef RTABMAP_OPENNI2
470 return _device->getDeviceInfo().getName();
479 #ifdef RTABMAP_OPENNI2
480 int readyStream = -1;
481 if(_device->isValid() &&
484 _device->getSensorInfo(openni::SENSOR_DEPTH) !=
NULL &&
485 _device->getSensorInfo(_type==
kTypeColorDepth?openni::SENSOR_COLOR:openni::SENSOR_IR) !=
NULL)
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)
492 UWARN(
"No frames received since the last 5 seconds, end of stream is reached!");
496 openni::VideoFrameRef depthFrame, colorFrame;
499 _depth->readFrame(&depthFrame);
501 _color->readFrame(&colorFrame);
503 if((_type ==
kTypeIR || depthFrame.isValid()) && colorFrame.isValid())
508 h=depthFrame.getHeight();
509 w=depthFrame.getWidth();
510 depth = cv::Mat(
h,
w, CV_16U, (
void*)depthFrame.getData()).clone();
512 h=colorFrame.getHeight();
513 w=colorFrame.getWidth();
514 cv::Mat tmp(
h,
w, CV_8UC3, (
void *)colorFrame.getData());
517 cv::cvtColor(tmp, rgb, CV_RGB2BGR);
524 UASSERT(_depthFx != 0.0
f && _depthFy != 0.0
f);
525 if(!rgb.empty() && (_type ==
kTypeIR || !depth.empty()))
531 float(rgb.cols/2) - 0.5f,
532 float(rgb.rows/2) - 0.5f,
533 this->getLocalTransform(),
539 if (_depthHShift != 0 || _depthVShift != 0)
541 cv::Mat
out = cv::Mat::zeros(depth.size(), depth.type());
543 _depthHShift>0?_depthHShift:0,
544 _depthVShift>0?_depthVShift:0,
545 depth.cols -
abs(_depthHShift),
546 depth.rows -
abs(_depthVShift))).copyTo(
548 _depthHShift<0?-_depthHShift:0,
549 _depthVShift<0?-_depthVShift:0,
550 depth.cols -
abs(_depthHShift),
551 depth.rows -
abs(_depthVShift))));
555 if(_stereoModel.right().isValidForRectification())
557 rgb = _stereoModel.right().rectifyImage(rgb);
558 model = _stereoModel.right();
560 if(_stereoModel.left().isValidForRectification() && !_stereoModel.stereoTransform().isNull())
562 depth = _stereoModel.left().rectifyImage(depth, 0);
563 CameraModel depthModel = _stereoModel.left().
scaled(1.0 /
double(_depthDecimation));
565 depth =
util2d::registerDepth(depth, depthModel.
K(), rgb.size()/_depthDecimation, _stereoModel.right().scaled(1.0/
double(_depthDecimation)).K(), _stereoModel.stereoTransform());
567 else if (_depthDecimation > 1)
572 else if (_depthDecimation > 1)
579 if(_stereoModel.left().isValidForRectification())
581 rgb = _stereoModel.left().rectifyImage(rgb);
584 depth = _stereoModel.left().rectifyImage(depth, 0);
586 model = _stereoModel.left();
591 if(_openNI2StampsAndIDsUsed)
593 data =
SensorData(rgb, depth,
model, depthFrame.getFrameIndex(),
double(depthFrame.getTimestamp()) / 1000000.0);
604 ULOGGER_WARN(
"The camera must be initialized before requesting an image.");
607 UERROR(
"CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");