27 #include <pcl/io/openni2/openni2_device_manager.h>
28 #include <pcl/io/pcd_io.h>
36 #include <Calibration/Calibration.h>
37 #include <Image/ImageProcessor.h>
44 #if PCL_VERSION > PCL_VERSION_CALC(1, 12, 0)
46 using FctT = std::function<T>;
49 using FctT = boost::function<T>;
55 OpenNIPointCloudProvider::onInitComponent()
60 offeringTopicFromProperty(
"RobotHealthTopicName");
61 offeringTopicFromProperty(
"DebugObserverName");
63 ImageProvider::onInitComponent();
64 CapturingPointCloudProvider::onInitComponent();
68 OpenNIPointCloudProvider::onConnectComponent()
73 getTopicFromProperty(debugObserver,
"DebugObserverName");
74 getTopicFromProperty(robotHealthTopic,
"RobotHealthTopicName");
76 ImageProvider::onConnectComponent();
77 CapturingPointCloudProvider::onConnectComponent();
81 OpenNIPointCloudProvider::onDisconnectComponent()
85 captureEnabled =
false;
86 ImageProvider::onDisconnectComponent();
87 CapturingPointCloudProvider::onDisconnectComponent();
91 OpenNIPointCloudProvider::onExitComponent()
96 ImageProvider::onExitComponent();
97 CapturingPointCloudProvider::onExitComponent();
99 grabberInterface.reset();
103 OpenNIPointCloudProvider::loadCalibrationFile(std::string fileName,
104 visionx::CameraParameters& calibration)
108 FileStorage fs(fileName, FileStorage::READ);
116 std::string cameraName = fs[
"camera_name"];
117 ARMARX_LOG <<
"loading calibration file for " << cameraName;
120 Eigen::Vector2i dimensions = getProperty<Eigen::Vector2i>(
"dimensions").getValue();
121 int imageWidth = fs[
"image_width"];
122 int imageHeight = fs[
"image_height"];
124 if (imageWidth != dimensions(0) || imageHeight != dimensions(1))
130 Mat cameraMatrix, distCoeffs;
132 fs[
"camera_matrix"] >> cameraMatrix;
133 fs[
"distortion_coefficients"] >> distCoeffs;
135 for (
int i = 0; i < 5; i++)
137 calibration.distortion[i] = distCoeffs.at<
float>(0, i);
140 calibration.focalLength[0] = cameraMatrix.at<
float>(0, 0);
141 calibration.focalLength[1] = cameraMatrix.at<
float>(1, 1);
143 calibration.principalPoint[0] = cameraMatrix.at<
float>(0, 2);
144 calibration.principalPoint[1] = cameraMatrix.at<
float>(1, 2);
150 OpenNIPointCloudProvider::onInitCapturingPointCloudProvider()
156 Eigen::Vector2i dimensions = getProperty<Eigen::Vector2i>(
"dimensions").getValue();
158 width = dimensions(0);
159 height = dimensions(1);
161 newPointCloudCapturingRequested =
true;
162 newImageCapturingRequested =
true;
164 ARMARX_VERBOSE <<
"creating OpenNI2Grabber " << width <<
"x" << height <<
"@" << frameRate
166 std::string configuredDeviceId = getProperty<std::string>(
"OpenNIDeviceId").getValue();
167 using namespace pcl::io::openni2;
168 auto connectedDeviceURIs = *OpenNI2DeviceManager::getInstance()->getConnectedDeviceURIs();
169 ARMARX_INFO <<
"connected devices: " << connectedDeviceURIs;
170 if (!configuredDeviceId.empty() && configuredDeviceId.size() > 2)
174 std::string deviceIndexNumber;
175 ARMARX_INFO <<
"Trying to find device with configured URI: '" << configuredDeviceId
177 for (
auto& uri : connectedDeviceURIs)
179 if (uri == configuredDeviceId)
181 ARMARX_INFO <<
"Found device with URI " << configuredDeviceId <<
" at index "
188 if (deviceIndexNumber.empty())
190 ARMARX_WARNING <<
"Could not find device with URI: " << configuredDeviceId
191 <<
" - Connecting now to any device";
192 grabberInterface.reset(
new pcl::io::OpenNI2Grabber());
196 grabberInterface.reset(
new pcl::io::OpenNI2Grabber(deviceIndexNumber));
199 else if (!configuredDeviceId.empty())
202 ARMARX_INFO <<
"Connecting to device id " << configuredDeviceId;
203 grabberInterface.reset(
new pcl::io::OpenNI2Grabber(
"#" + configuredDeviceId));
208 grabberInterface.reset(
new pcl::io::OpenNI2Grabber());
212 visionx::CameraParameters RGBCameraIntrinsics;
213 RGBCameraIntrinsics.focalLength.resize(2, 0.0f);
214 RGBCameraIntrinsics.principalPoint.resize(2, 0.0f);
215 RGBCameraIntrinsics.distortion.resize(4, 0.0f);
218 RGBCameraIntrinsics.rotation =
220 RGBCameraIntrinsics.translation =
224 std::string rgbCameraCalibrationFile =
225 getProperty<std::string>(
"RGBCameraCalibrationFile").getValue();
226 if (!rgbCameraCalibrationFile.empty() &&
227 loadCalibrationFile(rgbCameraCalibrationFile, RGBCameraIntrinsics))
230 grabberInterface->setRGBCameraIntrinsics(RGBCameraIntrinsics.focalLength[0],
231 RGBCameraIntrinsics.focalLength[1],
232 RGBCameraIntrinsics.principalPoint[0],
233 RGBCameraIntrinsics.principalPoint[1]);
238 ARMARX_INFO <<
"unable to load calibration file. using default values.";
239 double fx, fy, cx, cy;
240 grabberInterface->getRGBCameraIntrinsics(fx, fy, cx, cy);
244 if (grabberInterface->getDevice()->hasColorSensor())
246 fx = fy = grabberInterface->getDevice()->getColorFocalLength();
249 cx = (width - 1) / 2.0;
250 cy = (height - 1) / 2.0;
252 ARMARX_INFO <<
"rgb camera fx: " << fx <<
" fy: " << fy <<
" cx: " << cx
255 RGBCameraIntrinsics.principalPoint[0] = cx;
256 RGBCameraIntrinsics.principalPoint[1] = cy;
257 RGBCameraIntrinsics.focalLength[0] = fx;
258 RGBCameraIntrinsics.focalLength[1] = fy;
259 RGBCameraIntrinsics.width = width;
260 RGBCameraIntrinsics.height = height;
263 visionx::CameraParameters depthCameraIntrinsics;
264 depthCameraIntrinsics.focalLength.resize(2, 0.0f);
265 depthCameraIntrinsics.principalPoint.resize(2, 0.0f);
266 depthCameraIntrinsics.distortion.resize(4, 0.0f);
267 depthCameraIntrinsics.rotation =
269 depthCameraIntrinsics.translation =
272 std::string depthCameraCalibrationFile =
273 getProperty<std::string>(
"depthCameraCalibrationFile").getValue();
274 if (!depthCameraCalibrationFile.empty() &&
275 loadCalibrationFile(depthCameraCalibrationFile, depthCameraIntrinsics))
278 grabberInterface->setDepthCameraIntrinsics(depthCameraIntrinsics.focalLength[0],
279 depthCameraIntrinsics.focalLength[1],
280 depthCameraIntrinsics.principalPoint[0],
281 depthCameraIntrinsics.principalPoint[1]);
286 ARMARX_INFO <<
"unable to load calibration file. using default values.";
287 double fx, fy, cx, cy;
288 grabberInterface->getDepthCameraIntrinsics(fx, fy, cx, cy);
292 if (grabberInterface->getDevice()->hasDepthSensor())
294 fx = fy = grabberInterface->getDevice()->getDepthFocalLength();
296 cx = (width - 1) / 2.0;
297 cy = (height - 1) / 2.0;
299 ARMARX_INFO <<
"depth camera fx: " << fx <<
" fy: " << fy <<
" cx: " << cx
302 depthCameraIntrinsics.principalPoint[0] = cx;
303 depthCameraIntrinsics.principalPoint[1] = cy;
304 depthCameraIntrinsics.focalLength[0] = fx;
305 depthCameraIntrinsics.focalLength[1] = fy;
306 depthCameraIntrinsics.width = width;
307 depthCameraIntrinsics.height = height;
314 calibration.calibrationLeft.cameraParam = RGBCameraIntrinsics;
315 calibration.calibrationRight.cameraParam = depthCameraIntrinsics;
316 calibration.rectificationHomographyLeft =
318 calibration.rectificationHomographyRight =
321 ARMARX_INFO <<
"Baseline:" << grabberInterface->getDevice()->getBaseline();
323 pointcloudBuffer = pcl::PointCloud<pcl::PointXYZRGBA>::Ptr(
324 new pcl::PointCloud<pcl::PointXYZRGBA>(width, height));
326 rgbImages =
new CByteImage*[2];
328 rgbImages[0] =
new CByteImage(width, height, CByteImage::eRGB24);
329 rgbImages[1] =
new CByteImage(width, height, CByteImage::eRGB24);
330 ::ImageProcessor::Zero(rgbImages[0]);
331 ::ImageProcessor::Zero(rgbImages[1]);
333 if (grabberInterface->getDevice()->hasColorSensor())
335 FctT<void(
const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&)> pointCloudCallback =
338 callbackFunctionForOpenNIGrabberPointCloudWithRGB(std::forward<decltype(PH1)>(PH1));
340 grabberInterface->registerCallback(pointCloudCallback);
342 FctT<void(
const pcl::io::Image::Ptr&,
const pcl::io::DepthImage::Ptr&,
float)>
343 imageCallback = [
this](
auto&& PH1,
auto&& PH2,
auto&& PH3)
345 grabImages(std::forward<decltype(PH1)>(PH1),
346 std::forward<decltype(PH2)>(PH2),
347 std::forward<decltype(PH3)>(PH3));
349 grabberInterface->registerCallback(imageCallback);
353 ARMARX_INFO <<
"depth sensor. no color image available.";
355 FctT<void(
const pcl::PointCloud<pcl::PointXYZ>::ConstPtr&)> pointCloudCallback =
357 { callbackFunctionForOpenNIGrabberPointCloud(std::forward<decltype(PH1)>(PH1)); };
358 grabberInterface->registerCallback(pointCloudCallback);
360 FctT<void(
const pcl::io::IRImage::Ptr&,
const pcl::io::DepthImage::Ptr&,
float)>
361 imageCallback = [
this](
auto&& PH1,
auto&& PH2,
auto&& PH3)
363 grabDepthImage(std::forward<decltype(PH1)>(PH1),
364 std::forward<decltype(PH2)>(PH2),
365 std::forward<decltype(PH3)>(PH3));
367 grabberInterface->registerCallback(imageCallback);
372 OpenNIPointCloudProvider::onConnectPointCloudProvider()
377 {
"Vision",
"Camera"},
378 "OpenNIPointCloudProvider");
382 OpenNIPointCloudProvider::onStartCapture(
float frameRate)
384 ARMARX_INFO <<
"Openni grabber interface name: " << grabberInterface->getName();
385 ARMARX_INFO <<
"Openni device interface name: " << grabberInterface->getDevice()->getName()
386 <<
" id: " << grabberInterface->getDevice()->getStringID();
389 grabberInterface->getDevice()->setAutoExposure(
390 getProperty<bool>(
"EnableAutoExposure").getValue());
391 grabberInterface->getDevice()->setAutoWhiteBalance(
392 getProperty<bool>(
"EnableAutoWhiteBalance").getValue());
394 grabberInterface->start();
400 OpenNIPointCloudProvider::onStopCapture()
403 ARMARX_INFO <<
"Stopping OpenNI Grabber Interface";
404 if (grabberInterface)
406 grabberInterface->stop();
410 std::scoped_lock lock(syncMutex);
412 condition.notify_one();
416 OpenNIPointCloudProvider::onExitCapturingPointCloudProvider()
428 OpenNIPointCloudProvider::onInitImageProvider()
431 Eigen::Vector2i dimensions = getProperty<Eigen::Vector2i>(
"dimensions").getValue();
432 setImageFormat(visionx::ImageDimension(dimensions(0), dimensions(1)), visionx::eRgb);
437 OpenNIPointCloudProvider::getStereoCalibration(
const Ice::Current&)
443 OpenNIPointCloudProvider::callbackFunctionForOpenNIGrabberPointCloudWithRGB(
444 const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr& newCloud)
448 if (newPointCloudCapturingRequested)
450 long offset = getProperty<float>(
"CaptureTimeOffset").getValue() * 1000.0f;
451 timeOfLastPointCloudCapture = IceUtil::Time::now().toMicroSeconds() - offset;
452 pcl::copyPointCloud(*newCloud, *pointcloudBuffer);
453 std::scoped_lock lock(syncMutex);
454 auto size = newCloud->size();
455 pointcloudBuffer->resize(size);
456 float scaling = 1000.f;
457 for (
size_t i = 0; i < size; i++)
459 pointcloudBuffer->at(i).x = newCloud->at(i).x * scaling;
460 pointcloudBuffer->at(i).y = newCloud->at(i).y * scaling;
461 pointcloudBuffer->at(i).z = newCloud->at(i).z * scaling;
464 newPointCloudCapturingRequested =
false;
466 condition.notify_one();
471 OpenNIPointCloudProvider::callbackFunctionForOpenNIGrabberPointCloud(
472 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr& newCloud)
477 if (newPointCloudCapturingRequested)
480 long offset = getProperty<float>(
"CaptureTimeOffset").getValue() * 1000.0f;
481 timeOfLastPointCloudCapture = IceUtil::Time::now().toMicroSeconds() - offset;
482 Eigen::Affine3f
transform(Eigen::Scaling(1000.0f));
484 std::scoped_lock lock(syncMutex);
485 pcl::copyPointCloud(*newCloud, *pointcloudBuffer);
486 pcl::transformPointCloud(*pointcloudBuffer, *pointcloudBuffer,
transform);
489 newPointCloudCapturingRequested =
false;
491 condition.notify_one();
496 OpenNIPointCloudProvider::grabDepthImage(
const pcl::io::IRImage::Ptr& IRImage,
497 const pcl::io::DepthImage::Ptr& depthImage,
503 if (newImageCapturingRequested)
505 long offset = getProperty<float>(
"CaptureTimeOffset").getValue() * 1000.0f;
506 timeOfLastImageCapture = IceUtil::Time::now().toMicroSeconds() - offset;
507 cv::Mat depthBuffer(height, width, CV_16UC1);
508 depthImage->fillDepthImageRaw(width, height, (
unsigned short*)depthBuffer.data);
510 std::scoped_lock lock(syncMutex);
514 for (
int j = 0; j < depthBuffer.rows; j++)
516 int index = 3 * (j * width);
517 for (
int i = 0; i < depthBuffer.cols; i++)
519 unsigned short value = depthBuffer.at<
unsigned short>(j, i);
521 rgbImages[1]->pixels[
index + 0],
522 rgbImages[1]->pixels[
index + 1],
523 rgbImages[1]->pixels[
index + 2],
532 newImageCapturingRequested =
false;
534 condition.notify_one();
539 OpenNIPointCloudProvider::grabImages(
const pcl::io::Image::Ptr& RGBImage,
540 const pcl::io::DepthImage::Ptr& depthImage,
541 float reciprocalFocalLength)
546 if (newImageCapturingRequested)
548 long offset = getProperty<float>(
"CaptureTimeOffset").getValue() * 1000.0f;
549 timeOfLastImageCapture = IceUtil::Time::now().toMicroSeconds() - offset;
551 cv::Mat depthBuffer(height, width, CV_16UC1);
552 depthImage->fillDepthImageRaw(width, height, (
unsigned short*)depthBuffer.data);
554 std::scoped_lock lock(syncMutex);
559 for (
int j = 0; j < depthBuffer.rows; j++)
561 int index = 3 * (j * width);
562 for (
int i = 0; i < depthBuffer.cols; i++)
564 unsigned short value = depthBuffer.at<
unsigned short>(j, i);
566 rgbImages[1]->pixels[
index + 0],
567 rgbImages[1]->pixels[
index + 1],
568 rgbImages[1]->pixels[
index + 2],
607 RGBImage->fillRGB(width, height, rgbImages[0]->pixels);
609 newImageCapturingRequested =
false;
611 condition.notify_one();
616 OpenNIPointCloudProvider::doCapture()
619 std::unique_lock lock(syncMutex);
621 newPointCloudCapturingRequested =
true;
622 newImageCapturingRequested =
true;
624 while (captureEnabled && (newPointCloudCapturingRequested || newImageCapturingRequested))
627 condition.wait_for(lock, std::chrono::milliseconds(100));
636 provideImages(rgbImages, IceUtil::Time::microSeconds(timeOfLastImageCapture));
638 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr pointcloud(
639 new pcl::PointCloud<PointXYZRGBA>(*pointcloudBuffer));
641 pointcloud->header.stamp = timeOfLastPointCloudCapture;
642 providePointCloud(pointcloud);
644 heartbeatPlugin->heartbeat();
650 durations[
"report_time_ms"] =
new armarx::Variant(reportTime.toMilliSecondsDouble());
651 debugObserver->setDebugChannel(getName(), durations);
654 lastReportTimestamp = now;
659 std::vector<imrec::ChannelPreferences>
660 OpenNIPointCloudProvider::getImageRecordingChannelPreferences(
const Ice::Current&)
664 imrec::ChannelPreferences rgb;
665 rgb.requiresLossless =
false;
668 imrec::ChannelPreferences depth;
669 depth.requiresLossless =
true;
670 depth.name =
"depth";
676 OpenNIPointCloudProvider::createPropertyDefinitions()
682 OpenNIPointCloudProvider::OpenNIPointCloudProvider()
684 addPlugin(heartbeatPlugin);