librealsense: Getting wrong values for 3D point and rs2_deproject_pixel_to_point

Using ROS1 C++. Realsense D431i, latest version of realsense libraries, on Ubuntu 20.04

Introduction

In the following piece of code, I have a point from a D435i camera, post processed to do object detection, and I am interested in the 3D dimensions marked by point sideA.x, sideA.y which correspond to column, row in the color frame.

rs2_intrinsics intrinsics;
intrinsics = selection.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>().get_intrinsics();float pixel[2];
float my3Dpoint[3]; // x, y, z
pixel[0] = sideA.x;
pixel[1] = sideA.y;
rs2_deproject_pixel_to_point (my3Dpoint, &intrinsics, pixel, heightOfCamera);

The camera is mounted on the wrist of a 6dof arm, and positioned pot a pose double r=0., p=1.5, y=0 which means aligned with the world frame x and y, rotated facing and parallel to the flat surface below formed by x and y, at a known camera height through a value of z in the pose adjusted by the camera actual position from the end effector:

float heightOfCamera = nextPose.position.z + 0.03;

Before using the robot’s pose z as a source of depth of the point, I used this …

float depthofPoint = depth.get_distance (sideA.x, sideA.y);
rs2_deproject_pixel_to_point (my3Dpoint, &intrinsics, pixel, depthofPoint);

(BTW I am doing this exercise in an effort to diagnose problems iwith code I wrote to use a Eye-On-Hand calibration matrix…)

The Problem

The return values for x and y in my3Dpoint are smaller by about 40% from the actual values with both methdos for determining the depth of the pixel needed by rs2_deproject_pixel_to_point …

Ive read the material pointed to in this reply but did not find a guiding light there.

Guidance is much appreciated… Thanks in advance, Dave

About this issue

  • Original URL
  • State: closed
  • Created 2 years ago
  • Comments: 72

Most upvoted comments

My support colleagues have analyzed this case and provided feedback.

  1. It should not be assumed that the center of the image will coincide with (0, 0, 0). Instead, it depends on the sensor. The principal point may not be exactly the center of the sensor. Often, there is a small offset.

  2. There are multiple ways to find the 3D point in the depth coordinates system from a known pixel in the color image. Scripts for three different methods are provided below.


Method 1 - align depth to color, deproject pixel into point in color coordinate systems, then transform the point back to depth coordinate system.

rs2::align align_to(RS2_STREAM_COLOR);
       rs2::pipeline pipe;
       rs2::config cfg;
       cfg.enable_stream(RS2_STREAM_DEPTH, 1280, 720, RS2_FORMAT_Z16, 15);
       cfg.enable_stream(RS2_STREAM_COLOR, 1280, 720, RS2_FORMAT_RGBA8, 15);

       auto profile = pipe.start(cfg);

       while (app)
       {
              // Wait for the next set of frames from the camera
              auto frames = pipe.wait_for_frames();

       auto depth = frames.get_depth_frame();
              auto color = frames.get_color_frame();

              rs2_extrinsics color_extrin_to_depth = color.get_profile().as<rs2::video_stream_profile>().get_extrinsics_to(depth.get_profile().as<rs2::video_stream_profile>());

              frames = frames.apply_filter(align_to);
              auto color_aligned = frames.get_color_frame();
              auto depth_aligned = frames.get_depth_frame();

              rs2_intrinsics intr_depth = depth_aligned.get_profile().as<rs2::video_stream_profile>().get_intrinsics();

              // pixel in color coordinate system
              float u = 0.5;
              float v = 0.5;

              int w = color_aligned.get_width();
              int h = color_aligned.get_height();

              int c = w * u;
              int r = h * v;

              // assume depth and color same size after alignment, find depth pixel in color coordinate system
              float pixel[2];
              pixel[0] = c;
              pixel[1] = r;

              float point_in_color_coordinates[3]; // 3D point in color sensor coordinates
              float point_in_depth_coordinates[3]; // 3D point in depth sensor coordinates

              auto dist = depth.get_distance(static_cast<int>(pixel[0]), static_cast<int>(pixel[1]));
              rs2_deproject_pixel_to_point(point_in_color_coordinates, &intr_depth, pixel, dist);
              rs2_transform_point_to_point(point_in_depth_coordinates, &color_extrin_to_depth, point_in_color_coordinates);
       }

Method 2 – do not align, use the original depth and color images, rs2_project_color_pixel_to_depth_pixel, then rs2_deproject_pixel_to_point.

void getRealSense3DPoint(float result3DPoint[3], int c, int r, const rs2::depth_frame& depth, rs2_intrinsics* depth_intrin, rs2_intrinsics* color_intrin, rs2_extrinsics* color_extrin_to_depth, rs2_extrinsics* depth_extrin_to_color)
{

       float rgb_pixel[2], depth_pixel[2];
       int int_depth_pixel[2];
       rgb_pixel[0] = float(c); // col in RGB frame
       rgb_pixel[1] = float(r); // row  in RGB frame

       float depth_scale = depth.get_units();

       rs2_project_color_pixel_to_depth_pixel(depth_pixel,
              reinterpret_cast<const uint16_t*>(depth.get_data()),
              depth_scale,
              0.20, 2.0,  // From 0 to 2 meters Min to Max depth
              depth_intrin,
              color_intrin,
              color_extrin_to_depth,
              depth_extrin_to_color, rgb_pixel);

       int_depth_pixel[0] = (int)round(depth_pixel[0]);
       int_depth_pixel[1] = (int)round(depth_pixel[1]);
       depth_pixel[0] = int_depth_pixel[0];
       depth_pixel[1] = int_depth_pixel[1];

       auto dist = depth.get_distance(static_cast<int>(depth_pixel[0]), static_cast<int>(depth_pixel[1]));

       rs2_deproject_pixel_to_point(result3DPoint, depth_intrin, depth_pixel, dist);
}

Method 3 – align depth and use point cloud.

            rs2::pointcloud pc;
             rs2::points points;
             rs2::align align_to(RS2_STREAM_COLOR);

             rs2::pipeline pipe;
             rs2::config cfg;

             cfg.enable_stream(RS2_STREAM_DEPTH, 1280, 720, RS2_FORMAT_Z16, 15);
             cfg.enable_stream(RS2_STREAM_COLOR, 1280, 720, RS2_FORMAT_RGBA8, 15);

             auto profile = pipe.start(cfg);
             … …

             // Wait for the next set of frames from the camera
             auto frames = pipe.wait_for_frames();

             auto depth = frames.get_depth_frame();
             auto color = frames.get_color_frame();

             rs2_intrinsics intr_depth = depth.get_profile().as<rs2::video_stream_profile>().get_intrinsics(); // Calibration data
             rs2_intrinsics intr_color = color.get_profile().as<rs2::video_stream_profile>().get_intrinsics();
             rs2_extrinsics color_extrin_to_depth = color.get_profile().as<rs2::video_stream_profile>().get_extrinsics_to(depth.get_profile().as<rs2::video_stream_profile>());
             rs2_extrinsics depth_extrin_to_color = depth.get_profile().as<rs2::video_stream_profile>().get_extrinsics_to(color.get_profile().as<rs2::video_stream_profile>());

             frames = frames.apply_filter(align_to);
             auto color_aligned = frames.get_color_frame();

             // Tell pointcloud object to map to this color frame
             pc.map_to(color_aligned);

             auto depth_aligned = frames.get_depth_frame();

             // Generate the pointcloud and texture mappings
             points = pc.calculate(depth_aligned);

             // pixel in color image
             float u = 0.609375; // 780
             float v = 0.488889; // 352

             int w = color_aligned.get_width();
             int h = color_aligned.get_height();

             int c = w * u;
             int r = h * v;

             int index = c + w * r;

             // find corresponding depth point from vertices
             const rs2::vertex* tv = points.get_vertices();
             float x = tv[index].x;
             float y = tv[index].y;
             float z = tv[index].z;

             float point_in_color_coordinates[3]; // 3D point in color sensor coordinates
             float point_in_depth_coordinates[3]; // 3D point in depth sensor coordinates

             point_in_color_coordinates[0] = x;
             point_in_color_coordinates[1] = y;
             point_in_color_coordinates[2] = z;

             // transform 3d point from color coordinates into depth coordinates
             rs2_transform_point_to_point(point_in_depth_coordinates, &color_extrin_to_depth, point_in_color_coordinates);