[ros-users] PCL Visualization tests

Georg Arbeiter georg.arbeiter at ipa.fraunhofer.de
Fri Aug 27 06:40:16 UTC 2010


Thanks for the patch, it seems to be working now.

Georg

Am 26.08.2010 18:23, schrieb Radu Bogdan Rusu:
> 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
>>
>>
>

-- 
Dipl.-Ing. Georg Arbeiter, Fraunhofer IPA
Robotersysteme
Nobelstrasse 12, 70569 Stuttgart
Telefon 0711-970-1299, Fax 0711-970-1008
mailto:georg.arbeiter at ipa.fraunhofer.de
http://ipa.fraunhofer.de



More information about the ros-users mailing list