Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Conversion from pixel to 3D point in Camera frame #1339

Open
shrutichakraborty opened this issue Feb 21, 2024 · 1 comment
Open

Conversion from pixel to 3D point in Camera frame #1339

shrutichakraborty opened this issue Feb 21, 2024 · 1 comment

Comments

@shrutichakraborty
Copy link

shrutichakraborty commented Feb 21, 2024

Hello, I have a custom dnn that I used to detect objects through visp. I'd like to have the corners of the detectd boxes in the camera frame and so I was wondering if it is possible to have access to the rs2_deproject_pixel_to_point function from realsense in visp?

Furthermore, I would then like to use the computePlanarObjectPoseFromRGBD() using the pixel coordinates, the de projected 3D coordinates and camera parameters to find the plane, to then use this in a visual servo law to position a robot arm perpendicular to the object (as I have something plat and planar). Do you think this would be possible?

Thanks!

@shrutichakraborty shrutichakraborty changed the title COnversion from ixel to 3D point in Camera frame Conversion from pixel to 3D point in Camera frame Feb 21, 2024
@rolalaro
Copy link

To compute the 3D coordinates expressed in the camera frame corresponding to a pixel, you need the camera intrinsics parameters and the depth that corresponds to the pixel.
You can get the intrinsics parameters of the Realsense camera using vpRealsense2::getCameraParameters.
The depth information of a pixel is obtained by passing a pointer to a rs2::align align_to(RS2_STREAM_COLOR); object to the vpRealsense2::acquire method.
You can finally get the 3D coordinates of the pixel by using [vpPixelToMeterConversion::convertPoint][https://visp-doc.inria.fr/doxygen/visp-daily/classvpPixelMeterConversion.html#af85fde655f43b2213fc031361346cdae) and then multiply the normalized coordinates by the depth.
It would give something like that:

  vpRealSense2 rs;
  rs2::config config;
  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
  rs.open(config);
  vpImage<vpRGBa> Ic(rs.getIntrinsics(RS2_STREAM_COLOR).height, rs.getIntrinsics(RS2_STREAM_COLOR).width);
  vpImage<uint16_t> Id_raw(rs.getIntrinsics(RS2_STREAM_DEPTH).height, rs.getIntrinsics(RS2_STREAM_DEPTH).width);
  rs2::align align_to(RS2_STREAM_COLOR);
  rs.acquire((unsigned char *) Ic.bitmap, (unsigned char *) Id_raw.bitmap, nullptr, nullptr, &align_to);
  float depthScale = rs.getDepthScale();
  unsigned int u = /*your horizontal pixel value */;
  unsigned int v = /*your vertical pixel value */;
  float depth = Id_raw[v][u] * depthScale;
  vpCameraParameters cam = rs.getCameraParameters(RS2_STREAM_COLOR);
  double x, y;
  vpPixelToMeterConversion::convertPoint(cam, u, v, x , y);
 double cX = x * depth;
 double cY = y * depth;

HOWEVER if you want to use computePlanarObjectPoseFromRGBD(), you do not need to convert your 2D points. You just need to convert your vpImage<uint16_t> in a vpImage<float> using the depth scale, and to have the 3D model of your object (i.e. the 3D coordinates of the corners of the object in the object frame).

Hope it helps !

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants