ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

Converting a XYZ Point cloud to a depth image

asked 2018-10-04 09:44:59 -0500

lahiruherath gravatar image

updated 2022-01-12 18:11:33 -0500

lucasw gravatar image

Is there anyway to do the inverse of depth_image_proc/point_cloud_xyz. I need to do some conversions and calculation with pcl and convert information back to a depth image. I have the camera information as well

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2018-10-08 10:49:03 -0500

lahiruherath gravatar image

Hi Stefan, Thanks did something like that. went reverse on whats being done in depth_image_proc/point_cloud_xyz algorithm.

if (cam_info_taken == true){
  sensor_msgs::CameraInfo info = cam_info;
  float centre_x = cam_info.K[2];
  float centre_y = cam_info.K[5];
  float focal_x = cam_info.K[0];
  float focal_y = cam_info.K[4];

  cv::Mat cv_image = cv::Mat(cam_info.height, cam_info.width, CV_32FC1,cv::Scalar(std::numeric_limits<float>::max()));

  for (int i=0; i<msg->points.size();i++){
    if (msg->points[i].z == msg->points[i].z){
        float z = msg->points[i].z*1000.0;
        float u = (msg->points[i].x*1000.0*focal_x) / z;
        float v = (msg->points[i].y*1000.0*focal_y) / z;
        int pixel_pos_x = (int)(u + centre_x);
        int pixel_pos_y = (int)(v + centre_y);

    if (pixel_pos_x > (cam_info.width-1)){
      pixel_pos_x = cam_info.width -1;
    }
    if (pixel_pos_y > (cam_info.height-1)){
      pixel_pos_y = cam_info.height-1;
    }
    cv_image.at<float>(pixel_pos_y,pixel_pos_x) = z;
    }       
  }

  cv_image.convertTo(cv_image,CV_16UC1);

  sensor_msgs::ImagePtr output_image = cv_bridge::CvImage(std_msgs::Header(), "16UC1", cv_image).toImageMsg();
  output_image->header = info.header;
  output_image->header.stamp = info.header.stamp = t;
  publish_result.publish(output_image);
  publish_cam_info.publish(info);
}
edit flag offensive delete link more

Comments

if (msg->points[i].z == msg->points[i].z) always returns true. Could you explain it?

Haozhe Xie gravatar image Haozhe Xie  ( 2020-04-06 02:07:45 -0500 )edit

... he checks the depth for nan value

According to the IEEE standard, NaN values have the odd property that comparisons involving them are always false.

Sagexs gravatar image Sagexs  ( 2020-10-16 03:59:46 -0500 )edit

Hi, did you implemented this as a standalone node or is bundled inside another component?

I'm also looking for the same functionality. it would be nice if you released this as a open source ros node.

AravindaDP gravatar image AravindaDP  ( 2020-11-01 08:42:49 -0500 )edit

Had this in a separate node

lahiruherath gravatar image lahiruherath  ( 2020-11-01 20:13:23 -0500 )edit
2

answered 2018-10-04 18:12:28 -0500

You can use PCL's RangeImagePlanar. Some example code for converting a PointCloud to a cv::Mat depth image can be found here: to_cv_depth_img.h. This is perhaps not the most efficient option as it effectively does Z-buffer based rendering in software, but depending on application might be good enough.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2018-10-04 09:44:59 -0500

Seen: 6,848 times

Last updated: Jan 12 '22