Weird behavior with PointCloudConcatenateFieldsSynchronizer
Using the pcl_ros nodelets, I take my initial PC2, downsample, filter, and compute normals from it. I relay the PC that my normals are computed from into the same topic as my normals output, and then try to use PointCloudConcatenateFieldsSynchronizer to concatenate the fields. Even though my rate is ~15 Hz, the output of this function is minutes.
Anyone know what's up?
One more question, how do I actually see the <rosparams> that can be set for this nodelet?
Thank you!
Toby
http://docs.ros.org/api/pcl_ros/html/...
full launch file:
<launch>
<node pkg="nodelet" type="nodelet" name="pcl_manager" args="manager" output="screen" ns="wall" />
<!-- Run VoxelGrid Filter -->
<node pkg="nodelet" type="nodelet" name="voxelGridFilter" args="load pcl/VoxelGrid pcl_manager" output="screen" ns="wall">
<remap from="~input" to="/camera/depth/points" />
<rosparam>
filter_limit_max: 3.0
leaf_size: 0.02
</rosparam>
</node>
<!-- Run Radius Filter -->
<node pkg="nodelet" type="nodelet" name="radiusOutlierRemoval" args="load pcl/RadiusOutlierRemoval pcl_manager" output="screen" ns="wall" >
<remap from="~input" to="/wall/voxelGridFilter/output" />
<rosparam>
min_neighbors: 3
radius_search: 0.021
</rosparam>
</node>
<!-- Run Statistical Outlier Removal -->
<node pkg="nodelet" type="nodelet" name="statisticalOutlierRemoval" args="load pcl/StatisticalOutlierRemoval pcl_manager" output="screen" ns="wall" >
<remap from="~input" to="/wall/voxelGridFilter/output" />
<rosparam>
mean_k: 100
stddev: 1.0
</rosparam>
</node>
<!-- relay XYZ data to normalEstimator Output -->
<node pkg="topic_tools" type="relay" name="xyzRelay" args="/wall/statisticalOutlierRemoval/output /wall/normalEstimator/output" output="screen" ns="wall" />
<!-- Run Normal Estimator -->
<node pkg="nodelet" type="nodelet" name="normalEstimator" args="load pcl/NormalEstimation pcl_manager" output="screen" ns="wall">
<remap from="~input" to="/wall/statisticalOutlierRemoval/output" />
<rosparam>
k_search: 5
radius_search: 0.0
spatial_locator: 1 #FLANN
</rosparam>
</node>
<!-- Concatenate Normal & XYZ Fields -->
<node pkg="nodelet" type="nodelet" name="pointCloudConcatenateFieldsSynchronizer" args="load pcl/PointCloudConcatenateFieldsSynchronizer pcl_manager" output="screen" ns="wall">
<remap from="~input" to="/wall/normalEstimator/output" />
</node>
</launch>