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

retrieve rgb from kinect pointcloud

asked 2011-06-08 04:15:38 -0500

quimnuss gravatar image

updated 2016-10-24 09:00:16 -0500

ngrennan gravatar image

Hello! The pointcloud published at camera/rgb/points is sensed to have the rgb at the fourth float

rostopic echo /camera/rgb/points/fields
- 
  name: x
  offset: 0
  datatype: 7
  count: 1
- 
  name: y
  offset: 4
  datatype: 7
  count: 1
- 
  name: z
  offset: 8
  datatype: 7
  count: 1
- 
  name: rgb
  offset: 16
  datatype: 7
  count: 1
---

However, when storing the float with

 float *pstep2 = (float*)&msg->data[(kk) * msg->point_step];
      xi[kk] = pstep2[0]; //x
      yi[kk] = pstep2[1]; //y
      zi[kk] = pstep2[2]; //z
      ci[kk] = pstep2[3]; //rgb

and printing out the float shows how all of them are set to zero.

How can we retrieve the associated rgb values for each 3d point of the pointcloud output by the kinect?

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2011-06-08 05:41:04 -0500

quimnuss gravatar image

updated 2011-06-08 05:41:22 -0500

Yes, we knew that, but the float should be non-zero anyway. Actually using the union

typedef union
  {
    struct /*anonymous*/
    {
      unsigned char Blue;
      unsigned char Green;
      unsigned char Red;
      unsigned char Alpha;
    };
    float float_value;
    long long_value;
  } RGBValue;

returned binary invalid types. But we've solved it converting it first to PointXYZRGB

pcl::PointCloud<pcl::PointXYZRGB>::iterator pt_iter = this->pcl_xyzrgb.begin();
for (int rr = 0; rr < (int)pcl_xyzrgb.height; ++rr) {
  for (int cc = 0; cc < (int)pcl_xyzrgb.width; ++cc, ++pt_iter) {
    pcl::PointXYZRGB &pt = *pt_iter;
    RGBValue color;
    color.float_value= pt.rgb;
    matlab_xyzrgb << rr << " " << cc << " " << pt.x*1000 << " " << pt.y*1000 << " " << pt.z*1000 << " " << (int)color.Red << " " << (int)color.Green << " " << (int)color.Blue << std::endl;
  }
}

The code above works.

edit flag offensive delete link more
2

answered 2011-06-08 05:16:11 -0500

Lorenz gravatar image

The rgb value is stored in just one single float. You can, for instance, use a function like this to decode it:

void getRGB(float rgb_encoded, unsigned char &r, unsigned char &g, unsigned char &b)
{
  const unsigned char *color = reinterpret_cast<const unsigned char *>(&rgb_encoded);
  r = color[2];
  g = color[1];
  b = color[0];
}

When passing *pstep2 of your example as first parameter, you should get correct rgb values.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2011-06-08 04:15:38 -0500

Seen: 1,295 times

Last updated: Jun 08 '11