27 #include <pcl/common/transforms.h>
29 #include <VirtualRobot/MathTools.h>
38 #include <Calibration/Calibration.h>
39 #include <Calibration/StereoCalibration.h>
40 #include <Image/ImageProcessor.h>
41 #include <rc_genicam_api/buffer.h>
42 #include <rc_genicam_api/config.h>
43 #include <rc_genicam_api/image.h>
44 #include <rc_genicam_api/interface.h>
45 #include <rc_genicam_api/pixel_formats.h>
46 #include <rc_genicam_api/system.h>
54 using Point = pcl::PointXYZRGBA;
60 rcg_getColor(uint8_t rgb[3],
61 const std::shared_ptr<const rcg::Image>& img,
69 if (img->getPixelFormat() == Mono8)
71 size_t lstep = img->getWidth() + img->getXPadding();
72 const uint8_t* p = img->getPixels() + k * lstep + i;
74 uint32_t g = 0,
n = 0;
76 for (uint32_t kk = 0; kk < ds; kk++)
78 for (uint32_t ii = 0; ii < ds; ii++)
87 rgb[2] = rgb[1] = rgb[0] =
static_cast<uint8_t
>(g /
n);
89 else if (img->getPixelFormat() == YCbCr411_8)
91 size_t lstep = (img->getWidth() >> 2) * 6 + img->getXPadding();
92 const uint8_t* p = img->getPixels() + k * lstep;
99 for (uint32_t kk = 0; kk < ds; kk++)
101 for (uint32_t ii = 0; ii < ds; ii++)
104 rcg::convYCbCr411toRGB(
v, p,
static_cast<int>(i + ii));
115 rgb[0] =
static_cast<uint8_t
>(r /
n);
116 rgb[1] =
static_cast<uint8_t
>(g /
n);
117 rgb[2] =
static_cast<uint8_t
>(b /
n);
123 storePointCloud(
double f,
126 std::shared_ptr<const rcg::Image> intensityCombined,
127 std::shared_ptr<const rcg::Image> disp,
133 size_t width = disp->getWidth();
134 size_t height = disp->getHeight();
135 bool bigendian = disp->isBigEndian();
136 size_t leftWidth = intensityCombined->getWidth();
137 size_t ds = (leftWidth + disp->getWidth() - 1) / disp->getWidth();
145 const uint8_t* dps = disp->getPixels();
146 size_t dstep = disp->getWidth() *
sizeof(uint16_t) + disp->getXPadding();
151 for (
size_t k = 0; k < height; k++)
154 for (
size_t i = 0; i < width; i++)
156 if ((dps[j] | dps[j + 1]) != 0)
166 dps = disp->getPixels();
169 outPoints->
reserve(height * width);
173 for (
size_t k = 0; k < height; k++)
175 for (
size_t i = 0; i < width; i++)
183 d = scale * ((dps[j] << 8) | dps[j + 1]);
188 d = scale * ((dps[j + 1] << 8) | dps[j]);
197 double x = (i + 0.5 - 0.5 * width) * t / d;
198 double y = (k + 0.5 - 0.5 * height) * t / d;
199 double z = f * t / d;
208 uint8_t rgb[3] = {0, 0, 0};
212 static_cast<uint32_t
>(ds),
213 static_cast<uint32_t
>(i),
214 static_cast<uint32_t
>(k));
218 const double meterToMillimeter = 1000.0f;
219 point.x =
x * meterToMillimeter;
220 point.y = y * meterToMillimeter;
221 point.z = z * meterToMillimeter;
245 updateFinalCloudTransform(getProperty<float>(
"PointCloud_Scale_X").getValue(),
246 getProperty<float>(
"PointCloud_Scale_Y").getValue(),
247 getProperty<float>(
"PointCloud_Scale_Z").getValue(),
248 getProperty<float>(
"PointCloud_Rotate_Roll").getValue(),
249 getProperty<float>(
"PointCloud_Rotate_Pitch").getValue(),
250 getProperty<float>(
"PointCloud_Rotate_Yaw").getValue(),
251 getProperty<float>(
"PointCloud_Translate_X").getValue(),
252 getProperty<float>(
"PointCloud_Translate_Y").getValue(),
253 getProperty<float>(
"PointCloud_Translate_Z").getValue());
284 if (!
initDevice(getProperty<std::string>(
"DeviceId")))
298 if (rcg::setEnum(
nodemap,
"PixelFormat",
"YCbCr411_8",
false))
308 "/tmp/armar6_rc_point_cloud_calibration.txt");
310 std::string depthQuality = getProperty<std::string>(
"DepthImageResolution").getValue();
315 catch (std::invalid_argument& e)
318 ARMARX_WARNING <<
"Selected DepthImageResolution '" << depthQuality.c_str()
319 <<
"' is currently not available for this device. "
324 <<
" (out of Low, Medium, High, Full)";
331 scan3dCoordinateScale =
332 rcg::getFloat(
nodemap,
"Scan3dCoordinateScale",
nullptr,
nullptr,
true);
360 const rcg::Buffer* buffer =
stream->grab(10000);
369 if (buffer->getIsIncomplete() || !buffer->getImagePresent(0))
377 uint64_t pixelformat = buffer->getPixelFormat(0);
378 if (pixelformat == Mono8 || pixelformat == YCbCr411_8)
380 intensityBuffer.add(buffer, 0);
382 else if (pixelformat == Coord3D_C16)
384 disparityBuffer.add(buffer, 0);
393 uint64_t
timestamp = buffer->getTimestampNS();
395 std::shared_ptr<const rcg::Image> intensityCombined = intensityBuffer.find(
timestamp);
396 std::shared_ptr<const rcg::Image> disparity = disparityBuffer.find(
timestamp);
398 if (!intensityCombined || !disparity)
410 scan3dCoordinateScale,
422 int width = imageFormat.dimension.width;
423 int height = imageFormat.dimension.height;
431 const uint8_t* p = intensityCombined->getPixels();
433 size_t px = intensityCombined->getXPadding();
434 uint64_t format = intensityCombined->getPixelFormat();
466 PointCloud::Ptr transformedPointCloud(
new PointCloud());
467 const auto& tr = getFinalCloudTransform();
469 pcl::transformPointCloud(*pointCloud, *transformedPointCloud, tr);
490 throw std::runtime_error(
"Not yet implemented");
504 std::string prefix) :
505 armarx::ComponentPropertyDefinitions(prefix)
509 defineOptionalProperty<std::string>(
"DeviceId",
"00_14_2d_2c_6e_ed",
"");
510 defineOptionalProperty<float>(
"ScaleFactor", 2.0,
"Image down scale factor");
511 defineOptionalProperty<float>(
"framerate",
513 "Frames per second, actual framerate is equal to min(this "
514 "framerate, framerate provided by the device)")
515 .setMatchRegex(
"\\d+(.\\d*)?")
518 defineOptionalProperty<bool>(
"isEnabled",
true,
"enable the capturing process immediately");
519 defineOptionalProperty<std::string>(
520 "DepthImageResolution",
522 "Resolution of the depth image. "
523 "The higher the resolution, the lower the framerate provided by the device")
524 .setCaseInsensitive(
true)
530 defineOptionalProperty<std::string>(
531 "ReferenceFrameName",
"Roboception_LeftCamera",
"Optional reference frame name.");
533 defineOptionalProperty<float>(
"PointCloud_Scale_X", 1.0,
"");
534 defineOptionalProperty<float>(
"PointCloud_Scale_Y", 1.0,
"");
535 defineOptionalProperty<float>(
"PointCloud_Scale_Z", 1.0,
"");
536 defineOptionalProperty<float>(
"PointCloud_Translate_X", 0,
"");
537 defineOptionalProperty<float>(
"PointCloud_Translate_Y", 0,
"");
538 defineOptionalProperty<float>(
"PointCloud_Translate_Z", 0,
"");
539 defineOptionalProperty<float>(
"PointCloud_Rotate_Roll", 0,
"");
540 defineOptionalProperty<float>(
"PointCloud_Rotate_Pitch", 0,
"");
541 defineOptionalProperty<float>(
"PointCloud_Rotate_Yaw", 0,
"");
545 RCPointCloudProvider::buildGui()
547 const auto& srt = finalCloudTransform.getWriteBuffer();
558 .
addChild(
new armarx::RemoteGui::HSpacer)
564 .
addChild(
new armarx::RemoteGui::HSpacer)
570 .
addChild(
new armarx::RemoteGui::HSpacer);
577 updateFinalCloudTransform(prx.
getValue<
float>(
"sx").get(),
589 RCPointCloudProvider::updateFinalCloudTransform(
float sx,
599 finalCloudTransform.getWriteBuffer()(0) = sx;
600 finalCloudTransform.getWriteBuffer()(1) = sy;
601 finalCloudTransform.getWriteBuffer()(2) = sz;
603 finalCloudTransform.getWriteBuffer()(3) = rx;
604 finalCloudTransform.getWriteBuffer()(4) = ry;
605 finalCloudTransform.getWriteBuffer()(5) = rz;
607 finalCloudTransform.getWriteBuffer()(6) = tx;
608 finalCloudTransform.getWriteBuffer()(7) = ty;
609 finalCloudTransform.getWriteBuffer()(8) = tz;
611 finalCloudTransform.commitWrite();
615 RCPointCloudProvider::getFinalCloudTransform()
617 const auto& srt = finalCloudTransform.getUpToDateReadBuffer();
618 return VirtualRobot::MathTools::posrpy2eigen4f(
619 srt(6), srt(7), srt(8), srt(4), srt(5), srt(6)) *
620 Eigen::Vector4f{srt(0), srt(1), srt(2), 1.f}.asDiagonal();