29 #include <Image/ImageProcessor.h>
31 #include <librealsense2/rs.hpp>
32 #include <librealsense2/rs_advanced_mode.hpp>
33 #include <librealsense2/h/rs_sensor.h>
34 #include <librealsense2/rsutil.h>
45 void IntelRealSenseProvider::onInitImageProvider()
47 Eigen::Vector2f fov = getProperty<Eigen::Vector2f>(
"FieldOfView");
48 depthUtils.setFieldOfView(fov(0), fov(1));
50 Eigen::Vector2i dimensions = getProperty<Eigen::Vector2i>(
"Resolution");
51 setImageFormat(visionx::ImageDimension(dimensions(0), dimensions(1)), visionx::eRgb, visionx::eBayerPatternGr);
53 pointcloud.reset(
new pcl::PointCloud<CloudPointType>());
55 alignFilter.reset(
new rs2::align(RS2_STREAM_COLOR));
58 void IntelRealSenseProvider::onInitCapturingPointCloudProvider()
62 void IntelRealSenseProvider::onExitCapturingPointCloudProvider()
68 void IntelRealSenseProvider::onStartCapture(
float framesPerSecond)
75 Eigen::Vector2i dimensions = getProperty<Eigen::Vector2i>(
"Resolution").getValue();
77 cfg.enable_stream(RS2_STREAM_COLOR, dimensions(0), dimensions(1), RS2_FORMAT_RGB8, framesPerSecond);
78 cfg.enable_stream(RS2_STREAM_DEPTH, dimensions(0), dimensions(1), RS2_FORMAT_Z16, framesPerSecond);
79 rs2::pipeline_profile profile = pipe.start(cfg);
81 rs2::device dev = profile.get_device();
83 rs2::depth_sensor ds = dev.query_sensors().front().as<rs2::depth_sensor>();
85 if (getProperty<std::string>(
"ConfigFile").isSet())
89 auto devices = ctx.query_devices();
90 size_t device_count = devices.size();
93 throw armarx::LocalException(
"No device detected. Is it plugged in?\n");
97 auto dev = devices[0];
100 if (dev.is<rs400::advanced_mode>())
103 auto advanced_mode_dev = dev.as<rs400::advanced_mode>();
106 std::string path = getProperty<std::string>(
"ConfigFile");
110 ARMARX_INFO <<
"Loading realsense config from " << path;
111 std::ifstream t(path);
112 std::string
str((std::istreambuf_iterator<char>(t)), std::istreambuf_iterator<char>());
113 advanced_mode_dev.load_json(
str);
117 throw armarx::LocalException() <<
"Current device doesn't support advanced-mode!\n";
122 auto preset = getProperty<rs2_rs400_visual_preset>(
"Preset").getValue();
123 ARMARX_INFO <<
"Setting preset to: " << rs2_rs400_visual_preset_to_string(preset);
124 ds.set_option(RS2_OPTION_VISUAL_PRESET, preset);
128 depthScale = ds.get_depth_scale();
131 cloudFormat = getPointCloudFormat();
132 calibration = createStereoCalibration(profile);
134 setMetaInfo(
"Baseline",
new Variant(
std::to_string(calibration.calibrationRight.cameraParam.translation[0])
135 +
", " +
std::to_string(calibration.calibrationRight.cameraParam.translation[1]) +
136 ", " +
std::to_string(calibration.calibrationRight.cameraParam.translation[2])));
142 void IntelRealSenseProvider::onStopCapture()
149 bool IntelRealSenseProvider::doCapture()
155 data = pipe.wait_for_frames(timeout);
163 auto rstimestamp =
data.get_timestamp();
165 if (
data.get_frame_timestamp_domain() == RS2_TIMESTAMP_DOMAIN_GLOBAL_TIME)
167 timestamp = IceUtil::Time::milliSeconds(rstimestamp);
174 ARMARX_DEBUG <<
deactivateSpam(1) <<
"frame age: " << (IceUtil::Time::now() - IceUtil::Time::milliSeconds(rstimestamp)).toMilliSeconds() <<
" ms";
177 if (getProperty<bool>(
"ApplyAlignmentFilter").getValue())
184 auto depthFrame =
data.get_depth_frame();
186 const bool applyDisparityFilter = getProperty<bool>(
"ApplyDisparityFilter").getValue();
187 if (applyDisparityFilter)
190 depthFrame = depth_to_disparity_filter.process(depthFrame);
195 if (getProperty<bool>(
"ApplySpatialFilter").getValue())
198 depthFrame = spat_filter.process(depthFrame);
201 if (getProperty<bool>(
"ApplyTemporalFilter").getValue())
204 depthFrame = temporal_filter.process(depthFrame);
208 if (applyDisparityFilter)
211 depthFrame = disparity_to_depth_filter.process(depthFrame);
215 rs2::frame color =
data.get_color_frame();
221 color =
data.get_infrared_frame();
226 const int cw = color.as<rs2::video_frame>().get_width();
227 const int ch = color.as<rs2::video_frame>().get_height();
228 auto colorBuffer =
reinterpret_cast<const unsigned char*
>(color.get_data());
229 CByteImage rgbImage(cw, ch, CByteImage::eRGB24,
true);
230 rgbImage.pixels =
const_cast<unsigned char*
>(colorBuffer);
235 auto resultDepthBuffer = depthImage->pixels;
236 auto depthBuffer =
reinterpret_cast<const unsigned short*
>(depthFrame.get_data());
237 const int dw = depthFrame.as<rs2::video_frame>().get_width();
238 const int dh = depthFrame.as<rs2::video_frame>().get_height();
240 for (
int y = 0; y < dh; ++y)
242 for (
int x = 0; x < dw; ++x)
244 int depthValue = 1000.f * depthBuffer[index2] * depthScale;
252 CByteImage* images[2] = {&rgbImage,
255 provideImages(images, timestamp);
263 points =
pc.calculate(depthFrame);
270 pointcloud->width = dw;
271 pointcloud->height = dh;
272 pointcloud->is_dense =
false;
273 pointcloud->points.resize(points.size());
274 auto ptr = points.get_vertices();
275 auto texPtr = points.get_texture_coordinates();
278 float maxDepth = getProperty<float>(
"MaxDepth").getValue() / 1000.f;
281 for (
auto& p : pointcloud->points)
283 p.x = ptr->x * 1000.f;
284 p.y = ptr->y * 1000.f;
285 p.z = ptr->z <= maxDepth ? ptr->z * 1000.f : std::nan(
"");
288 int x = texPtr->u * cw;
289 int y = texPtr->v * ch;
290 if (x >= 0 && x < cw && y >= 0 && y < ch)
292 auto colorIndex = int((x + y * cw) * 3);
293 p.r = colorBuffer[colorIndex];
294 p.g = colorBuffer[colorIndex + 1];
295 p.b = colorBuffer[colorIndex + 2];
299 p.r = p.g = p.b = 255;
308 pointcloud->header.stamp = timestamp.toMicroSeconds();
309 providePointCloud(pointcloud);
317 std::string IntelRealSenseProvider::getDefaultName()
const
319 return "IntelRealSenseProvider";
325 getConfigIdentifier()));
328 void IntelRealSenseProvider::onInitComponent()
330 ImageProvider::onInitComponent();
331 CapturingPointCloudProvider::onInitComponent();
334 void IntelRealSenseProvider::onConnectComponent()
337 ImageProvider::onConnectComponent();
338 CapturingPointCloudProvider::onConnectComponent();
341 void IntelRealSenseProvider::onDisconnectComponent()
343 captureEnabled =
false;
345 ImageProvider::onDisconnectComponent();
346 CapturingPointCloudProvider::onDisconnectComponent();
349 void IntelRealSenseProvider::onExitComponent()
351 ImageProvider::onExitComponent();
352 CapturingPointCloudProvider::onExitComponent();
356 visionx::StereoCalibration IntelRealSenseProvider::getStereoCalibration(
const Ice::Current&)
361 bool IntelRealSenseProvider::getImagesAreUndistorted(
const Ice::Current&
c)
366 std::string IntelRealSenseProvider::getReferenceFrame(
const Ice::Current&
c)
368 return getProperty<std::string>(
"frameName");
371 StereoCalibration IntelRealSenseProvider::createStereoCalibration(
const rs2::pipeline_profile& selection)
const
375 auto getIntrinsics = [](visionx::CameraParameters & params, rs2::video_stream_profile & streamProfile)
378 auto i = streamProfile.get_intrinsics();
384 params.focalLength.resize(2, 0.0f);
385 params.principalPoint.resize(2, 0.0f);
386 params.distortion.resize(4, 0.0f);
392 params.principalPoint[0] = i.ppx;
393 params.principalPoint[1] = i.ppy;
394 params.focalLength[0] = i.fx;
395 params.focalLength[1] = i.fy;
396 params.width = streamProfile.width();
397 params.height = streamProfile.height();
399 rs2::video_stream_profile rgb_stream = selection.get_stream(RS2_STREAM_COLOR)
400 .as<rs2::video_stream_profile>();
401 rs2::video_stream_profile depth_stream = selection.get_stream(RS2_STREAM_DEPTH)
402 .as<rs2::video_stream_profile>();
404 visionx::CameraParameters rgbParams;
405 visionx::CameraParameters depthParams;
407 getIntrinsics(rgbParams, rgb_stream);
408 getIntrinsics(depthParams, depth_stream);
410 StereoCalibration calibration;
412 auto depth_stream = selection.get_stream(RS2_STREAM_DEPTH);
413 auto color_stream = selection.get_stream(RS2_STREAM_COLOR);
414 rs2_extrinsics e = depth_stream.get_extrinsics_to(color_stream);
416 float origin[3] { 0.f, 0.f, 0.f };
418 rs2_transform_point_to_point(
target, &e, origin);
423 calibration.calibrationLeft.cameraParam = rgbParams;
424 calibration.calibrationRight.cameraParam = depthParams;
427 calibration.calibrationRight.cameraParam.translation = {
target[0],
target[1],
target[2]};