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),
84 #ifdef RTABMAP_OPENNI2 90 openni::OpenNI::shutdown();
100 #ifdef RTABMAP_OPENNI2 101 if(_color && _color->getCameraSettings())
103 return _color->getCameraSettings()->setAutoWhiteBalanceEnabled(enabled) == openni::STATUS_OK;
106 UERROR(
"CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
113 #ifdef RTABMAP_OPENNI2 114 if(_color && _color->getCameraSettings())
116 return _color->getCameraSettings()->setAutoExposureEnabled(enabled) == openni::STATUS_OK;
119 UERROR(
"CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
126 #ifdef RTABMAP_OPENNI2 127 #if ONI_VERSION_MAJOR > 2 || (ONI_VERSION_MAJOR==2 && ONI_VERSION_MINOR >= 2) 128 if(_color && _color->getCameraSettings())
130 return _color->getCameraSettings()->setExposure(value) == openni::STATUS_OK;
133 UERROR(
"CameraOpenNI2: OpenNI >= 2.2 required to use this method.");
136 UERROR(
"CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
143 #ifdef RTABMAP_OPENNI2 144 #if ONI_VERSION_MAJOR > 2 || (ONI_VERSION_MAJOR==2 && ONI_VERSION_MINOR >= 2) 145 if(_color && _color->getCameraSettings())
147 return _color->getCameraSettings()->setGain(value) == openni::STATUS_OK;
150 UERROR(
"CameraOpenNI2: OpenNI >= 2.2 required to use this method.");
153 UERROR(
"CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
160 #ifdef RTABMAP_OPENNI2 161 if(_color->isValid() && _depth->isValid())
163 return _depth->setMirroringEnabled(enabled) == openni::STATUS_OK &&
164 _color->setMirroringEnabled(enabled) == openni::STATUS_OK;
172 #ifdef RTABMAP_OPENNI2 173 _openNI2StampsAndIDsUsed = used;
179 #ifdef RTABMAP_OPENNI2 182 _depthHShift = horizontal;
183 _depthVShift = vertical;
189 #ifdef RTABMAP_OPENNI2 190 openni::OpenNI::initialize();
192 openni::Array<openni::DeviceInfo> devices;
193 openni::OpenNI::enumerateDevices(&devices);
194 for(
int i=0; i<devices.getSize(); ++i)
196 UINFO(
"Device %d: Name=%s URI=%s Vendor=%s",
200 devices[i].getVendor());
202 if(_deviceId.empty() && devices.getSize() == 0)
204 UERROR(
"CameraOpenNI2: No device detected!");
208 openni::Status error = _device->open(_deviceId.empty()?openni::ANY_DEVICE:_deviceId.c_str());
209 if(error != openni::STATUS_OK)
211 if(!_deviceId.empty())
213 UERROR(
"CameraOpenNI2: Cannot open device \"%s\" (error=%d).", _deviceId.c_str(), error);
218 UERROR(
"CameraOpenNI2: Cannot open device \"%s\" (error=%d).", devices[0].
getName(), error);
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());
225 openni::OpenNI::shutdown();
231 bool hardwareRegistration =
true;
232 if(!calibrationFolder.empty())
235 std::string calibrationName = _device->getDeviceInfo().getName();
236 if(!cameraName.empty())
238 calibrationName = cameraName;
240 _stereoModel.setName(calibrationName,
"depth",
"rgb");
241 hardwareRegistration = !_stereoModel.load(calibrationFolder, calibrationName,
false);
245 hardwareRegistration =
false;
249 if((_type !=
kTypeColorDepth && !_stereoModel.left().isValidForRectification()) ||
250 (_type ==
kTypeColorDepth && !_stereoModel.right().isValidForRectification()))
252 UWARN(
"Missing calibration files for camera \"%s\" in \"%s\" folder, default calibration used.",
253 calibrationName.c_str(), calibrationFolder.c_str());
255 else if(_type ==
kTypeColorDepth && _stereoModel.right().isValidForRectification() && hardwareRegistration)
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());
260 else if(_type ==
kTypeColorDepth && _stereoModel.right().isValidForRectification() && !hardwareRegistration)
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());
269 if(_device->getPlaybackControl() &&
270 _device->getPlaybackControl()->setRepeatEnabled(
false) != openni::STATUS_OK)
272 UERROR(
"CameraOpenNI2: Cannot set repeat mode to false.");
274 openni::OpenNI::shutdown();
279 !_device->isImageRegistrationModeSupported(openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR))
281 UERROR(
"CameraOpenNI2: Device doesn't support depth/color registration.");
283 openni::OpenNI::shutdown();
287 if(_device->getSensorInfo(openni::SENSOR_DEPTH) ==
NULL ||
288 _device->getSensorInfo(_type==
kTypeColorDepth?openni::SENSOR_COLOR:openni::SENSOR_IR) ==
NULL)
290 UERROR(
"CameraOpenNI2: Cannot get sensor info for depth and %s.", _type==
kTypeColorDepth?
"color":
"ir");
292 openni::OpenNI::shutdown();
296 if(_depth->create(*_device, openni::SENSOR_DEPTH) != openni::STATUS_OK)
298 UERROR(
"CameraOpenNI2: Cannot create depth stream.");
300 openni::OpenNI::shutdown();
304 if(_color->create(*_device, _type==
kTypeColorDepth?openni::SENSOR_COLOR:openni::SENSOR_IR) != openni::STATUS_OK)
309 openni::OpenNI::shutdown();
314 _device->setImageRegistrationMode(openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR ) != openni::STATUS_OK)
316 UERROR(
"CameraOpenNI2: Failed to set depth/color registration.");
319 if (_device->setDepthColorSyncEnabled(
true) != openni::STATUS_OK)
321 UERROR(
"CameraOpenNI2: Failed to set depth color sync");
324 _depth->setMirroringEnabled(
false);
325 _color->setMirroringEnabled(
false);
327 const openni::Array<openni::VideoMode>& depthVideoModes = _depth->getSensorInfo().getSupportedVideoModes();
328 for(
int i=0; i<depthVideoModes.getSize(); ++i)
330 UINFO(
"CameraOpenNI2: Depth video mode %d: fps=%d, pixel=%d, w=%d, h=%d",
332 depthVideoModes[i].getFps(),
333 depthVideoModes[i].getPixelFormat(),
334 depthVideoModes[i].getResolutionX(),
335 depthVideoModes[i].getResolutionY());
338 const openni::Array<openni::VideoMode>& colorVideoModes = _color->getSensorInfo().getSupportedVideoModes();
339 for(
int i=0; i<colorVideoModes.getSize(); ++i)
341 UINFO(
"CameraOpenNI2: %s video mode %d: fps=%d, pixel=%d, w=%d, h=%d",
344 colorVideoModes[i].getFps(),
345 colorVideoModes[i].getPixelFormat(),
346 colorVideoModes[i].getResolutionX(),
347 colorVideoModes[i].getResolutionY());
350 openni::VideoMode mMode;
352 mMode.setResolution(640,480);
353 mMode.setPixelFormat(openni::PIXEL_FORMAT_DEPTH_1_MM);
354 _depth->setVideoMode(mMode);
356 openni::VideoMode mModeColor;
357 mModeColor.setFps(30);
358 mModeColor.setResolution(640,480);
359 mModeColor.setPixelFormat(openni::PIXEL_FORMAT_RGB888);
360 _color->setVideoMode(mModeColor);
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",
371 _color->getVideoMode().getFps(),
372 _color->getVideoMode().getPixelFormat(),
373 _color->getVideoMode().getResolutionX(),
374 _color->getVideoMode().getResolutionY(),
375 _color->getHorizontalFieldOfView(),
376 _color->getVerticalFieldOfView());
378 if(_depth->getVideoMode().getResolutionX() != 640 ||
379 _depth->getVideoMode().getResolutionY() != 480 ||
380 _depth->getVideoMode().getPixelFormat() != openni::PIXEL_FORMAT_DEPTH_1_MM)
382 UERROR(
"Could not set depth format to 640x480 pixel=%d(mm)!",
383 openni::PIXEL_FORMAT_DEPTH_1_MM);
387 openni::OpenNI::shutdown();
390 if(_color->getVideoMode().getResolutionX() != 640 ||
391 _color->getVideoMode().getResolutionY() != 480 ||
392 _color->getVideoMode().getPixelFormat() != openni::PIXEL_FORMAT_RGB888)
394 UERROR(
"Could not set %s format to 640x480 pixel=%d!",
396 openni::PIXEL_FORMAT_RGB888);
400 openni::OpenNI::shutdown();
404 if(_color->getCameraSettings())
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());
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);
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);
424 UINFO(
"depth fx=%f fy=%f", _depthFx, _depthFy);
428 UWARN(
"With type IR-only, depth stream will not be started");
431 if((_type !=
kTypeIR && _depth->start() != openni::STATUS_OK) ||
432 _color->start() != openni::STATUS_OK)
434 UERROR(
"CameraOpenNI2: Cannot start depth and/or color streams.");
440 openni::OpenNI::shutdown();
448 UERROR(
"CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
460 #ifdef RTABMAP_OPENNI2 463 return _device->getDeviceInfo().getName();
472 #ifdef RTABMAP_OPENNI2 473 int readyStream = -1;
474 if(_device->isValid() &&
477 _device->getSensorInfo(openni::SENSOR_DEPTH) !=
NULL &&
478 _device->getSensorInfo(_type==
kTypeColorDepth?openni::SENSOR_COLOR:openni::SENSOR_IR) !=
NULL)
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)
485 UWARN(
"No frames received since the last 5 seconds, end of stream is reached!");
489 openni::VideoFrameRef depthFrame, colorFrame;
492 _depth->readFrame(&depthFrame);
494 _color->readFrame(&colorFrame);
496 if((_type ==
kTypeIR || depthFrame.isValid()) && colorFrame.isValid())
501 h=depthFrame.getHeight();
502 w=depthFrame.getWidth();
503 depth = cv::Mat(h, w, CV_16U, (
void*)depthFrame.getData()).clone();
505 h=colorFrame.getHeight();
506 w=colorFrame.getWidth();
507 cv::Mat tmp(h, w, CV_8UC3, (
void *)colorFrame.getData());
510 cv::cvtColor(tmp, rgb, CV_RGB2BGR);
517 UASSERT(_depthFx != 0.0
f && _depthFy != 0.0
f);
518 if(!rgb.empty() && (_type ==
kTypeIR || !depth.empty()))
524 float(rgb.cols/2) - 0.5f,
525 float(rgb.rows/2) - 0.5f,
526 this->getLocalTransform(),
532 if(_stereoModel.right().isValidForRectification())
535 model = _stereoModel.right();
537 if(_stereoModel.left().isValidForRectification() && !_stereoModel.stereoTransform().isNull())
539 if (_depthHShift > 0 || _depthVShift > 0)
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)));
545 depth = _stereoModel.left().rectifyImage(depth, 0);
546 depth =
util2d::registerDepth(depth, _stereoModel.left().K(), rgb.size(), _stereoModel.right().K(), _stereoModel.stereoTransform());
552 if(_stereoModel.left().isValidForRectification())
554 rgb = _stereoModel.left().rectifyImage(rgb);
557 depth = _stereoModel.left().rectifyImage(depth, 0);
559 model = _stereoModel.left();
564 if(_openNI2StampsAndIDsUsed)
566 data =
SensorData(rgb, depth, model, depthFrame.getFrameIndex(), double(depthFrame.getTimestamp()) / 1000000.0);
577 ULOGGER_WARN(
"The camera must be initialized before requesting an image.");
580 UERROR(
"CameraOpenNI2: RTAB-Map is not built with OpenNI2 support!");
bool setAutoExposure(bool enabled)
virtual std::string getSerial() const
const Transform & getLocalTransform() const
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)
std::string getExtension()
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 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="")
void uSleep(unsigned int ms)
GLM_FUNC_DECL genType tan(genType const &angle)
#define ULOGGER_WARN(...)
static bool exposureGainAvailable()
bool setAutoWhiteBalance(bool enabled)