Creating a range image from a cloud of points.

classic Classic list List threaded Threaded
5 messages Options
Reply | Threaded
Open this post in threaded view
|

Creating a range image from a cloud of points.

Javier Correa
I-m trying to build a range image from a cloud of point of a segmented object. Basically I'm doing:

pcl::RangeImage range_image;
Eigen3::Affine3f scene_sensor_pose(Eigen3::Affine3f::Identity());
range_image.createFromPointCloud(cloud_cluster, deg2rad(0.5f), deg2rad(180.0f), deg2rad(180.0f), scene_sensor_pose);

Then i'm passing the image to a OpenCV image like this:
IplImage *tmp = cvCreateImage(cvSize(range_image.width , range_image.height), IPL_DEPTH_8U, 1); 
for(int p_x = 0; p_x < range_image.height; p_x++)
  for(int p_y = 0; p_y < range_image.width; p_y++)
    tmp->imageData[p_x * range_image.width + p_y] = (range_image.getPoint(p_x, p_y).range > 0.0 ? 255 : 0); 

The contour of the object can be distinguish, but it's completely deformed (as if points where missing from the image).

But at the image I'm not getting a correct image of the point cloud. I don't know if i'm doing something wrong or RangeImage isn't working (as i understand that i does).

Could anyone help me?
--
Javier Correa

Por favor, no imprimas este e-mail si realmente no lo necesitas... Conservar el medio ambiente es nuestra tarea...
Please, don't print this e-mail if it's not needed... preserve the environment is our task...


_______________________________________________
[hidden email] / http://pcl.ros.org
https://code.ros.org/mailman/listinfo/pcl-users
Reply | Threaded
Open this post in threaded view
|

Re: Creating a range image from a cloud of points.

Radu B. Rusu
Administrator
Javier,

I can offer a quick reply until Bastian wakes up and provides a better answer.


On 11/29/2010 11:05 AM, Javier Correa wrote:
> The contour of the object can be distinguish, but it's completely deformed (as if points where missing from the image).
>
> But at the image I'm not getting a correct image of the point cloud. I don't know if i'm doing something wrong or
> RangeImage isn't working (as i understand that i does).

If I understand correctly, you're expecting the image to be rectangular, but the data that gets filled has an ellipsoid
structure, like here: http://www.ros.org/presentations/2010-09-Steder-NARF-PCL.pdf (slide 3, bottom picture) ? If so,
this is perfectly normal.

You can always attach the image that you have so we can understand the issues better.

Cheers,
Radu.
_______________________________________________
[hidden email] / http://pcl.ros.org
https://code.ros.org/mailman/listinfo/pcl-users
Reply | Threaded
Open this post in threaded view
|

Re: Creating a range image from a cloud of points.

Bastian Steder
In reply to this post by Javier Correa
Hi Javier,

as Radu already said, I could make a more educated guess if you could
provide the picture.
But here a few things that might help:

If you have the pcl_tutorials package available, I would propose to try

rosrun pcl_tutorials tutorial_range_image_visualization your_point_cloud.pcd

This will visualize your range image using RangeImageVisualizer from
pcl_visualization (and also the point cloud in the 3D viewer).
If this looks OK there might be a problem in the opencv-part.
If it doesn't, one reason for it to look completely distorted might be
the used coordinate system. By default the range image uses the camera
frame with z to the front and x to the right. To change this to x to the
front and z to the top you can try

rosrun pcl_tutorials tutorial_range_image_visualization -c 1
your_point_cloud.pcd

or
range_image.createFromPointCloud(cloud_cluster, deg2rad(0.5f),
deg2rad(180.0f), deg2rad(180.0f), scene_sensor_pose,
RangeImage::LASER_FRAME);
in your code.

A bit of distortion is normal, since the range image uses a spherical
coordinates (so that 360deg can be represented).

If there are holes in the image it might be because the resolution of
your point cloud is lower than the one you chose for the range image.

If non of this helps, please send a screenshot of the image. Best from
both, tutorial_range_image_visualization and your program.

Cheers,
Bastian


On 11/29/2010 08:05 PM, Javier Correa wrote:

> I-m trying to build a range image from a cloud of point of a segmented
> object. Basically I'm doing:
>
> pcl::RangeImage range_image;
> Eigen3::Affine3f scene_sensor_pose(Eigen3::Affine3f::Identity());
> range_image.createFromPointCloud(cloud_cluster, deg2rad(0.5f),
> deg2rad(180.0f), deg2rad(180.0f), scene_sensor_pose);
>
> Then i'm passing the image to a OpenCV image like this:
> IplImage *tmp = cvCreateImage(cvSize(range_image.width ,
> range_image.height), IPL_DEPTH_8U, 1);
> for(int p_x = 0; p_x < range_image.height; p_x++)
>    for(int p_y = 0; p_y < range_image.width; p_y++)
>      tmp->imageData[p_x * range_image.width + p_y] =
> (range_image.getPoint(p_x, p_y).range > 0.0 ? 255 : 0);
>
> The contour of the object can be distinguish, but it's completely
> deformed (as if points where missing from the image).
>
> But at the image I'm not getting a correct image of the point cloud. I
> don't know if i'm doing something wrong or RangeImage isn't working (as
> i understand that i does).
>
> Could anyone help me?
> --
> Javier Correa
>
> Por favor, no imprimas este e-mail si realmente no lo necesitas...
> Conservar el medio ambiente es nuestra tarea...
> Please, don't print this e-mail if it's not needed... preserve the
> environment is our task...
>
>
>
> _______________________________________________
> [hidden email] / http://pcl.ros.org
> https://code.ros.org/mailman/listinfo/pcl-users


--
Bastian Steder

Albert-Ludwigs-University
Institute of Computer Science
Autonomous Intelligent Systems
Georges-Koehler-Allee 079
D-79110 Freiburg, Germany

Phone:  +49 (761) 203-8013
Fax  :  +49 (761) 203-8007
_______________________________________________
[hidden email] / http://pcl.ros.org
https://code.ros.org/mailman/listinfo/pcl-users
Reply | Threaded
Open this post in threaded view
|

Re: Creating a range image from a cloud of points.

Javier Correa Villanueva
Hi again, now I'm sending the email from the correct email.

I made a little video with my problem. I'm using a range camera (kinect right now) as my input.

As can be seen on the video, sometimes the hand shape can be distinguish, but in general it gets deformed.

I'll try to make a point cloud file to post it.

On Tue, Nov 30, 2010 at 9:46 AM, Bastian Steder <[hidden email]> wrote:
Hi Javier,

as Radu already said, I could make a more educated guess if you could provide the picture.
But here a few things that might help:

If you have the pcl_tutorials package available, I would propose to try

rosrun pcl_tutorials tutorial_range_image_visualization your_point_cloud.pcd

This will visualize your range image using RangeImageVisualizer from pcl_visualization (and also the point cloud in the 3D viewer).
If this looks OK there might be a problem in the opencv-part.
If it doesn't, one reason for it to look completely distorted might be the used coordinate system. By default the range image uses the camera frame with z to the front and x to the right. To change this to x to the front and z to the top you can try

rosrun pcl_tutorials tutorial_range_image_visualization -c 1 your_point_cloud.pcd

or
range_image.createFromPointCloud(cloud_cluster, deg2rad(0.5f), deg2rad(180.0f), deg2rad(180.0f), scene_sensor_pose, RangeImage::LASER_FRAME);
in your code.

A bit of distortion is normal, since the range image uses a spherical coordinates (so that 360deg can be represented).

If there are holes in the image it might be because the resolution of your point cloud is lower than the one you chose for the range image.

If non of this helps, please send a screenshot of the image. Best from both, tutorial_range_image_visualization and your program.

Cheers,
Bastian



On 11/29/2010 08:05 PM, Javier Correa wrote:
I-m trying to build a range image from a cloud of point of a segmented
object. Basically I'm doing:

pcl::RangeImage range_image;
Eigen3::Affine3f scene_sensor_pose(Eigen3::Affine3f::Identity());
range_image.createFromPointCloud(cloud_cluster, deg2rad(0.5f),
deg2rad(180.0f), deg2rad(180.0f), scene_sensor_pose);

Then i'm passing the image to a OpenCV image like this:
IplImage *tmp = cvCreateImage(cvSize(range_image.width ,
range_image.height), IPL_DEPTH_8U, 1);
for(int p_x = 0; p_x < range_image.height; p_x++)
  for(int p_y = 0; p_y < range_image.width; p_y++)
    tmp->imageData[p_x * range_image.width + p_y] =
(range_image.getPoint(p_x, p_y).range > 0.0 ? 255 : 0);

The contour of the object can be distinguish, but it's completely
deformed (as if points where missing from the image).

But at the image I'm not getting a correct image of the point cloud. I
don't know if i'm doing something wrong or RangeImage isn't working (as
i understand that i does).

Could anyone help me?
--
Javier Correa

Por favor, no imprimas este e-mail si realmente no lo necesitas...
Conservar el medio ambiente es nuestra tarea...
Please, don't print this e-mail if it's not needed... preserve the
environment is our task...



_______________________________________________
[hidden email] / http://pcl.ros.org
https://code.ros.org/mailman/listinfo/pcl-users


--
Bastian Steder

Albert-Ludwigs-University
Institute of Computer Science
Autonomous Intelligent Systems
Georges-Koehler-Allee 079
D-79110 Freiburg, Germany

Phone:  +49 (761) 203-8013
Fax  :  +49 (761) 203-8007


_______________________________________________
[hidden email] / http://pcl.ros.org
https://code.ros.org/mailman/listinfo/pcl-users
Reply | Threaded
Open this post in threaded view
|

Re: Creating a range image from a cloud of points.

Javier Correa Villanueva
I've found the problem. It was an my issue with opencv. Basically I did:

IplImage *tmp = cvCreateImage(cvSize(range_image.width , range_image.height), IPL_DEPTH_8U, 1); 
for(int p_x = 0; p_x < tmp->width; p_x++)
  for(int p_y = 0; p_y < tmp->height; p_y++)
    tmp->imageData[p_y*tmp->widthStep + p_x] = (range_image.getPoint(p_x, p_y).range > 0.0 ? 255 : 0);




On Tue, Nov 30, 2010 at 3:57 PM, Javier Correa Villanueva <[hidden email]> wrote:
Hi again, now I'm sending the email from the correct email.

I made a little video with my problem. I'm using a range camera (kinect right now) as my input.

As can be seen on the video, sometimes the hand shape can be distinguish, but in general it gets deformed.

I'll try to make a point cloud file to post it.

On Tue, Nov 30, 2010 at 9:46 AM, Bastian Steder <[hidden email]> wrote:
Hi Javier,

as Radu already said, I could make a more educated guess if you could provide the picture.
But here a few things that might help:

If you have the pcl_tutorials package available, I would propose to try

rosrun pcl_tutorials tutorial_range_image_visualization your_point_cloud.pcd

This will visualize your range image using RangeImageVisualizer from pcl_visualization (and also the point cloud in the 3D viewer).
If this looks OK there might be a problem in the opencv-part.
If it doesn't, one reason for it to look completely distorted might be the used coordinate system. By default the range image uses the camera frame with z to the front and x to the right. To change this to x to the front and z to the top you can try

rosrun pcl_tutorials tutorial_range_image_visualization -c 1 your_point_cloud.pcd

or
range_image.createFromPointCloud(cloud_cluster, deg2rad(0.5f), deg2rad(180.0f), deg2rad(180.0f), scene_sensor_pose, RangeImage::LASER_FRAME);
in your code.

A bit of distortion is normal, since the range image uses a spherical coordinates (so that 360deg can be represented).

If there are holes in the image it might be because the resolution of your point cloud is lower than the one you chose for the range image.

If non of this helps, please send a screenshot of the image. Best from both, tutorial_range_image_visualization and your program.

Cheers,
Bastian



On 11/29/2010 08:05 PM, Javier Correa wrote:
I-m trying to build a range image from a cloud of point of a segmented
object. Basically I'm doing:

pcl::RangeImage range_image;
Eigen3::Affine3f scene_sensor_pose(Eigen3::Affine3f::Identity());
range_image.createFromPointCloud(cloud_cluster, deg2rad(0.5f),
deg2rad(180.0f), deg2rad(180.0f), scene_sensor_pose);

Then i'm passing the image to a OpenCV image like this:
IplImage *tmp = cvCreateImage(cvSize(range_image.width ,
range_image.height), IPL_DEPTH_8U, 1);
for(int p_x = 0; p_x < range_image.height; p_x++)
  for(int p_y = 0; p_y < range_image.width; p_y++)
    tmp->imageData[p_x * range_image.width + p_y] =
(range_image.getPoint(p_x, p_y).range > 0.0 ? 255 : 0);

The contour of the object can be distinguish, but it's completely
deformed (as if points where missing from the image).

But at the image I'm not getting a correct image of the point cloud. I
don't know if i'm doing something wrong or RangeImage isn't working (as
i understand that i does).

Could anyone help me?
--
Javier Correa

Por favor, no imprimas este e-mail si realmente no lo necesitas...
Conservar el medio ambiente es nuestra tarea...
Please, don't print this e-mail if it's not needed... preserve the
environment is our task...



_______________________________________________
[hidden email] / http://pcl.ros.org
https://code.ros.org/mailman/listinfo/pcl-users


--
Bastian Steder

Albert-Ludwigs-University
Institute of Computer Science
Autonomous Intelligent Systems
Georges-Koehler-Allee 079
D-79110 Freiburg, Germany

Phone:  +49 (761) 203-8013
Fax  :  +49 (761) 203-8007



_______________________________________________
[hidden email] / http://pcl.ros.org
https://code.ros.org/mailman/listinfo/pcl-users