PCL filter nodelet crashes [closed]
I'm running a sequence of pcl filter nodelets (StatisticalOutlier -> VoxelGrid) and we are seeing frequent, spontaneous crashes. Oddly, it seems only this combination causes the crash, with only a single filter, or the reverse input/output order working fine.
I have a launch and bag file (attached) that produce a crash which has been confirmed on two machines. Provided a sanity check passes, how can I forward this to appropriate place as a bug report?
<launch>
<node pkg="nodelet" type="nodelet" name="pcl_filter_manager" args="manager"/>
<!-- Outlier filter -->
<node pkg="nodelet" type="nodelet" name="outlier_filter"
args="load pcl/StatisticalOutlierRemoval pcl_filter_manager" >
<param name="mean_k" type="int" value="2" />
<param name="stddev" type="double" value="0.2" />
<param name="negative" type="bool" value="false" />
<remap from="outlier_filter/input" to="umdetc/cloud" />
<remap from="outlier_filter/output" to="cloud_filter1" />
</node>
<!-- Voxel grid filter -->
<node pkg="nodelet" type="nodelet" name="voxel_filter"
args="load pcl/VoxelGrid pcl_filter_manager">
<param name="leaf_size" type="double" value="0.01" />
<remap from="voxel_filter/input" to="cloud_filter1" />
<remap from="voxel_filter/output" to="cloud_filtered"/>
</node>
</launch>
#0 0xace1346b in flann::KDTreeSingleIndex<flann::L2_Simple<float> >::computeBoundingBox(std::vector<flann::KDTreeSingleIndex<flann::L2_Simple<float> >::Interval, std::allocator<flann::KDTreeSingleIndex<flann::L2_Simple<float> >::Interval> >&) () from /opt/ros/fuerte/lib/libpcl_surface.so.1.5
#1 0xace13585 in flann::KDTreeSingleIndex<flann::L2_Simple<float> >::buildIndex() () from /opt/ros/fuerte/lib/libpcl_surface.so.1.5
#2 0xb42c38f2 in pcl::KdTreeFLANN<pcl::PointXYZ, flann::L2_Simple<float> >::setInputCloud(boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ> const> const&, boost::shared_ptr<std::vector<int, std::allocator<int> > const> const&) ()
from /opt/ros/fuerte/lib/libpcl_kdtree.so.1.5
#3 0xad229e09 in pcl::search::KdTree<pcl::PointXYZ>::setInputCloud(boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ> const> const&, boost::shared_ptr<std::vector<int, std::allocator<int> > const> const&) ()
from /opt/ros/fuerte/lib/libpcl_filters.so.1.5
#4 0xad2acc30 in pcl::StatisticalOutlierRemoval<sensor_msgs::PointCloud2_<std::allocator<void> > >::applyFilter(sensor_msgs::PointCloud2_<std::allocator<void> >&) () from /opt/ros/fuerte/lib/libpcl_filters.so.1.5
#5 0xad1d8e3e in pcl::Filter<sensor_msgs::PointCloud2_<std::allocator<void> > >::filter(sensor_msgs::PointCloud2_<std::allocator<void> >&) ()
from /opt/ros/fuerte/lib/libpcl_filters.so.1.5
#6 0xad4963ea in pcl_ros::StatisticalOutlierRemoval::filter (this=0x80ca1a0,
input=..., indices=..., output=...)
at /tmp/buildd/ros-fuerte-perception-pcl-1.2.3/debian/ros-fuerte-perception-pcl/opt/ros/fuerte/stacks/perception_pcl/pcl_ros/include/pcl_ros/filters/statistical_outlier_removal.h:79
#7 0xad410c40 in pcl_ros::Filter::computePublish (this=0x80ca1a0, input=...,
indices=...)
at /tmp/buildd/ros-fuerte-perception-pcl-1.2.3/debian/ros-fuerte-perception-pcl/opt/ros/fuerte/stacks/perception_pcl/pcl_ros/src/pcl_ros/filters/filter.cpp:68
#8 0xad411a7a in pcl_ros::Filter::input_indices_callback (this=0x80ca1a0,
cloud=..., indices=...)
at /tmp/buildd/ros-fuerte-perception-pcl-1.2.3/debian/ros-fuerte-perception-pcl/opt/ros/fuerte/stacks/perception_pcl/pcl_ros/src/pcl_ros/filters/filter.cpp:229
#9 0xad413fb3 in operator() (a2=..., p=<optimized out>, this=<optimized out>,
a1=...) at /usr/include/boost/bind/mem_fn_template.hpp:280
#10 operator()<boost::_mfi::mf2<void, pcl_ros::Filter, const boost::shared_ptr<const sensor_msgs::PointCloud2_<std::allocator<void> > >&, const boost::shared_ptr<const pcl::PointIndices_<std::allocator<void> > >&>, boost::_bi::list1<const boost::shared_ptr<const sensor_msgs::PointCloud2_<std::allocator<void> > >&> > (
a=<synthetic ...
Can you provide a backtrace?
How would I get this? stdout, even with output="screen" on all nodes, shows only the roslaunch notification of a dead process.
Run the launch file with the gdb: http://www.ros.org/wiki/roslaunch/Tutorials/Roslaunch%20Nodes%20in%20Valgrind%20or%20GDB.
Added. It's crashing in the pcl Outlier filter itself.
Sorry for a late reply. If you have not been able to resolve the issue, can you please send me a link to the bag file and tell me which version of Ubuntu/ROS/PCL are you using? D.
Here is the file: http://dl.dropbox.com/u/15500942/cloud_crash.bag
I am using Fuerte on Ubuntu 12.04 and the default install of PCL (1.5). I wasn't able to try 1.6 since the unstable pcl_ros package doesn't include the nodelets. I vaguely remember seeing some crash fixes for KDTree in the 1.6 changelists so maybe this is a non-issue after upgrading