[ros-users] PCL Visualization tests

Radu Bogdan Rusu rusu at willowgarage.com
Thu Aug 26 16:23:43 UTC 2010


Georg,

Good catch. We seem to have a small bug that got introduced recently. Can you apply the following patch and let me know 
if it works? I'll make a release that incorporates it at the end of the week.

Index: src/libpcl_visualization/pcl_visualizer.cpp
===================================================================
--- src/libpcl_visualization/pcl_visualizer.cpp	(revision 31992)
+++ src/libpcl_visualization/pcl_visualizer.cpp	(working copy)
@@ -658,11 +658,13 @@

    vtkSmartPointer<vtkDataArray> scalars = data->GetPointData ()->GetScalars ();
    double minmax[2];
-  scalars->GetRange (minmax);
+  if (scalars)
+    scalars->GetRange (minmax);

    vtkSmartPointer<vtkDataSetMapper> mapper = vtkSmartPointer<vtkDataSetMapper>::New ();
    mapper->SetInput (data);
-  mapper->SetScalarRange (minmax);
+  if (scalars)
+    mapper->SetScalarRange (minmax);
    mapper->SetScalarModeToUsePointData ();
    mapper->ScalarVisibilityOn ();

Thanks,
Radu.

On 08/26/2010 07:41 AM, Georg Arbeiter wrote:
> Hi!
>
> When I try to run the test_shapes example in pcl_visualization the
> application crashes with a seg fault. gdb backtrace is the following:
>
> Program received signal SIGSEGV, Segmentation fault.
> pcl_visualization::PCLVisualizer::createActorFromVTKDataSet
> (this=0xbfffeeac,
>       data=..., actor=...)
>       at
> /opt/ros/cturtle/stacks/point_cloud_perception/pcl_visualization/src/libpcl_visualization/pcl_visualizer.cpp:661
> 661      scalars->GetRange (minmax);
> (gdb) bt
> #0  pcl_visualization::PCLVisualizer::createActorFromVTKDataSet (
>       this=0xbfffeeac, data=..., actor=...)
>       at
> /opt/ros/cturtle/stacks/point_cloud_perception/pcl_visualization/src/libpcl_visualization/pcl_visualizer.cpp:661
> #1  0x0804bd9f in
> pcl_visualization::PCLVisualizer::addPolygon<pcl::PointXYZ>  (
>       argc=1, argv=0xbffff104)
>       at
> /opt/ros/cturtle/stacks/point_cloud_perception/pcl_visualization/src/libpcl_visualization/pcl_visualizer.hpp:549
> #2  pcl_visualization::PCLVisualizer::addPolygon<pcl::PointXYZ>  (argc=1,
>       argv=0xbffff104)
>       at
> /opt/ros/cturtle/stacks/point_cloud_perception/pcl_visualization/src/libpcl_visualization/pcl_visualizer.hpp:571
> #3  main (argc=1, argv=0xbffff104)
>       at
> /opt/ros/cturtle/stacks/point_cloud_perception/pcl_visualization/src/test_shapes.cpp:28
>
> The same happens when i try to use the addLine or addSphere function.
> Can you tell me how to fix this?
>
> Best regards,
> Georg
>
>

-- 
| Radu Bogdan Rusu | http://rbrusu.com/



More information about the ros-users mailing list